Study/[ROS2] ROS2 Basic

ROS2 with C++ - Node composition

soohwan_justin 2023. 7. 30. 23:11

본 포스트는 ROS1에 대한 전반적인 내용 및 ROS2 Python에 대한 지식이 있다는 가정 하에 작성되었으며, The Construct Youtube 영상을 참고하였습니다.

또한, 시뮬레이션 환경은 turtlebot3 waffle_pi를 사용합니다 : https://github.com/ROBOTIS-GIT/turtlebot3_simulations

 

 

 

ROS 프로그램(nodes)은 바로 실행하거나, launch 파일로 실행할 수 있게 실행 파일로 컴파일 됩니다. 하지만 각 실행 파일은 하나의 프로세스만 실행합니다. 이 말은, 단일 프로세스에서 ROS node는 하나 이상 실행할 수 없다는 것인데... ROS2에서는 components라는 방법을 사용하면 가능합니다.

 

components는 ROS1의 nodelets에 대응됩니다. 어떤 코드를 component로서 짜면, 이를 실행 파일 대신에 공유 라이브러리로 빌드할 수 있으며, 이는 하나의 프로세스에 여러 개의 components를 불러올 수 있게 해줍니다.

 

 

 

1. component 만들기

1. 다음 명령으로 패키지를 만듭니다.

$ ros2 pkg create my_components --build-type ament_cmake --dependencies rclcpp rclcpp_components composition geometry_msgs

 

2. hpp파일 만들기

my_components/include/my_components 디렉토리에 moverobot_components.hpp 파일을 만듭니다.

my_components/include/my_components/moverobot_components.hpp

#ifndef COMPOSITION__MOVEROBOT_COMPONENT_HPP_
#define COMPOSITION__MOVEROBOT_COMPONENT_HPP_

#include "my_components/visibility_control.h"
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"

namespace my_components
{

class MoveRobot : public rclcpp::Node
{
public:
  COMPOSITION_PUBLIC
  explicit MoveRobot(const rclcpp::NodeOptions & options);

protected:
  void on_timer();

private:
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_;
  rclcpp::TimerBase::SharedPtr timer_;
};

}  // namespace composition

#endif  // COMPOSITION__MOVEROBOT_COMPONENT_HPP_

 

 

3. 다음으로, 위의 hpp파일을 정의하기 위한 cpp 파일을 만듭니다. src 디렉토리에 moverobot_component.cpp를 만듭니다.

my_components/src/moverobot_component.cpp

#ifndef COMPOSITION__MOVEROBOT_COMPONENT_HPP_
#define COMPOSITION__MOVEROBOT_COMPONENT_HPP_

#include "my_components/visibility_control.h"
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"

namespace my_components
{

class MoveRobot : public rclcpp::Node
{
public:
  COMPOSITION_PUBLIC
  explicit MoveRobot(const rclcpp::NodeOptions & options);

protected:
  void on_timer();

private:
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_;
  rclcpp::TimerBase::SharedPtr timer_;
};

}  // namespace composition

#endif  // COMPOSITION__MOVEROBOT_COMPONENT_HPP_

 

4. 다시 include/my_components 디렉토리에 visibility_control.h 파일을 만듭니다.

my_components/include/my_components/visibility_control.h

// Copyright 2016 Open Source Robotics Foundation, Inc.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
//     http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.

#ifndef COMPOSITION__VISIBILITY_CONTROL_H_
#define COMPOSITION__VISIBILITY_CONTROL_H_

#ifdef __cplusplus
extern "C"
{
#endif

// This logic was borrowed (then namespaced) from the examples on the gcc wiki:
//     https://gcc.gnu.org/wiki/Visibility

#if defined _WIN32 || defined __CYGWIN__
  #ifdef __GNUC__
    #define COMPOSITION_EXPORT __attribute__ ((dllexport))
    #define COMPOSITION_IMPORT __attribute__ ((dllimport))
  #else
    #define COMPOSITION_EXPORT __declspec(dllexport)
    #define COMPOSITION_IMPORT __declspec(dllimport)
  #endif
  #ifdef COMPOSITION_BUILDING_DLL
    #define COMPOSITION_PUBLIC COMPOSITION_EXPORT
  #else
    #define COMPOSITION_PUBLIC COMPOSITION_IMPORT
  #endif
  #define COMPOSITION_PUBLIC_TYPE COMPOSITION_PUBLIC
  #define COMPOSITION_LOCAL
#else
  #define COMPOSITION_EXPORT __attribute__ ((visibility("default")))
  #define COMPOSITION_IMPORT
  #if __GNUC__ >= 4
    #define COMPOSITION_PUBLIC __attribute__ ((visibility("default")))
    #define COMPOSITION_LOCAL  __attribute__ ((visibility("hidden")))
  #else
    #define COMPOSITION_PUBLIC
    #define COMPOSITION_LOCAL
  #endif
  #define COMPOSITION_PUBLIC_TYPE
#endif

#ifdef __cplusplus
}
#endif

#endif  // COMPOSITION__VISIBILITY_CONTROL_H_

간단히 말해서, 이 코드는 공유 라이브러리를 불러오는 처리 과정을 최적화 해줍니다. 자세한 내용은 https://gcc.gnu.org/wiki/Visibility 를 참조하세요.

 

 

5. CMakeLists.txt파일을 수정합니다

cmake_minimum_required(VERSION 3.8)
project(my_components)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(composition REQUIRED)
find_package(geometry_msgs REQUIRED)

include_directories(include)

add_library(moverobot_component SHARED src/moverobot_component.cpp)
target_compile_definitions(moverobot_component PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(moverobot_component
  "rclcpp"
  "rclcpp_components"
  "geometry_msgs")
rclcpp_components_register_nodes(moverobot_component "my_components::MoveRobot")
set(node_plugins "${node_plugins}my_components::MoveRobot;$<TARGET_FILE:moverobot_component>\n")

install(TARGETS
  moverobot_component
  ARCHIVE DESTINATION lib
  LIBRARY DESTINATION lib
  RUNTIME DESTINATION bin)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

 

 

위 CMakeLists.txt파일에 대해 추가 설명을 하자면...

 

add_library(moverobot_component SHARED src/moverobot_component.cpp)

C++ script로부터 공유 라이브러리를 만듭니다.

 

rclcpp_components_register_nodes(moverobot_component "my_components::MoveRobot")
set(node_plugins "${node_plugins}my_components::MoveRobot;$<TARGET_FILE:moverobot_component>\n")

아까 만들었던 component를 등록합니다.

 

install(TARGETS
  moverobot_component
  ARCHIVE DESTINATION lib
  LIBRARY DESTINATION lib
  RUNTIME DESTINATION bin)

위의 내용들을 workspace에 설치합니다.

 

 

6. 빌드해보고, source 후 아래 명령으로 확인해봅니다.

$ ros2 component types

 

7. 위 component를 불러오기 위해서는 component container가 필요합니다. 아래 명령으로 실행합니다.

$ ros2 run rclcpp_components component_container

 

아래 명령으로 확인해봅니다.

$ ros2 component list

 

아래 명령으로 우리가 만든 component를 불러올 수 있습니다.

$ ros2 component load /ComponentManager <pkg_name> <component_name>

 

즉, 우리가 사용할 명령은

$ ros2 component load /ComponentManager my_components my_components::MoveRobot

 

 

다시 아래 명령을 입력해보면, /moverobot component가 1번으로 할당된 것을 확인할 수 있습니다.

$ ros2 component list

 

 

다음 명령으로 unload할 수 있습니다.

$ ros2 component unload /ComponentManager <component_id>

 

따라서,

$ ros2 component unload /ComponentManager <component_id>

 

8. 이번엔 launch 파일을 만들어보겠습니다.

moverobot_component.launch.py

import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
    """Generate launch description with multiple components."""
    container = ComposableNodeContainer(
            name='my_container',
            namespace='',
            package='rclcpp_components',
            executable='component_container',
            composable_node_descriptions=[
                ComposableNode(
                    package='my_components',
                    plugin='my_components::MoveRobot',
                    name='moverobot'),
            ],
            output='screen',
    )

    return launch.LaunchDescription([container])

 

9. CMakeLists.txt 파일에 아래 내용을 추가하고, 빌드하고, 실행해보면, 같은 결과를 얻을 수 있습니다.

# Install launch files.
install(DIRECTORY
  launch
  DESTINATION share/${PROJECT_NAME}
)

 

launch 파일로 실행한 경우, 따로 unload명령을 하지 않아도 launch 파일을 종료하면 자동으로 unload됩니다.

 

 

 

2. 2개의 Component 만들어보기

odometry를 subscribe하는 component를 만들어보고, 이전에 만들었던 component와 같이 실행해보겠습니다.

 

1. hpp 파일 만들기

readodom_component.hpp

#ifndef COMPOSITION__MOVEROBOT_COMPONENT_HPP_
#define COMPOSITION__MOVEROBOT_COMPONENT_HPP_

#include "my_components/visibility_control.h"
#include "rclcpp/rclcpp.hpp"
#include "geometry_msgs/msg/twist.hpp"

namespace my_components
{

class MoveRobot : public rclcpp::Node
{
public:
  COMPOSITION_PUBLIC
  explicit MoveRobot(const rclcpp::NodeOptions & options);

protected:
  void on_timer();

private:
  rclcpp::Publisher<geometry_msgs::msg::Twist>::SharedPtr pub_;
  rclcpp::TimerBase::SharedPtr timer_;
};

}  // namespace composition

#endif  // COMPOSITION__MOVEROBOT_COMPONENT_HPP_

 

 

2. cpp 파일 만들기

moverobot_component.cpp

#include "my_components/moverobot_component.hpp"

#include <chrono>
#include <iostream>
#include <memory>
#include <utility>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
#include "geometry_msgs/msg/twist.hpp"

using namespace std::chrono_literals;

namespace my_components
{
MoveRobot::MoveRobot(const rclcpp::NodeOptions & options)
: Node("moverobot", options)
{
  
  pub_ = create_publisher<geometry_msgs::msg::Twist>("cmd_vel", 10);

  timer_ = create_wall_timer(1s, std::bind(&MoveRobot::on_timer, this));
}

void MoveRobot::on_timer()
{
  auto msg = std::make_unique<geometry_msgs::msg::Twist>();
  msg->linear.x = 0.3;
  msg->angular.z = 0.3;
  std::flush(std::cout);

  pub_->publish(std::move(msg));
}

}

#include "rclcpp_components/register_node_macro.hpp"

RCLCPP_COMPONENTS_REGISTER_NODE(my_components::MoveRobot)

 

3. CMakeLists.txt 파일 수정

CMakeLists.txt

cmake_minimum_required(VERSION 3.8)
project(my_components)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(composition REQUIRED)
find_package(geometry_msgs REQUIRED)
find_package(nav_msgs REQUIRED)


include_directories(include)

add_library(moverobot_component SHARED src/moverobot_component.cpp)
target_compile_definitions(moverobot_component PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(moverobot_component
  "rclcpp"
  "rclcpp_components"
  "geometry_msgs")
rclcpp_components_register_nodes(moverobot_component "my_components::MoveRobot")
set(node_plugins "${node_plugins}my_components::MoveRobot;$<TARGET_FILE:moverobot_component>\n")

add_library(readodom_component SHARED src/readodom_component.cpp)
target_compile_definitions(readodom_component PRIVATE "COMPOSITION_BUILDING_DLL")
ament_target_dependencies(readodom_component
  "rclcpp"
  "rclcpp_components"
  "nav_msgs")
rclcpp_components_register_nodes(readodom_component "my_components::OdomSubscriber")
set(node_plugins "${node_plugins}my_components::OdomSubscriber;$<TARGET_FILE:readodom_component>\n")

install(TARGETS
  moverobot_component
  readodom_component
  ARCHIVE DESTINATION lib
  LIBRARY DESTINATION lib
  RUNTIME DESTINATION bin)

# Install launch files.
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}
)

if(BUILD_TESTING)
  find_package(ament_lint_auto REQUIRED)
  # the following line skips the linter which checks for copyrights
  # comment the line when a copyright and license is added to all source files
  set(ament_cmake_copyright_FOUND TRUE)
  # the following line skips cpplint (only works in a git repo)
  # comment the line when this package is in a git repo and when
  # a copyright and license is added to all source files
  set(ament_cmake_cpplint_FOUND TRUE)
  ament_lint_auto_find_test_dependencies()
endif()

ament_package()

 

 

4. package.xml 파일 수정

아래 태그만 추가해줍니다.

  <depend>nav_msgs</depend>

 

5. launch 파일 만들기

moverobot_component.launch.py

import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode


def generate_launch_description():
    """Generate launch description with multiple components."""
    container = ComposableNodeContainer(
            name='my_container',
            namespace='',
            package='rclcpp_components',
            executable='component_container',
            composable_node_descriptions=[
                ComposableNode(
                    package='my_components',
                    plugin='my_components::MoveRobot',
                    name='moverobot'),
            ],
            output='screen',
    )

    return launch.LaunchDescription([container])

 

6. 빌드 후, 실행

 

 

 

 

'Study > [ROS2] ROS2 Basic' 카테고리의 다른 글

ROS2 with C++ - Node Parameters  (0) 2023.08.03
ROS2 with C++ - Lifecycle Nodes  (0) 2023.08.02
ROS2 with C++ - Action  (0) 2023.07.30
ROS2 with C++ - Service  (0) 2023.07.30
ROS2 with C++ - Executors and Callbacks  (0) 2023.07.30