在 ROS 通信协议中,数据是以约定好的结构传输的,即数据类型,比如Topic使用的msg,Service使用的srv,ROS 中的 std_msgs 封装了一些原生的数据类型,比如:Bool、Char、Float32、Int64、String等,但这些类型结构简单,常常不能满足我们的需要,这时我们可以使用自定义的消息类型。
比如我们创建一个自定义消息,定义一个机器人的ID,位置(x, y)。
一、创建RobotPose.msg
我们仍然使用前文创建的 topic_hello_world
功能包,结构如下:
在src
的同级目录创建 msg
目录,在msg
目录创建 RobotPose.msg
文件,内容如下:
string id
float64 x
float64 y
float64 angle
二、配置编译文件
需要对 CMakeLists.txt
作以下修改:
2.1 添加message_generation功能包
message_generation
功能包,在构建时根据msg
和srv
生成消息和服务的接口文件(比如C++头文件和Python包),以便在 ROS 节点中使用。
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
message_generation
)
注意这里需要同时在package.xml
中添加以下内容:
<build_depend>message_generation</build_depend>
2.2 添加msg文件
添加自定义msg
,该函数依赖message_generation
功能包。
add_message_files(
FILES
RobotPose.msg
)
2.3 配置依赖并生成接口文件
添加处理msg
或srv
所需要的依赖,并生成接口文件,该函数依赖message_generation
功能包。
generate_messages(
DEPENDENCIES
std_msgs
)
2.4 添加message_runtime依赖
message_runtime
用于在运行时提供消息的序列化和反序列化支持。
这里注意,有时可能会看到没有显式添加 message_runtime
也能正常运行,这通常是因为其他依赖项(例如roscpp
或 std_msgs
)可能已经隐含地包含了 message_runtime
。在这种情况下,构建系统已经处理了消息生成的任务。
然而,为了确保你的软件包在所有情况下都能正常工作,最好显示添加 message_runtime
作为你的软件包的依赖项。这样可以确保你的消息定义在构建和运行时得到正确处理。
需要对 CMakeLists.txt
作以下修改:
catkin_package(
CATKIN_DEPENDS roscpp rospy std_msgs message_runtime
)
同时在package.xml
中添加以下内容:
<exec_depend>message_runtime</exec_depend>
节外生枝的小知识:
catkin_package
是在ROS软件包的CMakeLists.txt
文件中用于配置Catkin软件包的一条命令。它主要用于描述ROS软件包的元信息,并在构建系统中定义软件包的依赖关系。以下是catkin_package
的一般用途:
软件包元信息配置:
catkin_package
允许你指定软件包的元信息,例如软件包的名称、版本、作者、描述等。这些信息将用于标识和描述你的ROS软件包。cmakeCopy codecatkin_package( NAME your_package_name VERSION 0.1.0 DESCRIPTION "Your package description" AUTHOR "Your Name" )
设置软件包的依赖项:
catkin_package
允许你指定你的软件包依赖于其他ROS软件包的哪些部分。这些依赖项将在构建和运行时被解析和满足。cmakeCopy codecatkin_package( ... CATKIN_DEPENDS roscpp std_msgs message_runtime )
导出软件包的目标: 通过
${PROJECT_NAME}_EXPORTED_TARGETS
这样的参数,你可以导出软件包的目标,以便其他软件包能够正确地依赖你的软件包,并包含所有必要的目标。cmakeCopy codecatkin_package( ... EXPORTED_TARGETS ${PROJECT_NAME}_EXPORTED_TARGETS )
总体而言,
catkin_package
提供了一个中心化的地方,用于指定ROS软件包的基本信息和配置,以便构建系统和其他软件包能够正确地使用和依赖你的软件包。在ROS中,它是配置软件包最重要的命令之一。
三、实现发布者与订阅者(C++版)
3.1 源码
在创建的 topic_hello_world
包路径的 src
目录中创建 user_msg_pub.cpp
以实现发布者,编辑内容如下:
#include <ros/ros.h>
#include "topic_hello_world/RobotPose.h"
int main(int argc, char **argv)
{
ros::init(argc, argv, "user_msg_pub");
ros::NodeHandle nh;
ros::Publisher pose_pub = nh.advertise<topic_hello_world::RobotPose>("/robot_pose", 10);
topic_hello_world::RobotPose pose;
pose.id = "vbot";
pose.x = 23.6;
pose.y = 12.8;
pose.angle = 90.0;
while(ros::ok())
{
pose_pub.publish(pose);
ROS_INFO("Pub robot: %s, pose(%lf, %lf, %lf)", pose.id.c_str(), pose.x, pose.y, pose.angle);
ros::Duration(1).sleep();
ros::spinOnce();
}
return 0;
}
创建 user_msg_sub.cpp
以实现订阅者,编辑内容如下:
#include <ros/ros.h>
#include "topic_hello_world/RobotPose.h"
void robotPoseCallback(const topic_hello_world::RobotPose::ConstPtr &pose)
{
ROS_INFO("Sub robot: %s, pose(%lf, %lf, %lf)", pose->id.c_str(), pose->x, pose->y, pose->angle);
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "user_msg_sub");
ros::NodeHandle nh;
ros::Subscriber pose_sub = nh.subscribe<topic_hello_world::RobotPose>("/robot_pose", 10, robotPoseCallback);
ros::spin();
return 0;
}
修改 CMakeLists.txt
,只需添加如下内容:
add_executable(${PROJECT_NAME}_user_msg_pub src/user_msg_pub.cpp)
add_executable(${PROJECT_NAME}_user_msg_sub src/user_msg_sub.cpp)
target_link_libraries(${PROJECT_NAME}_user_msg_pub
${catkin_LIBRARIES}
)
target_link_libraries(${PROJECT_NAME}_user_msg_sub
${catkin_LIBRARIES}
)
3.2 编译运行
进入工作空间执行 catkin_make
命令编译工程,你可能会遇到如下错误:
这是因为上文提到的message_generation
功能包,在它编译自定义msg生成对应接口文件之前,编译了c++源文件,但这时头文件RobotPose.h
还没有生成,所以报错了。
到这里你有没有发现,如果各功能包间有依赖关系,他们的编译是有先后顺序的,那我们怎么控制这个先后顺序呢?答案是:不需要。哈哈,CMake已经替我们做了,我们只需告诉它哪个模块需要什么依赖,CMake内部会自动分析项目中的依赖关系,并根据这些依赖关系计算一个拓扑排序。然后,CMake会按照这个顺序处理各个功能包,以确保在构建过程中满足所有依赖关系。
我们可以在 CMakeLists.txt
中使用 add_dependencies()
来添加这个依赖关系,语法如下:
add_dependencies(target_name dependency_target_name)
其中,target_name
是要添加依赖关系的目标名称,dependency_target_name
是要添加的依赖目标名称。
例如,如果你有一个名为 my_node
的目标,你想要添加一个名为 my_dependency
的库作为其依赖项,可以使用以下命令:
add_dependencies(my_node my_dependency)
所以,为解决上述报错,我们在 topic_hello_world/CMakeLists.txt
中添加如下内容:
# 注意他们要放在add_executable之后,即先告诉CMake是哪个节点,再告诉CMake它需要什么依赖
add_dependencies(${PROJECT_NAME}_user_msg_pub ${PROJECT_NAME}_generate_messages_cpp)
add_dependencies(${PROJECT_NAME}_user_msg_sub ${PROJECT_NAME}_generate_messages_cpp)
其中,第一项是我们生成的节点,第二项 ${PROJECT_NAME}_generate_messages_cpp
是一个用于生成消息类型的C++文件的宏,它的作用是根据 .msg
和 .srv
文件生成对应的 .h
和 .cpp
文件。
3.3 节外生枝的小知识:
在ROS软件包的构建过程中,除了
${PROJECT_NAME}_generate_messages_cpp
,还有一些其他与消息生成和编译相关的宏。这些宏通常都是与 Catkin 工具链和 ROS 构建系统的一部分。以下是一些常见的与消息生成相关的宏:
${PROJECT_NAME}_generate_messages
: 这个宏表示生成所有与消息相关的任务。通常,在调用catkin_package(...)
时,CATKIN_DEPENDS
部分会包含${PROJECT_NAME}_generate_messages
,以确保在构建软件包时执行消息生成任务。catkin_package( CATKIN_DEPENDS roscpp std_msgs message_runtime ${PROJECT_NAME}_generate_messages )
${PROJECT_NAME}_generate_messages_py
: 类似于${PROJECT_NAME}_generate_messages_cpp
,这个宏用于指定生成与消息相关的Python代码的路径。当你的ROS软件包包含使用Python编写的节点或服务时,可能会用到这个宏。
${PROJECT_NAME}_EXPORTED_TARGETS
: 这个宏用于导出所有与软件包相关的目标,包括消息生成任务。通常,在调用catkin_package(...)
时,EXPORTED_TARGETS
部分会包含${PROJECT_NAME}_EXPORTED_TARGETS
,以确保其他软件包能够正确地依赖你的软件包,并包括所有必要的目标。cmakeCopy codecatkin_package( ... INCLUDE_DIRS include LIBRARIES ${PROJECT_NAME}_library CATKIN_DEPENDS roscpp std_msgs message_runtime DEPENDS system_lib EXPORTED_TARGETS ${PROJECT_NAME}_EXPORTED_TARGETS )
请注意,具体的宏可能会受到ROS版本、Catkin工具链版本和软件包的配置选项的影响。上述宏的名称中的
${PROJECT_NAME}
部分会根据你的软件包的名称而变化。
3.4 编译成功后,使用如下命令依次启动发布者和订阅者。
1. 启动ros master
roscore
2. 启动发布者
rosrun topic_hello_world topic_hello_world_user_msg_pub
3. 启动订阅者
rosrun topic_hello_world topic_hello_world_user_msg_sub
结果如下:
目前为止,Topic Hello World 的自定义msg已经成功了。
四、实现发布者与订阅者(Python版)
4.1 源码
在 topic_hello_world
包路径下的 scripts
目录中,创建 user_msg_pub.py
以实现发布者,编辑内容如下:
#! /usr/bin python
import rospy
from topic_hello_world.msg import RobotPose
def main():
rospy.init_node("user_msg_pub")
pub = rospy.Publisher("/robot_pose", RobotPose, queue_size=10)
msg = RobotPose()
msg.id = "vbot"
msg.x = 52.1
msg.y = 12.6
msg.angle = 180.0
while not rospy.is_shutdown():
pub.publish(msg)
rospy.loginfo("Pub robot: {}, pose({}, {}, {})".format(msg.id, msg.x, msg.y, msg.angle))
rospy.sleep(1)
if __name__ == "__main__":
main()
在scrips
中创建 user_msg_sub.py
以实现订阅者,编辑内容如下:
#! /usr/bin python
import rospy
from topic_hello_world.msg import RobotPose
def robotPoseCallback(msg):
rospy.loginfo("Sub robot: {}, pose({}, {}, {})".format(msg.id, msg.x, msg.y, msg.angle))
def main():
rospy.init_node("user_msg_sub")
rospy.Subscriber("/robot_pose", RobotPose, robotPoseCallback, queue_size=10)
rospy.spin()
if __name__ == "__main__":
main()
修改 CMakeLists.txt
,只需添加如下内容:
catkin_install_python(PROGRAMS
scripts/user_msg_pub.py
scripts/user_msg_sub.py
DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION}
)
4.2 编译运行
进入工作空间执行 catkin_make
命令编译工程,编译成功后,使用如下命令依次启动发布者和订阅者。
1. 启动ros master(如果已启动,无需再启动)
roscore
2. 启动发布者
rosrun topic_hello_world user_msg_pub.py
3. 启动订阅者
rosrun topic_hello_world user_msg_sub.py
结果如下: