新一代机器人操作系统(robot operation system),继承了ROS1大部分优异特点,并对部分功能进行了增强,同时对ROS1中存在的主要问题进行了修复和改进,相关介绍很多,这里就不赘述了。
ROS1与ROS2的主体架构对比图:
对以上架构图进行剖析:
整体设计上的区别大概就是以上几点,实际应用中的细节性差异非常多,API基本被全部重写了,ROS1切到ROS2的用户建议仔细阅读官方迁移文档,下面主要看看这些改动对于实际应用的影响。
catkin_make -DCMAKE_BUILD_TYPE=Release --install
开发阶段一般会去掉–install选项,这与代码中关于配置以及launch的修改都会实时生效,大大提高了开发效率。
ROS2使用ament系统进行编译管理,按照ROS2官方编译系统的说法,ament系统是catkin系统的升级,修复了ROS1中大家反馈的一些问题,例如为了devel模式增加了大量逻辑等等,细节看官方文档就好,典型操作如下:
colcon build --cmake-args -DCMAKE_BUILD_TYPE=Release
一个直观感受就是colcon的参数指定都需要使用全称,虽然比较麻烦,但是可以减少误操作,使用类似catkin的开发模式只需要加上–symlink-install即可。
<launch>
<arg name="topic_name" default="chatter"/>
<node pkg="demo_nodes_cpp" exec="talker">
<remap from="chatter" to="$(var topic_name)"/>
node>
<node pkg="demo_nodes_cpp" exec="listener">
<remap from="chatter" to="$(var topic_name)"/>
node>
launch>
ROS2:
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.actions import ExecuteProcess
from launch.substitutions import LaunchConfiguration
def generate_launch_description():
DeclareLaunchArgument(
'topic_name',
default_value='chatter',
description='chatter topic name'),
return LaunchDescription([
Node(
package='demo_nodes_cpp',
executable='talker',
remappings=[
('chatter', LaunchConfiguration('topic_name')),
]
),
Node(
package='demo_nodes_cpp',
executable='chatter',
remappings=[
('chatter', LaunchConfiguration('topic_name')),
]
)
])
一个非常明显的区别,ROS2的launch文件编写复杂度远远高于ROS1的xml格式,虽然ROS2官方描述也可以支持xml格式,但实测中确实出过一些问题,并且从官方教程到几乎所有的ROS2开源库都使用了python版本的launch文件,文件复杂度不算是一个严重的问题,毕竟现在IDE下编写效率已经很高了,但launch.substitutions这个库着实没有xml中的${var}替换来得好用,举个例子:
from launch import LaunchDescription
from launch_ros.actions import Node
from launch.actions import DeclareLaunchArgument
from launch.actions import ExecuteProcess
from launch.substitutions import LaunchConfiguration
def generate_launch_description():
DeclareLaunchArgument(
'urdf_file_name',
default_value='a.urdf',
description=''),
urdf = os.path.join(
get_package_share_directory('urdf'),
'urdf',
LaunchConfiguration('urdf_file_name'))
with open(urdf, 'r') as infp:
robot_desc = infp.read()
return LaunchDescription([
Node(
package='robot_state_publisher',
executable='robot_state_publisher',
name='robot_state_publisher',
output='screen',
parameters=[{'robot_description': robot_desc}],
#arguments=[urdf]),
])
按照这个写法直接运行是会出问题的,因为substitution只有到运行时才会进行真正的替换,而os.path.join的操作在替换之前就进行了,实现同样的功能,替换成ROS1的xml格式不仅简洁明了,并且不会出问题。
rosbag2_cpp::StorageOptions storage_options({path, "sqlite3"});
const rosbag2_cpp::ConverterOptions converter_options(
{rmw_get_serialization_format(), rmw_get_serialization_format()});
auto writer = std::make_unique<rosbag2_cpp::writers::SequentialWriter>();
writer->open(storage_options, converter_options);
auto serializer = rclcpp::Serialization<sensor_msgs::msg::PointCloud2>();
auto bag_serialized_msg = std::make_shared<rosbag2_storage::SerializedBagMessage>();
writer->create_topic({"topic", "sensor_msgs/msg/PointCloud2", rmw_get_serialization_format(), ""});
sensor_msgs::msg::PointCloud2 ros_cloud;
// cloud -> serialized bag message
auto rclcpp_serialized_msg = rclcpp::SerializedMessage();
serializer.serialize_message(&ros_cloud, &rclcpp_serialized_msg);
bag_serialized_msg->serialized_data =
std::shared_ptr<rcutils_uint8_array_t>(new rcutils_uint8_array_t, [](rcutils_uint8_array_t* msg) {
auto fini_return = rcutils_uint8_array_fini(msg);
delete msg;
if (fini_return != RCUTILS_RET_OK) {
std::cerr << "Failed to destroy serialized message " << rcutils_get_error_string().str;
}
});
*tools.bag_serialized_msg->serialized_data = rclcpp_serialized_msg.release_rcl_serialized_message();
// end convert
tools.bag_serialized_msg->topic_name = cloud.first;
writer->write(tools.bag_serialized_msg);
截至目前,galactic虽然对以上过程进行了一定程度的封装,但封装也极为简化,同时read的流程仍没有封装,使用还是很麻烦。
class MinimalPublisher : public rclcpp::Node
{
public:
MinimalPublisher()
: Node("minimal_publisher"), count_(0)
{
publisher_ = this->create_publisher<std_msgs::msg::String>("topic", 10);
timer_ = this->create_wall_timer(
500ms, std::bind(&MinimalPublisher::timer_callback, this));
}
private:
rclcpp::TimerBase::SharedPtr timer_;
rclcpp::Publisher<std_msgs::msg::String>::SharedPtr publisher_;
size_t count_;
}
从ROS1转ROS2的开发者可能会稍有不适,ROS1中带上ros命名空间就可以各处使用ros的API了,而ROS2中如果希望将系统分割为很多个类,有两个选择:
1、将所有类都继承自rclcpp::Node
2、将一个外层封装类或者一个核心类继承自rclcpp::Node,其他类构造时接受它的引用或指针,利用这个引用调用ros API。
虽然说使用上比ROS1更麻烦,但让用户养成良好的面向对象变成习惯是一个好的选择。
class MinimalSubscriber : public rclcpp::Node
{
public:
MinimalSubscriber()
: Node("minimal_subscriber")
{
sub1_ = this->create_subscription<std_msgs::msg::String>("topic1", 10,
std::bind(&MinimalSubscriber::callback1, this, _1));
sub2_ = this->create_subscription<std_msgs::msg::String>("topic2", 10,
std::bind(&MinimalSubscriber::callback2, this, _1));
}
private:
rclcpp::Subscriber<std_msgs::msg::String>::SharedPtr sub1_;
rclcpp::Subscriber<std_msgs::msg::String>::SharedPtr sub2_;
}
int main(){
rclcpp::init(argc, argv);
rclcpp::ExecutorOptions exec_option;
rclcpp::executors::MultiThreadedExecutor exec(exec_option, 10);
exec.add_node(std::make_shared<MinimalSubscriber>());
exec.spin();
rclcpp::shutdown();
return 0;
}
按照以上的写法,callback1和callback2并不会异步运行,即使使用了MultiThreadedExecutor,没有手动指定subscriber的group,程序仍然等于是单线程在运行,想要两个callback异步运行,必须手动将其group指定为不同的group才行,因为一个ros node内部的subscribers默认都属于同一group,而不同ros node的subscribers默认属于不同group。
这种subscriber的管理方式确实会更清晰,但使用起来也更加麻烦。
export ROS_DOMAIN_ID=66
只要在同一ID的机器就可以接受到彼此的消息。
test_node:
ros__parameters:
common:
topic: "your_topic"
第一行必须跟node的name一致,若launch文件修改name,yaml会无法读取。第二行必须增加ros__parameters,加载二级分级参数时,代码中需要:
node_->declare_parameter("common.topic", "topic");
ROS1中使用/分级。