1. 项目整体结构对比(左均为ROS2,右为ROS1)
根目录:可以看出来结构是类似的
config文件夹:添加了一个params.yaml文件,之前的yaml是通过roslaunch加载,ROS2的yaml后续会讲解
其他文件夹没有变化,就不一一列举了
2. CMakeLists.txt修改(上为ROS2,下为ROS1)
相比于ROS1,ROS2最主要的变化体现在CMakeLists.txt上,下面将对比ROS2与ROS1在这部分的区别
cmake_minimum_required(VERSION 3.5)
project(bitcq_camera)
set(CMAKE_CXX_STANDARD 17)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -fPIC -Wall -g -Wno-sign-compare -pthread")
set(CMAKE_EXE_LINKER_FLAGS "${CMAKE_EXE_LINKER_FLAGS} -Wl,-rpath,'$ORIGIN/'" )
set(CMAKE_SHARED_LINKER_FLAGS "${CMAKE_SHARED_LINKER_FLAGS} -Wl,-rpath,'$ORIGIN/'" )
set(LIBRARY_OUTPUT_PATH "${PROJECT_BINARY_DIR}")
set(EXECUTABLE_OUTPUT_PATH "${PROJECT_BINARY_DIR}")
cmake_minimum_required(VERSION 3.0.2)
project(bitcq_camera)
set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} -std=c++17 -fPIC -Wall -g -Wno-sign-compare -pthread")
首先是cmake_minimum_required的版本,ROS2强制要求CMake版本在3.5以上,所以这里需要修改
其次是CMAKE_CXX_STANDARD, ROS2强制要求C++版本为C++14以上,这里选择C++17是为了使用新特性
然后是CMAKE_EXE_LINKER_FLAGS CMAKE_SHARED_LINKER_FLAGS 这两个参数,是用于设置输出的程序与.so处于同一文件夹下,可以寻找到动态路径下的.so文件,使用该命令是由于ROS2特殊的编译机制,下面将详细解释
同理,下面设置LIBRARY_OUTPUT_PATH EXECUTABLE_OUTPUT_PATH 也是因为ROS2的编译机制问题
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rosidl_default_generators REQUIRED)
find_package(std_msgs REQUIRED)
find_package(message_filters REQUIRED)
find_package(sensor_msgs REQUIRED)
find_package(image_transport REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(catkin REQUIRED COMPONENTS
roscpp
std_msgs
image_transport
cv_bridge
sensor_msgs
)
可以看出来,ROS2使用ament_cmake 代替了catkin_make, 并且roscpp 也替换为了rclcpp, 其他包差异不大
set(msg_files
"msg/Detector2D.msg"
"msg/Detector2DArray.msg"
"msg/BoundingBox2D.msg"
"msg/BoundingBox.msg"
"msg/BoundingBoxes.msg"
"msg/ObjectHypothesis.msg"
)
rosidl_generate_interfaces(${PROJECT_NAME}_Message
${msg_files}
DEPENDENCIES std_msgs geometry_msgs
LIBRARY_NAME ${PROJECT_NAME}
)
ament_register_extension(
"rosidl_generate_interfaces"
"rosidl_generator_cpp"
"rosidl_generator_cpp_generate_interfaces.cmake"
)
ament_export_dependencies(rosidl_default_runtime)
add_message_files(
FILES
Detector2D.msg
Detector2DArray.msg
BoundingBox2D.msg
BoundingBox.msg
BoundingBoxes.msg
ObjectHypothesis.msg
)
generate_messages(DEPENDENCIES std_msgs vision_msgs)
这里使用了之前find_package 获取到的rosidl_generate_interfaces来进行消息的生成,相比于ROS1,ROS2这里消息需要添加参数 LIBRARY_NAME ${PROJECT_NAME},这样才能在cpp中正常获取需要的消息,这是由于ROS2
的消息生成为.so文件并且放置到install文件夹下,否则会在后面生成带_Message的消息,会无法正确链接源程序。
add_library(${PROJECT_NAME} SHARED src/${PROJECT_NAME}.cpp src/display.cpp src/yolo_with_plugins.cpp)
add_executable(${PROJECT_NAME}_node nodes/${PROJECT_NAME}_node.cpp)
add_executable(trt_yolo_v4 src/trt_yolo_v4.cpp ${util_src})
这里做了一点优化,将Main函数放置于node中,符合ROS2的项目结构。
target_include_directories(${PROJECT_NAME} PRIVATE
include
${ament_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
)
target_include_directories(${PROJECT_NAME}_node PRIVATE
include
)
include_directories(
${catkin_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
${OpenCV_INCLUDE_DIRS}
${CMAKE_CURRENT_SOURCE_DIR}/include
)
这里使用target_include_directories代替了原有的include_directories,由于include_directories的作用范围是全局,且include需要在add_executable之前,使用target_include_directories可以更针对性的导入包,使项目结构更加清晰。
ament_target_dependencies(${PROJECT_NAME}
rclcpp
rclcpp_lifecycle
rclcpp_components
rosidl_default_generators
std_msgs
geometry_msgs
message_filters
sensor_msgs
image_transport
cv_bridge
)
ament_target_dependencies(${PROJECT_NAME}_node
rclcpp
)
rosidl_target_interfaces(${PROJECT_NAME}
${PROJECT_NAME}_Message
"rosidl_typesupport_cpp"
)
catkin_package(
CATKIN_DEPENDS nodelet rospy image_transport sensor_msgs vision_msgs cv_bridge message_runtime
)
这也是一个替换方式,使用了ament_target_dependencies代替catkin_package的作用
install(DIRECTORY launch
DESTINATION share/${PROJECT_NAME}
FILES_MATCHING PATTERN "*.py"
)
install(DIRECTORY config
DESTINATION share/${PROJECT_NAME}
FILES_MATCHING PATTERN "*.yaml"
)
install(PROGRAMS
${PROJECT_BINARY_DIR}/libyaml-cpp.so.0.7
$/{PROJECT_BINARY_DIR}/libgxiapi.so
${PROJECT_BINARY_DIR}/GxGVTL.cti
${PROJECT_BINARY_DIR}/GxU3VTL.cti
DESTINATION lib/${PROJECT_NAME}
)
install(TARGETS ${PROJECT_NAME}_node
RUNTIME DESTINATION lib/${PROJECT_NAME}
ARCHIVE DESTINATION lib/${PROJECT_NAME}
LIBRARY DESTINATION lib/${PROJECT_NAME}
DESTINATION lib/${PROJECT_NAME}
)
install(TARGETS ${PROJECT_NAME}_node ${PROJECT_NAME}
ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION}
)
install(DIRECTORY launch/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/launch
FILES_MATCHING PATTERN "*.launch"
)
install(DIRECTORY config/Galaxy_Camera/
DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION}/config
FILES_MATCHING PATTERN "*.yaml"
)
这里需要着重讲解一下ROS2与ROS1在安装文件上的区别。可以看到
在ROS1中使用install,只需指定{CATKIN_PACKAGE_LIB_DESTINATION},会将库文件安装到devel下面,无需手动指定,但是可以通过ldd命令查看链接的项目内含的库文件是链接至源库目录,如下图。
而在ROS2中则是默认将程序安装到install目录,而外部依赖的库文件如果不手动指定rpath路径,则会出现Not Found的问题。
但是上图中的可执行文件是在install目录中的执行文件,我们看一下这个文件实际编译的位置(也就是Build文件夹中)的可执行文件,发现可以正常链接。
也就是ROS2实际上在Build文件夹中进行编译,在执行install之后会将可执行文件以及库文件安装至install文件夹中,因此我们需要设置rpath,来满足同目录下的相对路径库文件查找,并且我们使用了${PROJECT_BINARY_DIR} 这个指令来指定安装位置与Bin文件的输出路径一致,如果不指定rpath,则在ldconfig中程序无法查找当前相对路径下链接到的库文件。
下图可以看下在build和install文件夹中分别是如何分布的。
ROS1 ROS2 build ROS2 install
ament_package()
在CMakeLists.txt中最后一行请添加这句语句,声明这是ament package。
3. Launch文件对比(上为ROS2,下为ROS1)
import os
import launch
from ament_index_python.packages import get_package_share_directory
from launch.substitutions import EnvironmentVariable
from launch.substitutions import LaunchConfiguration
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
def generate_launch_description():
param_dir = os.path.join(get_package_share_directory('bitcq_camera'), 'config', 'params.yaml')
print(param_dir)
return LaunchDescription([
Node(
package='bitcq_camera',
executable='bitcq_camera_node',
# namespace='bc',
name='bitcq_camera_node',
prefix=['stdbuf -o L'],
output='screen',
parameters=[
param_dir
]
)
])
<launch>
<!-- DEBUG: launch-prefix="gdb -ex run -(delete)-args" -->
<node name="bitcq_camera" pkg="bitcq_camera" type="bitcq_camera_node" output="screen">
<rosparam command="load" file="$(find bitcq_camera)/config/bitcq_camera.yaml"/>
<param name="galaxy_yaml_path" value="$(find bitcq_camera)/config/Galaxy_Camera/galaxy_camera.yaml"/>
<param name="rtsp_yaml_path" value="$(find bitcq_camera)/config/Rtsp_Camera/rtsp_camera.yaml"/>
<param name="gmsl_yaml_path" value="$(find bitcq_camera)/config/GMSL_Camera/gmsl_camera.yaml"/>
</node>
</launch>
ROS2中将launch替换为了python文件,通过运行此文件进行节点的启动。这里对这个文件里面的一些参数进行解释。
package: 项目的包名
executable:输出的可执行文件(node)的名字
namespace:可选的设置,只要设置了,你发布的rostopic的前面就会添加上这个namespace,如/bc/image_source_0,同时在params.yaml中也需要添加上namespace,否则无法正常读取配置文件
prefix:这一句添加了才可以正常的在程序中使用std进行语句输出
output:这个参数也是类似于ROS1中的output
Params.yaml:该文件是用于在python文件中加载参数,类似于在ROS1的launch中的param标签。请注意写法。
bitcq_camera_node:
ros__parameters:
bitcq_yaml_path: "/root/ros2_ws/install/bitcq_camera/share/bitcq_camera/config/bitcq_camera.yaml"
galaxy_yaml_path: "/root/ros2_ws/install/bitcq_camera/share/bitcq_camera/config/Galaxy_Camera/galaxy_camera.yaml"
gmsl_yaml_path: "/root/ros2_ws/install/bitcq_camera/share/bitcq_camera/config/Rtsp_Camera/rtsp_camera.yaml"
rtsp_yaml_path: "/root/ros2_ws/install/bitcq_camera/share/bitcq_camera/config/GMSL_Camera/gmsl_camera.yaml"
4. Node Main函数区别(上为ROS2,下为ROS1)
#include <bitcq_camera.h>
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
auto yolov4 = std::make_shared<Yolov4>(rclcpp::NodeOptions{});
rclcpp::spin(yolov4);
rclcpp::shutdown();
}
#include <bitcq_camera.h>
int main(int argc, char** argv)
{
ros::init(argc,argv,"yolov4_detection",ros::init_options::AnonymousName);
ros::NodeHandle n("~");
DYolov4 Yolov4(n);
ros::spin();
ros::shutdown();
}
这里看出来大部分都是ros对rclcpp的替换,但是创建节点的时候是有区别的。
5. 头文件区别(上为ROS2,下为ROS1)
#include <rclcpp/rclcpp.hpp>
#include <image_transport/image_transport.hpp>
#include <image_transport/subscriber.hpp>
#include <image_transport/subscriber_filter.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <cv_bridge/cv_bridge.h>
#include <sensor_msgs/msg/image.hpp>
#include "yolov4_trt/msg/bounding_box2_d.hpp"
#include "yolov4_trt/msg/object_hypothesis.hpp"
#include "yolov4_trt/msg/detector2_d_array.hpp"
#include "yolov4_trt/msg/detector2_d.hpp"
#include "yolov4_trt/msg/bounding_box.hpp"
#include "yolov4_trt/msg/bounding_boxes.hpp"
#include "ros/ros.h"
#include "ros/package.h"
#include <ros/console.h>
#include <image_transport/image_transport.h>
#include <image_transport/subscriber_filter.h>
#include <message_filters/subscriber.h>
#include <message_filters/synchronizer.h>
#include <message_filters/sync_policies/approximate_time.h>
#include "cv_bridge/cv_bridge.h"
#include <sensor_msgs/Image.h>
#include "yolov4_trt_ros/Detector2DArray.h"
#include "yolov4_trt_ros/Detector2D.h"
#include "yolov4_trt_ros/BoundingBox.h"
#include "yolov4_trt_ros/BoundingBoxes.h"
可以看出来变化主要是在消息的头文件上,需要注意ROS2中消息的头文件以及引用均需要在中间加msg字段
6. 类和构造函数的区别(上为ROS2,下为ROS1)
class Yolov4 : public rclcpp::Node
{
public:
explicit Yolov4(rclcpp::NodeOptions const& options) : rclcpp::Node{ "yolov4_trt_node", options }
{
}
}
class Yolov4
{
public:
ros::NodeHandle nh;
image_transport::ImageTransport it;
Yolov4(const ros::NodeHandle& node_handle) : nh(node_handle), it(node_handle)
{
}
}
在ROS1中,新建的NodeHandle是作为构造函数参数传递进类里面进行使用,而ROS2的类直接继承自rclcpp::Node,在使用node时直接使用this指针即可。
这里使用了explicit来显式声明构造函数,这种用法前提是构造函数只有一个参数传递。
我们这里使用一个语句来使用this指针,查看查看一下效果。
RCLCPP_INFO(this->get_logger(), “[%s]: Initializing…”, this->get_name());
7. 参数获取(上为ROS2,下为ROS1)
this->declare_parameter("topic_name_0");
this->get_parameter("topic_name_0", video_topic_0);
this->declare_parameter("category_number");
this->get_parameter("category_number", category_num);
this->declare_parameter("confidence_threshold");
this->get_parameter("confidence_threshold", conf_th);
this->declare_parameter("show_image");
this->get_parameter("show_image", show_img);
nh.param<std::string>("/yolov4_trt/topic_name_0", video_topic_0, "/image_source_0");
nh.param<int>("/yolov4_trt/category_number", category_num, 80);
nh.param<float>("/yolov4_trt/confidence_threshold", conf_th, 0.5);
nh.param<bool>("/yolov4_trt/show_image", show_img, true);
这里用四个参数举例,可以看出ROS1和ROS2的区别,在ROS2的构造函数中使用this指针代替了NodeHandle的作用来进行参数的获取。
8. Publisher和Subscriber的区别(上为ROS2,下为ROS1)
rmw_qos_profile_t qos = rmw_qos_profile_default;
//ImageTransport 创建订阅者节点
ImageTransport::Subscriber image_sub =
image_transport::create_subscription(
this,
"/image_source_1",
std::bind(&Yolov4::imageCallback, this, std::placeholders::_1),
"raw",
qos
);
//普通sensor_msgs的创建
auto image_sub2 = this->create_subscription<sensor_msgs::msg::Image>(
"/image_source_1",
qos,
std::bind(&Yolov4::imageCallback, this, std::placeholders::_1)
)
//ImageTransport 创建订阅者节点
const boost::function<void(const sensor_msgs::ImageConstPtr&)> f(
boost::bind(&Yolov4::imageCallback,this,_1)
);
ImageTransport::Subscriber image_sub= it.subscribe("/image_source_1",1,f);
//普通sensor_msgs的创建
ros::Subscriber<sensor_msgs::Image> image_sub2 = nh.subscribe("/image_source_1",1,f);
可以看出来ROS2使用了create_subscription来创建接收器。这里演示了ROS1和ROS2中的两种订阅器创建方式。其他消息订阅器的创建也和这个类似。
cv::Mat image = cv::Mat::zeros(cv::Size(1920, 1080), CV_8UC3);
rmw_qos_profile_t qos = rmw_qos_profile_default;
//ImageTransport 推送节点创建
image_transport::Publisher itPub;
sensor_msgs::msg::Image::SharedPtr msg;
itPub = image_transport::create_publisher(this, "image_source_1", qos);
msg = cv_bridge::CvImage(std_msgs::msg::Header(), "bgr8", image).toImageMsg();
msg->header.stamp = rclcpp::Clock().now();
itPub.publish(msg);
//普通消息推送节点
std::shared_ptr<rclcpp::Publisher<yolov4_trt::msg::BoundingBoxes>> msgPub =
this->create_publisher<yolov4_trt::msg::BoundingBoxes>("bounding_boxes_0", 1);
yolov4_trt::msg::BoundingBoxes boxes_msg;
boxes_msg.header.stamp = rclcpp::Clock().now();
boxes_msg.header.frame_id = "detection";
yolov4_trt::msg::BoundingBox bounding_box_msg;
boxes_msg.bounding_boxes.push_back(bounding_box_msg);
msgPub->publish(boxes_msg);
cv::Mat image = cv::Mat::zeros(cv::Size(1920, 1080), CV_8UC3);
//ImageTransport 推送节点创建
image_transport::ImageTransport it(node);
image_transport::Publisher pub = it.advertise("image_source_1", 1);
sensor_msgs::ImagePtr msg;
msg = cv_bridge::CvImage(std_msgs::Header(), "bgr8", image).toImageMsg();
pub.publish(msg);
//普通消息推送节点
ros::Publisher msgPub =
nh.advertise<yolov4_trt_ros::BoundingBoxes>("/bounding_boxes_0", 1);
yolov4_trt_ros::BoundingBoxes boxes_msg;
boxes_msg.header.stamp = ros::Time::now();
boxes_msg.header.frame_id = "detection";
yolov4_trt_ros::BoundingBox bounding_box_msg;
boxes_msg.bounding_boxes.push_back(bounding_box_msg);
msgPub.publish(boxes_msg);
可以对比我编写的四个例程,对项目中原有的推送节点进行修改。
9. ROS2中一些用法与ROS1的对比(上为ROS2,下为ROS1)
rclcpp::WallRate loopRate(30);
while (rclcpp::ok())
{
//TO-DO
rclcpp::spin_some(this->get_node_base_interface());
loopRate.sleep();
}
ros::Rate loopRate(60);
while (node.ok())
{
//TO-DO
ros::spinOnce();
loopRate.sleep();
}
可以看到在ROS2中,在构造函数外如果需要使用一些需要node节点的自带函数,则可以使用this->get_node_base_interface()来声明获取一个node,而不是直接使用this指针。