====== Example for Making your EEROS Application a ROS Node ====== Back to [[getting_started:ros|]]. ===== Working with ROS1 ===== The CMake file for the EEROS application using ROS1 has to be expanded as follows: cmake_minimum_required(VERSION 3.10) project(testProject) set(CMAKE_CXX_STANDARD 14) ## ROS message(STATUS "looking for package 'ROS'") find_package( roslib REQUIRED ) if (roslib_FOUND) message( STATUS "-> ROS found") add_definitions(-DROS_FOUND) include_directories( "${roslib_INCLUDE_DIRS}" ) message( STATUS "roslib_INCLUDE_DIRS: " ${roslib_INCLUDE_DIRS} ) list(APPEND ROS_LIBRARIES "${roslib_LIBRARIES}") find_package( rosconsole REQUIRED) list(APPEND ROS_LIBRARIES "${rosconsole_LIBRARIES}") find_package( roscpp REQUIRED ) list(APPEND ROS_LIBRARIES "${roscpp_LIBRARIES}") add_definitions(-DUSE_ROS) else() message( STATUS "-> ROS NOT found") endif() find_package(EEROS REQUIRED) add_executable(testProject main.cpp) target_link_libraries(testProject PRIVATE eeros ${ROS_LIBRARIES}) Your test program might look like #include #include #include int main(int argc, char **argv) { ... eeros::control::rosTools::initNode("eerosNode"); // initialize the ROS node in your main function and give it a name. log.info() << "ROS node initialized."; signal(SIGINT, ...); ... All ROS tools such as ''rqt'' will list your EEROS application under the name ''eerosNode''. \\ If you want to register a signal handler, e.g. for shutting down a system (see [[getting_started:practical_problems:abort|]]), you have to register it after the ROS node is initialized. The ROS node will properly shut down as soon as the last node handler is destroyed when going out of scope. ===== Working with ROS2 ===== The CMake file for the EEROS application using ROS2 has to be expanded as follows: cmake_minimum_required(VERSION 3.10) project(testProject) set(CMAKE_CXX_STANDARD 14) ## ROS message(STATUS "looking for package 'ROS2'") find_package(rclcpp REQUIRED) if (rclcpp_FOUND) message(STATUS "-> ROS2 found") add_definitions(-DROS2_FOUND) include_directories( "${rclcpp_INCLUDE_DIRS}") message(STATUS "rclcpp_INCLUDE_DIRS: " ${rclcpp_INCLUDE_DIRS}) list(APPEND ROS_LIBRARIES "${rclcpp_LIBRARIES}") find_package(rosconsole QUIET) list(APPEND ROS_LIBRARIES "${rosconsole_LIBRARIES}") add_definitions(-DUSE_ROS2) else() message( STATUS "-> ROS2 NOT found") endif() find_package(EEROS REQUIRED) add_executable(testProject main.cpp) target_link_libraries(testProject PRIVATE eeros ${EEROS_LIBS} ${ROS_LIBRARIES}) Your test program might look like #include #include #include int main(int argc, char **argv) { ... auto node = eeros::control::rosTools::initNode("eerosNode"); // initialize the ROS node in your main function and give it a name. if (node != nullptr) log.info() << "ROS node initialized: " << node->get_name(); signal(SIGINT, ...); ... ControlSystem cs(node, dt); ... When defining a control system which uses ROS subscriber or publisher blocks, you have to pass this node to them. All ROS tools such as ''rqt'' will list your EEROS application under the name ''eerosNode''. The variable ''node'' has to be passed to all blocks in the control system which publish or subscribe to ROS messages.\\ If you want to register a signal handler, e.g. for shutting down a system (see [[getting_started:practical_problems:abort|]]), you have to register it after the ROS node is initialized. The ROS node will properly shut down as soon as the last node handler is destroyed when going out of scope.