一、msg
用于发布-订阅的通信方式中。
1、在包的src同级目录下创建msg文件夹。
2、在msg文件夹中,创建.msg文件(例:my_msg.msg)
3、编辑my_msg.msg文件
int32 data1
string data2
4、编辑package.xml , 添加依赖
<build_depend>message_generation</build_depend>
<build_export_depend>message_generation</build_export_depend>
<exec_depend>message_runtime</exec_depend>
5、编辑CMakeLists.txt
find_package()中添加message_generation
find_package(catkin REQUIRED COMPONENTS
message_generation
roscpp
rospy
std_msgs
)
add_message_files()中添加my_msg.msg
add_message_files(FILES
my_msg.msg
)
generate_messages()添加std_msgs
generate_messages(DEPENDENCIES
std_msgs
)
catkin_package()添加message_runtime
catkin_package(CATKIN_DEPENDS
message_runtime)
最后在add_executable(xxx src/xxx.cpp)后面添加一行
add_dependencies(xxx ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) #该项让编译器知道要注意编译顺序
target_link_libraries(xxx
${catkin_LIBRARIES}
)
具体例子如下:
add_executable(talker src/talker.cpp) #可执行文件
target_link_libraries(talker ${catkin_LIBRARIES})#链接库
add_executable(listener src/listener.cpp)
target_link_libraries(listener ${catkin_LIBRARIES})#链接库
add_dependencies(listener ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) #该项让编译器知道要注意编译顺序
add_dependencies(talker ${${PROJECT_NAME}_EXPORTED_TARGETS} ${catkin_EXPORTED_TARGETS}) #该项让编译器知道要注意编译顺序
include_directories(
include
${catkin_INCLUDE_DIRS}
)
6、编译,catkin_make,在devel/include 中可以看到头文件
listener.cpp
#include <iostream>
#include "ros/ros.h"
#include "std_msgs/String.h"
#include<ros_test/my_msg.h>
void chatterCallBack(const ros_test::my_msg::ConstPtr &msg)
{
ROS_INFO("I get: [%d:][%s]}",msg->data1,msg->data2.c_str());
}
int main(int argc, char **argv)
{
//ros节点初始化 "listener"节点名称,在ROS里同一时间不允许出现两个
ros::init(argc,argv,"listener");
//创建节点句柄
ros::NodeHandle h;
//创建一个subscriber, topic:chatter,消息类型std_msgs::String, 接收到消息,响应chatterCallBack
ros::Subscriber listener_sub = h.subscribe("chatter",1000,chatterCallBack);
//循环等待回调函数
ros::spin();
return 0;
}
talker.cpp
#include <iostream>
#include "ros/ros.h"
#include "std_msgs/String.h"
#include<ros_test/my_msg.h>
int main(int argc, char **argv)
{
//ros节点初始化 "talker"节点名称,在ROS里同一时间不允许出现两个
ros::init(argc,argv,"talker");
//创建节点句柄
ros::NodeHandle h;
ros_test::my_msg msg;
//创建一个publisher, topic:chatter,消息类型std_msgs::String
ros::Publisher chatter_pub = h.advertise<ros_test::my_msg>("chatter",1000); // "chatter"话题名称,消息缓存
//设置单循环的频率
ros::Rate looprate(10);
while (ros::ok())
{
std::stringstream ss;
ss<<"hello world12121";
msg.data1 = 1000;
msg.data2 = ss.str();
//发布消息
ROS_INFO("%s",msg.data2.c_str());
chatter_pub.publish(msg);
//等待回调函数
ros::spinOnce();
//按照之前设定的进行循环
looprate.sleep();
}
}