
Ros2 容器操作源代码C++详细教程(将多线程放到一个进程内运行)
Ros2 容器操作源代码C++详细教程(将多线程放到一个进程内运行)Talker + Listener
·
之前想做一个容器来实现图像传输,遍观网上教程没有把步骤讲清楚的,我这里把源码的 Talker 和 Listener 单独拿出来放到一个容器内运行,详细讲解步骤。
可拷贝下来自己跑跑,环境为ubuntu + vscode + ros2
操作步骤包括:
1.头文件
2.cpp文件
3.cmake编写
4.xml 文件
5.launch文件
1.头文件
主要是文件开头的宏定义,防止重复定义。
#ifndef COMPOSITION__TALKER_COMPONENT_HPP_
#define COMPOSITION__TALKER_COMPONENT_HPP_
//放头文件
//#include "rclcpp/rclcpp.hpp"
//#include "std_msgs/msg/string.hpp"
//#include <chrono>
//#include <iostream>
//#include <memory>
//#include <utility>
namespace composition
{
class Talker : public rclcpp::Node
{
public:
//暂不知此宏定义的含义,猜测跟options有关
// COMPOSITION_PUBLIC
explicit Talker(const rclcpp::NodeOptions & options);
protected:
void on_timer();
private:
size_t count_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr pub_;
rclcpp::TimerBase::SharedPtr timer_;
};
} // namespace composition
#endif // COMPOSITION__TALKER_COMPONENT_HPP_
2.cpp文件
cpp文件不能有main函数,把你的操作步骤都写到构造函数之中,主要改变是需要在文件末尾进行注册。
#include "composition_test/talker_component.hpp"
using namespace std::chrono_literals;
namespace composition
{
Talker::Talker(const rclcpp::NodeOptions & options)
: Node("talker", options), count_(0)
{
// Create a publisher of "std_mgs/String" messages on the "chatter" topic.
pub_ = create_publisher<std_msgs::msg::String>("chatter", 10);
// Use a timer to schedule periodic message publishing.
timer_ = create_wall_timer(1s, std::bind(&Talker::on_timer, this));
}
void Talker::on_timer()
{
auto msg = std::make_unique<std_msgs::msg::String>();
msg->data = "Hello World: " + std::to_string(++count_);
RCLCPP_INFO(this->get_logger(), "Publishing: '%s'", msg->data.c_str());
std::flush(std::cout);
// Put the message into a queue to be processed by the middleware.
// This call is non-blocking.
pub_->publish(std::move(msg));
}
} // namespace composition
#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(composition::Talker)
3.cmake
1.首先要加依赖,容器的依赖为 find_package(rclcpp_components REQUIRED)
2.添加自己写的头文件 include_directories(include)
3.将构件编译为动态链接库使得其他文件能够调用。
add_library(
talker_component SHARED
src/talker_component.cpp
)
4.把依赖添加到构件上
ament_target_dependencies(
talker_component
"rclcpp"
"rclcpp_components"
)
5.把构件放到自己的install目录下,这样运行的时候才找得到
install(TARGETS
talker_component
listener_component
ARCHIVE DESTINATION lib
LIBRARY DESTINATION lib
RUNTIME DESTINATION bin)
6.注册自己的构件
rclcpp_components_register_nodes(talker_component "composition::Talker")
rclcpp_components_register_nodes(listener_component "composition::Listener")
4. xml文件
添加一个<depend>rclcpp_components</depend>即可。
5.launch文件
在文件中可以手动调用容器,向其中加入构件实现一键启动。
import launch
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
container = ComposableNodeContainer(
#容器直接用ros2自带的容器即可
name='my_container',
namespace='',
package='rclcpp_components',
executable='component_container',
#向容器加入各个构件
composable_node_descriptions=[
ComposableNode(
package='ros2_usbcapture',
plugin='wmj::camera_node',
name='talker',
#各个构建要求参数options,所以可以在这里直接定义参数,比如这里的开启的intra_process
extra_arguments=[{'use_intra_process_comms': True}]
),
ComposableNode(
package='ros2_usbcapture',
plugin='wmj::Image_get_test',
name='listener',
extra_arguments=[{'use_intra_process_comms': True}]
)
],
output='screen',
)
return launch.LaunchDescription([container])
更多推荐
所有评论(0)