ROS2로 간단한 실습을 진행하던 중 하나의 pkg에 python node와 C++ node를 같이 포함시킬 수 있는지 자료를 찾아보았다.
ROS1은 cmake를 사용한 build를 사용하였다. 하지만 ROS2로 넘어오면서 python은 ament_python으로, C++은 ament_cmake로 build 방식이 변경되었다.
python을 ament_python으로 build하면서 setup.py, setup.cfg와 같은 파일을 수정해서 build를 진행해야 했고 이 방식은 ROS1에서 사용하지 않았던 방식이므로 python과 C++로 작성한 node가 하나의 pkg에 사용되기 위해서는 다른 방식이 필요할 것으로 예측하였다.
구글에서 자료를 찾던 와중 친절한 튜토리얼 사이트를 찾을 수 있었다.
https://roboticsbackend.com/ros2-package-for-both-python-and-cpp-nodes/
해당 사이트를 참고하여 실습을 진행하였다.
테스트를 진행하기 위한 pkg를 생성한다.
$ cd ~/robot_ws/src
$ ros2 pkg create my_cpp_py_pkg --build-type ament_cmake --dependencies rclcpp rclpy std_msgs
--build-type를 ament_cmake로 사용해준다.
Node 파일은 src 폴더 안에 작성해주면 된다. 실습을 위해 talker_cpp.cpp 코드를 추가하였다.
#include <chrono>
#include <functional>
#include <memory>
#include <string>
#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"
using namespace std::chrono_literals;
class HelloworldPublisher : public rclcpp::Node
{
public:
HelloworldPublisher()
: Node("talker"), count_(0)
{
auto qos_profile = rclcpp::QoS(rclcpp::KeepLast(10));
helloworld_publisher_ = this->create_publisher<std_msgs::msg::String>(
"chatter", qos_profile);
timer_ = this->create_wall_timer(
1s, std::bind(&HelloworldPublisher::publish_helloworld_msg, this));
}
private:
void publish_helloworld_msg()
{
auto msg = std_msgs::msg::String();
msg.data = "Hello World: " + std::to_string(count_++);
RCLCPP_INFO(this->get_logger(), "Published message: '%s'", msg.data.c_str());
helloworld_publisher_->publish(msg);
}
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr helloworld_publisher_;
size_t count_;
};
int main(int argc, char * argv[])
{
rclcpp::init(argc, argv);
auto node = std::make_shared<HelloworldPublisher>();
rclcpp::spin(node);
rclcpp::shutdown();
return 0;
}
실습을 진행할 때는 header를 추가하지 않았다.
만약 코드를 작성할 때 C++의 hpp 파일을 추가해야한다면 include 파일 내부 my_cpp_py_pkg 폴더 안에 hpp 파일을 넣어준다.
추가한 hpp파일을 C++ 파일에 include 시키기 위해서는 다음과 같이 작성하면 된다.
#include "my_cpp_py_pkg/cpp_header.hpp"
python node를 작성하기 전에 pkg이름과 동일한 폴더를 하나 만들고 그 안에 __init.py 파일을 추가한다. __init.py 파일은 내용을 비운 상태로 유지한다.
$ cd ~/robot_ws/src/my_cpp_py_pkg
$ mkdir my_cpp_py_pkg
$ cd my_cpp_py_pkg
$ gedit __init__.py # 본인이 자주 사용하는 편집기를 사용하여 파일 생성 후 저장
__init__.py를 생성한 이후 pkg 폴더로 돌아가서 scripts 폴더를 생성하고 그 안에 listener_py.py 코드를 작성하였다.
$ cd ~/robot_ws/src/my_cpp_py_pkg
$ mkdir scripts
$ cd scripts
$ code listener_py.py
#!/usr/bin/env python3
import rclpy
from rclpy.node import Node
from rclpy.qos import QoSProfile
from std_msgs.msg import String
class HelloworldSubscriber(Node):
def __init__(self):
super().__init__('listener')
qos_profile = QoSProfile(depth=10)
self.helloworld_subscriber = self.create_subscription(
String,
'chatter',
self.subscribe_topic_message,
qos_profile)
def subscribe_topic_message(self, msg):
self.get_logger().info('Received message: {0}'.format(msg.data))
def main(args=None):
rclpy.init(args=args)
node = HelloworldSubscriber()
try:
rclpy.spin(node)
except KeyboardInterrupt:
node.get_logger().info('Keyboard Interrupt (SIGINT)')
finally:
node.destroy_node()
rclpy.shutdown()
if __name__ == '__main__':
main()
python node를 작성할 때 맨 윗줄에 #!/usr/bin/env python3를 빼먹으면 안된다.
또한 작성한 node의 권한을 변경해줘야 한다.
$ chmod +x listener_py.py
만약 python module 파일을 추가하기 위해서는 my_cpp_py_pkg 폴더 안에 추가하면 된다.
작성을 완료한 폴더 구조는 다음과 같다.
.
├── CMakeLists.txt
├── include
│ └── my_cpp_py_pkg
├── my_cpp_py_pkg
│ └── __init__.py
├── package.xml
├── scripts
│ └── listener_py.py
└── src
└── talker_cpp.cpp
header 파일과 module 파일을 추가하지 않았기 때문에 위와 같은 결과가 나온다.
scripts의 listener_py.py의 권한을 변경하는 것을 잊지말고 다음 단계를 진행한다.
package.xml 파일을 수정해준다.
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_python</buildtool_depend>
python파일을 cmake를 통해 build 해야하므로 ament_cmake_python을 추가하는 작업이 필요하다.
실습에 사용한 package.xml의 전체는 아래와 같다.
<?xml version="1.0"?>
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
<package format="3">
<name>my_cpp_py_pkg</name>
<version>0.0.0</version>
<description>TODO: Package description</description>
<maintainer email="junwoo@todo.todo">junwoo</maintainer>
<license>TODO: License declaration</license>
<buildtool_depend>ament_cmake</buildtool_depend>
<buildtool_depend>ament_cmake_python</buildtool_depend>
<depend>rclcpp</depend>
<depend>rclpy</depend>
<depend>std_msgs</depend>
<test_depend>ament_lint_auto</test_depend>
<test_depend>ament_lint_common</test_depend>
<export>
<build_type>ament_cmake</build_type>
</export>
</package>
CMakeLists를 다음과 같이 수정한다.
cmake_minimum_required(VERSION 3.5)
project(my_cpp_py_pkg)
# Default to C99
if(NOT CMAKE_C_STANDARD)
set(CMAKE_C_STANDARD 99)
endif()
# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
endif()
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(rclpy REQUIRED)
find_package(std_msgs REQUIRED)
find_package(ament_cmake_python REQUIRED)
# include cpp "include" directory
# include_directories(include)
# create cpp executable
add_executable(talker src/talker_cpp.cpp)
ament_target_dependencies(talker rclcpp std_msgs)
# install cpp executable
install(TARGETS
talker
DESTINATION lib/${PROJECT_NAME}
)
# install python modules
# ament_python_install_package(${PROJECT_NAME})
# install python executables
install(PROGRAMS
scripts/listener_py.py
DESTINATION lib/${PROJECT_NAME}
)
if(BUILD_TESTING)
find_package(ament_lint_auto REQUIRED)
# the following line skips the linter which checks for copyrights
# uncomment the line when a copyright and license is not present in all source files
#set(ament_cmake_copyright_FOUND TRUE)
# the following line skips cpplint (only works in a git repo)
# uncomment the line when this package is not in a git repo
#set(ament_cmake_cpplint_FOUND TRUE)
ament_lint_auto_find_test_dependencies()
endif()
ament_package()
find dependencies 부분에서 사용할 dependencies를 확인한다.
이때 ament_cmake_python을 추가해줘야한다.
C++ node 파일은 크게 다를 것 없이 추가해주면 된다.
python node 파일을 install 해주는 부분을 추가한다.
실습에서 header와 module을 사용하지 않았기 때문에 나중에 내가 참고하기 편하도록 주석처리하였다.
이후 colcon build를 진행한다.
$ cd ~/robot_ws
$ colcon build --package-select my_cpp_py_pkg
터미널 2개를 열고 노드가 동작하는 것을 확인한다.
$ ros2 run my_cpp_py_pkg talker
$ ros2 run my_cpp_py_pkg listener
rqt_graph로 확인한 그래프는 다음과 같다.