message_generation功能包是用于生成C++或Python能使用的代码。
message_runtime则是提供运行时的支持。
消息类型与C++或者Python的数据类型对应关系如下表:
自定义消息
-
在功能包中新建一个文件夹,名字为msg,这很重要,若非特别想要,尽量不要修改这个文件夹的名字。
-
在msg文件夹其中新建一个名为
topic_msg.msg
消息类型文件。 -
然后在这个消息文件写入以下测试内容:
0安装环境
1-1 安装ros
https://www.cnblogs.com/gooutlook/p/16363452.html
1-2 安装串口
sudo apt-get install ros-noetic-serial
noetic是板本号
1创建环境工程
1创建catkin_ros工程文件环境
mkdir -p catkin_ros/src
在catkin_ros路径下编译
catkin_make
自动生成
#将新的工作空间加入到环境变量中
source devel/setup.bash
2 创建项目工程
环境工程catkin_ros/src下创建工程imu_gps_publish
方法1 程序创建imu_gps_publish包
(没有工程前提下,程序自动创建基本依赖的等)
#创建一个名为'imu_gps_publish'的新程序包,这个程序包依赖于std_msgs、roscpp和rospy:
catkin_create_pkg imu_gps_publish roscpp rospy std_msgs message_generation message_runtime
此时整个工作空间的文件架构如下:
catkin_ros #工作空间 build devle src imu_gps_publish include src CMakeLists.txt package.xml CMakeLists.txt
其中CMakeLists.txt和package.xml在自动阶段加入roscpp等基本库引用
方法2 已有程序直接导入已有的工程
将现有工程拷贝过来,但是要修改名字和一些路径
拷贝CMakeLists.txt package.xml src代码 msg自定义消息等
2 创建自定消息
2-1创建消息文件
在项目包里面创建msg文件夹
创建自定义消息topic_msg.msg
bool bool_msg int8 int8_msg uint8 uint8_msg int16 int16_msg uint16 uint16_msg int32 int32_msg uint32 uint32_msg int64 int64_msg uint64 uint64_msg float32 float32_msg float64 float64_msg string string_msg time time_msg duration duration_msg
2-2 创建编辑package.xml
<?xml version="1.0"?> <package format="2"> <name>imu_gps_publish</name> <version>0.0.0</version> <description>The imu_gps_publish package</description> <!-- One maintainer tag required, multiple allowed, one person per tag --> <!-- Example: --> <!-- <maintainer email="jane.doe@example.com">Jane Doe</maintainer> --> <maintainer email="dongdong@todo.todo">dongdong</maintainer> <!-- One license tag required, multiple allowed, one license per tag --> <!-- Commonly used license strings: --> <!-- BSD, MIT, Boost Software License, GPLv2, GPLv3, LGPLv2.1, LGPLv3 --> <license>TODO</license> <buildtool_depend>catkin</buildtool_depend> <build_depend>message_generation</build_depend> <build_depend>roscpp</build_depend> <build_depend>rospy</build_depend> <build_depend>std_msgs</build_depend> <build_export_depend>roscpp</build_export_depend> <build_export_depend>rospy</build_export_depend> <build_export_depend>std_msgs</build_export_depend> <exec_depend>message_runtime</exec_depend> <exec_depend>roscpp</exec_depend> <exec_depend>rospy</exec_depend> <exec_depend>std_msgs</exec_depend> <!-- The export tag contains other, unspecified, tags --> <export> <!-- Other tools can request additional information be placed here --> </export> </package>
修改
1项目名字imu_gps_publish和文件夹一样
<name>imu_gps_publish</name> <version>0.0.0</version> <description>The imu_gps_publish package</description>
2如果你是在已有的功能包中想要自定义消息,则在package.xml
文件中添加功能包依赖:
<build_depend>message_generation</build_depend> <run_depend>message_runtime</run_depend>
2-3创建编辑CMakeLists.txt
cmake_minimum_required(VERSION 3.0.2) project(imu_gps_publish) ## Compile as C++11, supported in ROS Kinetic and newer # add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS message_generation message_runtime roscpp rospy std_msgs ) add_message_files( FILES topic_msg.msg ) generate_messages( DEPENDENCIES std_msgs ) catkin_package( # INCLUDE_DIRS include # LIBRARIES my_topic002 # CATKIN_DEPENDS message_generation message_runtime roscpp rospy std_msgs # DEPENDS system_lib ) ########### ## Build ## ########### include_directories( # include ${catkin_INCLUDE_DIRS} ) #add_executable(publisher_topic002 src/publisher_topic002.cpp) #target_link_libraries(publisher_topic002 ${catkin_LIBRARIES}) #add_dependencies(publisher_topic002 ${PROJECT_NAME}_generate_messages_cpp) #add_executable(subscriber_topic002 src/subscriber_topic002.cpp) #target_link_libraries(subscriber_topic002 ${catkin_LIBRARIES}) #add_dependencies(subscriber_topic002 ${PROJECT_NAME}_generate_messages_cpp)
其中
1修改项目名字和文件夹一样
cmake_minimum_required(VERSION 3.0.2) project(imu_gps_publish)
2 修改自定义的消息
3其他说明(自动生成的时候加入的,这里直接贴了出来给查看)
CMakeLists.txt要修改4-5个地方,根据实际场景修改即可:
3-1首先调用find_package查找依赖的功能包,必须要有的是roscpp、rospy、message_generation、message_runtime,而在消息文件中嵌套了其他的消息,则需要依赖其他的功能包。
find_package(catkin REQUIRED COMPONENTS message_generation message_runtime roscpp rospy std_msgs )
3-2添加消息文件,指定.msg文件。
add_message_files( FILES topic_msg.msg )
3-3指定生成消息文件时的依赖项,其实如果消息文件中有依赖的话,就需要在这里设置,此处假设我依赖了std_msgs(当然我是没有依赖的),就要配置如下:
generate_messages( DEPENDENCIES std_msgs )
3-4 catkin_package
声明相关的依赖,一般来通过catkin_create_pkg
命令选择了依赖的话,这里是不需要设置的,不过我也给出来我的配置:
catkin_package( # INCLUDE_DIRS include # LIBRARIES my_topic002 # CATKIN_DEPENDS message_generation message_runtime roscpp rospy std_msgs # DEPENDS system_lib )
3-5编写编译规则,生成的可执行文件名字、源码、链接库、依赖等内容。
消息阶段用不到
add_executable(publisher_topic002 src/publisher_topic002.cpp) target_link_libraries(publisher_topic002 ${catkin_LIBRARIES}) add_dependencies(publisher_topic002 ${PROJECT_NAME}_generate_messages_cpp) add_executable(subscriber_topic002 src/subscriber_topic002.cpp) target_link_libraries(subscriber_topic002 ${catkin_LIBRARIES}) add_dependencies(subscriber_topic002 ${PROJECT_NAME}_generate_messages_cpp)
编译消息
在catkin_ros文件路径下编译
catkin_make
可以看到生成的自定义消息文件地址
在devel的include文件夹中
3对消息的引用
3-1发布器
imu_gps_publish/src下创建publisher_topic002.cpp
#include <cstdlib> #include <iostream> #include <string> #include <cstring> //0 导入ros依赖 #include "ros/ros.h" //0 导入消息 工程名字/消息名字 #include "imu_gps_publish/topic_msg.h" #include "std_msgs/String.h" int main(int argc, char **argv) { // 0-1 ROS节点初始化 ros::init(argc, argv, "publisher_topic002"); // 0-2 创建节点句柄 ros::NodeHandle n; // 1 创建发布器 // 1-1创建一个Publisher,发布名为my_topic_msg,消息类型为imu_gps_publish::topic_msg,队列长度100 ros::Publisher pub_topic = n.advertise<my_topic002::topic_msg>("my_topic_msg",100); // 1-2设置循环的频率 ros::Rate loop_rate(1); while (ros::ok()) { // 2 创建消息 // 2-0 创建消息 my_topic002::topic_msg msg; // 2-1 消息初始化 msg.bool_msg = true; msg.string_msg = "hello world!"; msg.float32_msg = 6.66; msg.float64_msg = 666.666; msg.int8_msg = -66; msg.int16_msg = -666; msg.int32_msg = -6666; msg.int64_msg = -66666; msg.uint8_msg = 66; msg.uint16_msg = 666; msg.uint32_msg = 6666; msg.uint64_msg = 66666; msg.time_msg = ros::Time::now(); // 3 发布消息 pub_topic.publish(msg); // 4按照循环频率延时 loop_rate.sleep(); } return 0; }
修改
1自定义消息路径和名字 工程包名字imu_gps_publish+自定义的消息名字topic_msg
包含头文件
//0 导入消息 工程名字/消息名字 #include "imu_gps_publish/topic_msg.h"
2 所有关于自定义消息的引用名字
imu_gps_publish::topic_msg
3-2接收节点
创建subscriber_topic002.cpp
#include <cstdlib> #include <iostream> #include <string> #include <cstring> //0 导入ros依赖 #include <ros/ros.h> //0 导入消息 工程名字/消息名字 #include "imu_gps_publish/topic_msg.h" #include <std_msgs/String.h> // 接收到订阅的消息后,会进入消息回调函数 void test_topic_cb(const imu_gps_publish::topic_msg::ConstPtr & msg) { // 将接收到的消息打印出来 ROS_INFO("------------------ msg ---------------------"); ROS_INFO("bool_msg: [%d]", msg->bool_msg); ROS_INFO("string_msg: [%s]", msg->string_msg.c_str()); ROS_INFO("float32_msg: [%f]", msg->float32_msg); ROS_INFO("float64_msg: [%f]", msg->float64_msg); ROS_INFO("int8_msg: [%d]", msg->int8_msg); ROS_INFO("int16_msg: [%d]", msg->int16_msg); ROS_INFO("int32_msg: [%d]", msg->int32_msg); ROS_INFO("int64_msg: [%ld]", msg->int64_msg); ROS_INFO("uint8_msg: [%d]", msg->uint8_msg); ROS_INFO("uint16_msg: [%d]", msg->uint16_msg); ROS_INFO("uint32_msg: [%d]", msg->uint32_msg); ROS_INFO("uint64_msg: [%ld]", msg->uint64_msg); ROS_INFO("time_msg: [%d.%d]", msg->time_msg.sec, msg->time_msg.nsec); } int main(int argc, char **argv) { // 初始化ROS节点 ros::init(argc, argv, "subscriber_topic002"); // 创建节点句柄 ros::NodeHandle n; // 创建一个Subscriber,订阅名为my_topic_msg的消息,注册回调函数test_topic_cb ros::Subscriber sub_topic = n.subscribe<imu_gps_publish::topic_msg>("my_topic_msg", 100, test_topic_cb); // 循环等待回调函数 ros::spin(); return 0; }
修改
1自定义消息路径和名字 工程包名字imu_gps_publish+自定义的消息名字topic_msg
//0 导入消息 工程名字/消息名字 #include "imu_gps_publish/topic_msg.h"
2 所有关于自定义消息的引用名字
3-3 修改CMakeLists.txt编译节点
添加发射和接受节点的生成
add_executable(publisher_topic002 src/publisher_topic002.cpp) target_link_libraries(publisher_topic002 ${catkin_LIBRARIES}) add_dependencies(publisher_topic002 ${PROJECT_NAME}_generate_messages_cpp) add_executable(subscriber_topic002 src/subscriber_topic002.cpp) target_link_libraries(subscriber_topic002 ${catkin_LIBRARIES}) add_dependencies(subscriber_topic002 ${PROJECT_NAME}_generate_messages_cpp)
完整的
cmake_minimum_required(VERSION 3.0.2) project(imu_gps_publish) ## Compile as C++11, supported in ROS Kinetic and newer # add_compile_options(-std=c++11) find_package(catkin REQUIRED COMPONENTS message_generation message_runtime roscpp rospy std_msgs ) add_message_files( FILES topic_msg.msg ) generate_messages( DEPENDENCIES std_msgs ) catkin_package( # INCLUDE_DIRS include # LIBRARIES my_topic002 # CATKIN_DEPENDS message_generation message_runtime roscpp rospy std_msgs # DEPENDS system_lib ) ########### ## Build ## ########### include_directories( # include ${catkin_INCLUDE_DIRS} ) add_executable(publisher_topic002 src/publisher_topic002.cpp) target_link_libraries(publisher_topic002 ${catkin_LIBRARIES}) add_dependencies(publisher_topic002 ${PROJECT_NAME}_generate_messages_cpp) add_executable(subscriber_topic002 src/subscriber_topic002.cpp) target_link_libraries(subscriber_topic002 ${catkin_LIBRARIES}) add_dependencies(subscriber_topic002 ${PROJECT_NAME}_generate_messages_cpp)
3-4 编译工程
在大工程catkin_ros下编译
catkin_make
4运行工程
4-1 运行ros初始化
随意路径运行,必须单独运行在一个窗口
roscore
4-2 在命令行注册项目地址,使得命令行可以找到要执行的ros节点
source /home/dongdong/v2_Project/v4_ROS/catkin_ros/devel/setup.bash
4-3 运行节点
rosrun 项目名字 编译节点
运行发布节点
rosrun imu_gps_publish publisher_topic002
注意同一个命令终端执行过4-2中source指令,不然找不到ROS节点运行
运行接受节点
rosrun imu_gps_publish subscriber_topic002
注意同一个命令终端执行过4-2中source指令,不然找不到ROS节点运行
程序结果
1秒发送一次数据,接收端接受显示。
rostopic list -v #查看节点
下一步 发布图像数据