本文主要从以下几个方面进行说明:
首先创建一个空的package单独存放msg类型(当然也可以在任意的package中自定义msg类型)
这里为便于说明,建立一个名为 wts_rviz_msgs 的包,用于对自定义msg类型的用法举例。
$ cd catkin_ws/src //这里只是举例,实际为工程根目录(src、devel同级目录下)
$ catkin_create_pkg wts_rviz_msgs
在 wts_rviz_msgs 中创建msg文件夹,在msg文件夹其中新建如下消息类型文件:
$ cd wts_rviz_msgs
$ mkdir msg
基本类型可参考:
PointInfo.msg内容:
float32 dPointX
float32 dPointY
ParkingSpot.msg内容:
string parking_spot_name
bool publish_state
geometry_msgs/Pose2D pose
PointInfo[] point_list
ParkingSpotList.msg内容:
ParkingSpot[] parking_spot_list
需要message_generation生成C++或Python能使用的代码,需要message_runtime提供运行时的支持,所以package.xml中添加以下两句
ROS1中:
<build_depend>message_generation</build_depend>
<run_depend>message_runtime</run_depend>
ROS2中:
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
CMakeLists.txt要注意四个地方
(1) 设置find_package
首先调用 find_package 查找依赖的包,必备的有roscpp rospy message_generation,其他根据具体类型添加,比如上面的msg文件中用到了geometry_msgs/Pose pose类型,那么必须查找geometry_msgs
find_package(catkin REQUIRED COMPONENTS roscpp rospy message_generation std_msgs geometry_msgs)
(2) 设置add_message_files
然后是 add_message_files ,指定msg文件
add_message_files(
FILES
PointInfo.msg
ParkingSpot.msg
ParkingSpotList.msg
)
(3) 设置generate_messages
然后是 generate_messages ,指定生成消息文件时的依赖项,比如上面嵌套了其他消息类型geometry_msgs,那么必须注明
#generate_messages必须在catkin_package前面
generate_messages(
DEPENDENCIES
std_msgs
geometry_msgs
)
(4) 设置catkin_package
然后是 catkin_package 设置运行依赖
catkin_package(
CATKIN_DEPENDS message_runtime
)
(5) 编译
$ cd catkin_ws //这里只是举例,实际为工程根目录(src、devel同级目录下)
$ catkin_make -j4
(6) 查看rosmsg
到这里新的msg类型 wts_rviz_msgs/ParkingSpotList 就可以使用了,下面编译这个包,然后利用rosmsg show指令查看。
$ cd 工程根目录 //与devel同级目录
$ source devel/setup.bash #注意:必须执行source 进行安装,否则不识别该消息
$ rosmsg show wts_rviz_msgs/ParkingSpotList
要使用自定义的消息类型必须source自定义消息所在的工作空间, 否则rosmsg show wts_rviz_msgs/ParkingSpotList t和rostopic echo /wts_topic_rviz_msgs(/wts_rviz_msgs 是节点中使用自定义消息类型 wts_rviz_msgs/ParkingSpotList 的topic)都会报错,因为没有source的情况下自定义消息类型是不可见的,被认为是未定义类型
一种典型的错误是删掉工作空间下的devel和build文件夹之后重新编译代码,此时由于没有source自定义消息所在的工作空间,即使使用自定义消息的代码和自定义消息在同一个包也无法找到,该消息头文件,此时需要运行source devel/setup.bash之后重新编译就好。
如果是在test_msgs包内的节点中调用test_msgs/Test类型,只需要在.cpp文件中如下调用即可
#include "wts_rviz_msgs/ParkingSpotList.h"
wts_rviz_msgs::ParkingSpotList msg_parking_spot_list_published;
如果是在其他包调用 wts_rviz_msgs/ParkingSpotList 类型则需要修改package.xml和CMakeLists.txt,比如同样在工作空间catkin_ws内有一个名为 interactive_parking_spot 的包,我们可以在这个包内写一个节点,使用我们刚才自定义的消息类型 wts_rviz_msgs/ParkingSpotList ,如下:
**(1)修改package.xml **
养成好习惯,维护软件包清单的更新,以便于别人使用你的软件前安装各种依赖项,当然这个文件不影响程序编译
ROS1中:
<build_depend>roscpp</build_depend>
<run_depend>roscpp</run_depend>
<build_depend>wts_rviz_msgs</build_depend>
<run_depend>wts_rviz_msgs</run_depend>
ROS2中:
<build_depend>roscpp</build_depend>
<run_depend>roscpp</run_depend>
<build_depend>wts_rviz_msgs</build_depend>
<exec_depend>wts_rviz_msgs</exec_depend>
**(2)修改CMakeLists.txt **
调用自定义消息类型主要修改两个地方,以下是重点:
一是find_package中需要声明查找包含该消息类型的包;
二是add_dependencies要注明该消息的依赖,其他地方和普通节点一样
#:注意,由于本例中使用了 geometry_msgs/Pose2D 类型,编译版本需要 大于 C++11
add_compile_options(-std=c++17)
find_package(catkin REQUIRED COMPONENTS
roscpp
geometry_msgs
wts_rviz_msgs
)
add_executable(interactive_parking_spot src/main.cpp)
target_link_libraries(interactive_parking_spot
${catkin_LIBRARIES}
)
#调用同一工作空间的自定义消息类型时注明依赖关系,防止发生头文件找不到的报错
add_dependencies(interactive_parking_spot wts_rviz_msgs_gencpp)
如果缺少add_dependencies中对 wts_rviz_msgs_gencpp 的依赖声明,在编译的时候如果先编译 interactive_parking_spot 包再编译 wts_rviz_msgs/ParkingSpotList 包则会出现如下报错(ROS工作空间各个软件包的编译顺序是随机的),因为头文件wts_rviz_msgs/ParkingSpotList.h 还未生成
fatal error: wts_rviz_msgs/ParkingSpotList.h: 没有那个文件或目录
#include “wts_rviz_msgs/ParkingSpotList.h”
#include "wts_rviz_msgs/ParkingSpotList.h"
int main(int argc, char** argv)
{
ros::init(argc, argv, "simple_marker");
ros::NodeHandle n;
ros::Publisher chatter_pub = n.advertise<wts_rviz_msgs::ParkingSpotList>("wts_topic_msg_parking_spots_info", 1000);
ros::Rate loop_rate(1);
while(ros::ok())
{
int iNum = parkingSpot.m_mapParkingSpot.size();
wts_rviz_msgs::ParkingSpotList msg_parking_spot_list_published;
std::map<std::string, WtsRvizParkingSpot>::iterator iter;
int iIndex = 0;
for(iter = parkingSpot.m_mapParkingSpot.begin(); iter!=parkingSpot.m_mapParkingSpot.end(); iter++)
{
wts_rviz_msgs::ParkingSpot parking_spot;
parking_spot.parking_spot_name = "ParkingSpotName";
parking_spot.publish_state = true
parking_spot.pose.x = 2.0082790851593018;
parking_spot.pose.x = 0;
parking_spot.pose.theta = 0.7217559218406677;
for(int iIndex = 0; iIndex < iter->second.vctrParkingSpotPoints.size(); iIndex++)
{
wts_rviz_msgs::PointInfo point_info;
point_info.dPointX = -1.6596179008483887;
point_info.dPointY = 2.2936594486236572;
parking_spot.point_list.push_back(point_info);
}
msg_parking_spot_list_published.parking_spot_list.push_back(parking_spot);
iIndex++;
}
chatter_pub.publish(msg_parking_spot_list_published);
ros::spinOnce();
loop_rate.sleep();
}
}
新建接受消息节点mylisten.cpp,添加以下代码:bash
#include <ros/ros.h>
#include <geometry_msgs/Pose2D.h>
#include "wts_rviz_msgs/ParkingSpotList.h"
void msgCallback(const wts_rviz_msgs::ParkingSpotList::ConstPtr &P)
{
ROS_INFO("I recevied the topic: ");
for(std::vector<wts_rviz_msgs::ParkingSpotList>::const_iterator it = P->path.begin(); it != P->path.end(); ++it)
{
//... ...
}
}
int main(int argc,char ** argv)
{
ros::init(argc,argv,"test1");
ros::NodeHandle n;
ros::Subscriber msg_sub = n.subscribe("wts_topic_msg_parking_spots_info", 100, msgCallback);
ros::spin();
return 0;
}
仿照前面发布msg的示例,修改CMakeLists.txt、package.xml,而后catkin_make从新编译,就OK了。