ROS2 launch文件与参数设置
在ros2创建的C++语言的package中,通过launch文件启动多个节点,并从yaml文件中读取订阅的topic名称。
项目架构
working_space/
|
└───build/
|
└───install/
|
└───log/
|
└───src/
└───package_1/
| |
| └───config/
| | └───***.rviz
| | └───***.yaml
| |
| └───include/
| |
| └───package_1/
| | └───***.h
| | └───***.hpp
| |
| └───launch/
| | └───***.launch.py
| |
| └───src/
| | └───***.cpp
| | └───***.cpp
| |
| └───CMakeLists.txt
| └───package.xml
|
└───package_2/
|
└───package_3/
launch文件编写
from ament_index_python.packages import get_package_share_directory
import launch
import launch.actions
import launch.substitutions
import launch_ros.actions
import os.path
def generate_launch_description():
rviz_config_dir = os.path.join(get_package_share_directory('sensor_fusion'), 'config', 'fusion.rviz')
para_dir = os.path.join(get_package_share_directory('sensor_fusion'), 'config', 'sensor_fusion_subscribed_topic.yaml')
return launch.LaunchDescription([
launch.actions.DeclareLaunchArgument(
'node_prefix',
# if launch file's prefix is "_lanuch.py", change '.' into '_'
default_value=[launch.substitutions.EnvironmentVariable('USER'), '.'],
description='Prefix for node names'
),
launch_ros.actions.Node(
package='rviz2',
node_namespace='rviz2',
node_executable='rviz2',
arguments=['-d', rviz_config_dir]
),
launch_ros.actions.Node(
package='kitti_pub',
node_namespace='kitti_pub',
node_executable='kitti_pub',
output='screen'
),
launch_ros.actions.Node(
package='sensor_fusion',
node_namespace='sensor_fusion',
node_executable='sensor_fusion',
parameters=[para_dir],
output='screen'
)
])
yaml文件编写
# namespace
sensor_fusion:
# node_name
sensor_fusion:
# parameters
ros__parameters:
# topic's name will be namespace setted in the launch file plus original publisher topic.
point_cloud_topic: "/kitti_pub/kitti_points"
image_topic: "/kitti_pub/kitti_cam02"
detect_box2d_topic: "/kitti_pub/yolo_det"
CMakeLists.txt文件修改
ament_package() 前面加上以下内容,才能在share文件夹中找到launch文件和config文件。
install(DIRECTORY
launch
DESTINATION share/${PROJECT_NAME}/
)
install(DIRECTORY
config
DESTINATION share/${PROJECT_NAME}/
)
源文件内读取yaml文件参数并初始化subscriber
// Same type with the parameters in yaml to read the params
string point_cloud_topic, image_topic, detect_box2d_topic;
// Declare and get parameters from yaml or use alternative parameters
this->declare_parameter<string>("point_cloud_topic", "/kitti_pub/kitti_points");
this->declare_parameter<string>("image_topic", "/kitti_pub/kitti_cam02");
this->declare_parameter<string>("detect_box2d_topic", "/kitti_pub/yolo_det");
this->get_parameter_or<string>("point_cloud_topic", point_cloud_topic, "/kitti_pub/kitti_points");
this->get_parameter_or<string>("image_topic", image_topic, "/kitti_pub/kitti_cam02");
this->get_parameter_or<string>("detect_box2d_topic", detect_box2d_topic, "/kitti_pub/yolo_det");
// Declare subscribers
message_filters::Subscriber<sensor_msgs::msg::PointCloud2> pcl_sub;
message_filters::Subscriber<sensor_msgs::msg::Image> img_sub;
message_filters::Subscriber<darknet_ros_msgs::msg::BoundingBoxes> det_sub;
// Initialize subscribers
pcl_sub.subscribe(this, point_cloud_topic);
img_sub.subscribe(this, image_topic);
det_sub.subscribe(this, detect_box2d_topic);
参考链接:
https://docs.ros.org/en/dashing/Tutorials/Launch-Files/Creating-Launch-Files.html
https://docs.ros.org/en/dashing/Tutorials/Launch-system.html
https://blog.csdn.net/qq_33399315/article/details/106863743?spm=1001.2014.3001.5501