| /***************************************************************************** |
| * Copyright (c) 2020 CEA LIST. |
| * |
| * |
| * All rights reserved. This program and the accompanying materials |
| * are made available under the terms of the Eclipse Public License v2.0 |
| * which accompanies this distribution, and is available at |
| * https://www.eclipse.org/legal/epl-2.0/ |
| * |
| * Contributors: |
| * Ansgar Radermacher ansgar.radermacher@cea.fr |
| * |
| *****************************************************************************/ |
| |
| package org.eclipse.papyrus.robotics.ros2.codegen.cpp.component |
| |
| import org.eclipse.papyrus.designer.uml.tools.utils.ElementUtils |
| import org.eclipse.papyrus.designer.languages.cpp.profile.C_Cpp.Include |
| import org.eclipse.papyrus.designer.languages.cpp.profile.C_Cpp.ManualGeneration |
| import org.eclipse.papyrus.robotics.profile.robotics.functions.FunctionKind |
| import org.eclipse.papyrus.robotics.ros2.codegen.common.utils.RosHelpers |
| import org.eclipse.uml2.uml.Class |
| import org.eclipse.uml2.uml.Type |
| |
| import static extension org.eclipse.papyrus.robotics.codegen.common.utils.ActivityUtils.* |
| import static extension org.eclipse.papyrus.robotics.codegen.common.utils.ComponentUtils.getInstName |
| import static extension org.eclipse.papyrus.robotics.core.utils.FunctionUtils.getFunctions |
| import static extension org.eclipse.papyrus.robotics.core.utils.ParameterUtils.* |
| import static extension org.eclipse.papyrus.uml.tools.utils.StereotypeUtil.apply |
| import static extension org.eclipse.papyrus.uml.tools.utils.StereotypeUtil.applyApp |
| |
| class CreateMain { |
| /** |
| * register a ROS2 components |
| */ |
| def static registerComponent(Class component) ''' |
| #include "rclcpp_components/register_node_macro.hpp" |
| |
| // Register the component with class_loader. |
| // This acts as a sort of entry point, allowing the component to be discoverable when its library |
| // is being loaded into a running process. |
| RCLCPP_COMPONENTS_REGISTER_NODE(«component.qualifiedName») |
| ''' |
| |
| /** |
| * Create the main entry point for a class |
| */ |
| def static createMain(Class component) { |
| val main = component.nearestPackage.createOwnedClass(component.name + "_main", false); |
| component.createDependency(main) |
| main.apply(ManualGeneration) |
| val include = main.applyApp(Include); |
| include.body = component.createMainCode.toString |
| } |
| |
| def static lambdaStart(Class component) ''' |
| [«component.instName»](const rclcpp_lifecycle::State&) { |
| ''' |
| |
| def static lambdaEnd() ''' |
| return rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn::SUCCESS; |
| ''' |
| |
| def static createMainCode(Class component) ''' |
| «val instRef = component.instName + "->"» |
| «val onConfigure = component.onLifecycleEvent(instRef, FunctionKind.ON_CONFIGURE)» |
| «val onActivate = component.onActivate(instRef)» |
| «val onDeActivate = component.onQuitActive(instRef, FunctionKind.ON_DEACTIVATE)» |
| «val onShutdown = component.onQuitActive(instRef, FunctionKind.ON_SHUTDOWN)» |
| «val onCleanup = component.onLifecycleEvent(instRef, FunctionKind.ON_CLEANUP)» |
| «val compClassName = component.qualifiedName + component.postfix» |
| #include "«component.nearestPackage.name»/«component.name»«component.postfix».h" |
| |
| «IF component.hasPeriodicActivities» |
| using namespace std::chrono_literals; |
| «ENDIF» |
| «component.createTimer» |
| // declare options |
| rclcpp::NodeOptions «component.instName»_options; |
| |
| int main(int argc, char **argv) { |
| rclcpp::init(argc, argv); |
| |
| auto «component.instName» = std::make_shared<«compClassName»>(«component.instName»_options); |
| |
| RCLCPP_INFO(«instRef»get_logger(), "«component.name» has been initialized"); |
| |
| «IF onConfigure.length > 0» |
| «instRef»register_on_configure( |
| «component.lambdaStart» |
| «onConfigure» |
| «lambdaEnd» |
| } |
| ); |
| «ENDIF» |
| «IF onActivate.length > 0» |
| «instRef»register_on_activate( |
| «component.lambdaStart» |
| «onActivate» |
| «lambdaEnd» |
| } |
| ); |
| «ENDIF» |
| «IF onDeActivate.length > 0» |
| «instRef»register_on_deactivate( |
| «component.lambdaStart» |
| «onDeActivate» |
| «lambdaEnd» |
| } |
| ); |
| «ENDIF» |
| «IF onShutdown.length > 0» |
| «instRef»register_on_shutdown( |
| «component.lambdaStart» |
| «onShutdown» |
| «lambdaEnd» |
| } |
| ); |
| «ENDIF» |
| «IF onCleanup.length > 0» |
| «instRef»register_on_cleanup( |
| «component.lambdaStart» |
| «onCleanup» |
| «lambdaEnd» |
| } |
| ); |
| «ENDIF» |
| «IF component.allParameters.size > 0» |
| «instRef»declareParameters(); |
| «instRef»initParameterVars(); |
| «ENDIF» |
| |
| rclcpp::executors::MultiThreadedExecutor executor; |
| |
| executor.add_node(«instRef»get_node_base_interface()); |
| |
| executor.spin(); |
| rclcpp::shutdown(); |
| } |
| ''' |
| |
| def static void createTimer(Class component) { |
| for (activity : component.activities) { |
| val period = activity.period |
| if (period !== null) { |
| val timerBase = ElementUtils.getQualifiedElementFromRS(component, |
| "ros2Library::rclcpp::timer::TimerBase") as Type; |
| val timer = component.createOwnedAttribute('''timer_«activity.base_Class.name»_''', timerBase); |
| RosHelpers.useSharedPtr(timer) |
| } |
| } |
| } |
| |
| /** |
| * Create a function to call during the state transition towards a certain |
| * state. Calls the function with the passed "kind" |
| */ |
| def static onLifecycleEvent(Class component, String instRef, FunctionKind kind) ''' |
| «FOR activity : component.activities» |
| «val associatedFcts = activity.getFunctions(kind)» |
| «IF associatedFcts.size > 0» |
| «FOR associatedFct : associatedFcts» |
| «instRef»«associatedFct.name»(); |
| «ENDFOR» |
| «ENDIF» |
| «ENDFOR» |
| ''' |
| |
| /** |
| * Create a function to call during the state transition towards activation. |
| * In particular, call the functions with "kind" ON_ACTIVATE and start periodic timers |
| */ |
| def static onActivate(Class component, String instRef) ''' |
| «FOR activity : component.activities» |
| «val activityCl = activity.base_Class» |
| «val period = activity.period» |
| «val activateFcts = activity.getFunctions(FunctionKind.ON_ACTIVATE)» |
| «val periodicFcts = activity.getFunctions(FunctionKind.PERIODIC)» |
| «IF activateFcts.size > 0» |
| «FOR activateFct : activateFcts» |
| «instRef»«activateFct.name»(); |
| «ENDFOR» |
| «ENDIF» |
| «IF period !== null && periodicFcts.size > 0» |
| // periodic execution («period») for «activityCl.name» using a wall timer |
| «FOR periodicFct : periodicFcts» |
| «instRef»timer_«activityCl.name»_ = «instRef»create_wall_timer(«period», |
| std::bind(&«component.nearestPackage.name»::«component.name»«component.postfix»::«periodicFct.name», «component.instName»)); |
| «ENDFOR» |
| «ENDIF» |
| «ENDFOR» |
| ''' |
| |
| /** |
| * Create a function to call during the state transition leaving the active state (either shutdown or deactivate). |
| * In particular, call the functions with "kind" ON_DEACTIVATE and stop periodic timers |
| */ |
| def static onQuitActive(Class component, String instRef, FunctionKind kind) ''' |
| «FOR activity : component.activities» |
| «val activityCl = activity.base_Class» |
| «val period = activity.period» |
| «val associatedFcts = activity.getFunctions(kind)» |
| «val periodicFcts = activity.getFunctions(FunctionKind.PERIODIC)» |
| «IF (period !== null && periodicFcts.size > 0) || associatedFcts.size > 0» |
| «FOR activateFct : associatedFcts» |
| «instRef»«activateFct.name»(); |
| «ENDFOR» |
| «IF period !== null && periodicFcts.size > 0» |
| // stop timer of «activityCl.name» |
| «instRef»timer_«activityCl.name»_->cancel(); |
| «ENDIF» |
| «ENDIF» |
| «ENDFOR» |
| ''' |
| } |