ROS 5: 自定义消息话题
实现目标:完成宝可梦信息的话题传输
自定义话题的流程:
graph TB a(定义msg文件) a -->b(package.xml中添加依赖) b -->c(CMakeLists.txt添加编译选项) c -->d(编译生成相关文件)
一、定义消息
先定义消息类型,ros使用*.msg
格式存储消息。
msg文件不是编程语言,所以在编译的时候,会根据不同的编程语言动态扩展层不同的数据类型。
string name #名字
string type #属性
uint8 gender #性别
uint8 unknown = 0
uint8 male = 1
uint8 female = 2
二、修改package.xml
在功能包的package.xml里,增加两句话,为其增加依赖包。包名如下:
<build_depend>message_generation</build_depend>
<exec_depend>message_runtime</exec_depend>
三、调整CMakeLists.txt
在CMakeLists.txt中补充以下内容
- 1、在第十行find_package的最后补充上
message_generation
.
find_package(catkin REQUIRED COMPONENTS
geometry_msgs
roscpp
rospy
std_msgs
turtlesim
message_generation
)
- 2、声明ROS消息。在
Declare ROS dynamic reconfigure parameters
上方,有关于msg编译的指导。
## 在“msg”文件夹中生成消息
# add_message_files(
# FILES
# Message1.msg
# Message2.msg
# )
## 在“srv”文件夹中生成服务
# add_service_files(
# FILES
# Service1.srv
# Service2.srv
# )
## 在“action”文件夹中生成操作
# add_action_files(
# FILES
# Action1.action
# Action2.action
# )
## 生成具有在此处列出的任何依赖项的添加消息和服务
# generate_messages(
# DEPENDENCIES
# geometry_msgs# std_msgs
# )
我们只需写入:
add_message_files(
FILES
Pokemon.msg
)
generate_messages(
DEPENDENCIES
std_msgs
)
################################################
## Declare ROS dynamic reconfigure parameters ##
################################################
- 3、在catkin_package增加运行依赖
###################################
## catkin specific configuration ##
###################################
catkin_package(
CATKIN_DEPENDS geometry_msgs roscpp rospy std_msgs turtlesim message_runtime
)
完成上述修改后,在工作空间使用catkin_make
编译,然后在工作空间的devel中就可以找到这个功能包的文件夹,里面就含有一个Pokemon.h
头文件。
四,编写代码
c++
publisher
#include <ros/ros.h>
#include "learn_topic/Pokemon.h"
int main(int argc,char **argv){
ros::init(argc,argv,"pokemon_pub_topic");
ros::NodeHandle n;
ros::Publisher Pub_Pokemon = n.advertise<learn_topic::Pokemon>("/pokemon_info",10);
ros::Rate loop_rate(10);
while (ros::ok())
{
learn_topic::Pokemon pokemon_msg;
pokemon_msg.name = "pikachu";
pokemon_msg.type = "electric";
pokemon_msg.gender = learn_topic::Pokemon::male;
Pub_Pokemon.publish(pokemon_msg);
ROS_INFO("Publish Pokemon INfo\n\t name:%s type:%s gender:%d", pokemon_msg.name.c_str(),pokemon_msg.type.c_str(),pokemon_msg.gender);
loop_rate.sleep();
}
return 0;
}
subscriber
#include <ros/ros.h>
#include "learn_topic/Pokemon.h"
void pokemonInfoCallback(const learn_topic::Pokemon::ConstPtr& msg)
{
ROS_INFO("Subcribe Pokemon Info: name:%s type:%s gender:%d",
msg->name.c_str(), msg->type.c_str(), msg->gender);
}
int main(int argc,char **argv){
ros::init(argc, argv, "pokemon_sub_topic");
ros::NodeHandle n;
ros::Subscriber Sub_Pokemon = n.subscribe<learn_topic::Pokemon>("/pokemon_info",10,pokemonInfoCallback);
ros::spin();
return 0;
}
cmake
add_executable(pub_pokemon src/pub_pokemon.cpp)
target_link_libraries(pub_pokemon ${catkin_LIBRARIES})
add_dependencies(pub_pokemon ${PROJECT_NAME}_generate_messages_cpp)
add_executable(sub_pokemon src/sub_pokemon.cpp)
target_link_libraries(sub_pokemon ${catkin_LIBRARIES})
add_dependencies(sub_pokemon ${PROJECT_NAME}_generate_messages_cpp)
python
publisher
import rospy
from learn_topic.msg import Pokemon
def pub_pokemon():
rospy.init_node('py_pokemon_pub_topic', anonymous=True)
Pub_Pokemon = rospy.Publisher('/pokemon_info', Pokemon, queue_size=10)
rate = rospy.Rate(10)
count = 0
while not rospy.is_shutdown():
pokemon_msg = Pokemon()
pokemon_msg.name = "psyduck"
pokemon_msg.type = "water"
pokemon_msg.gender = 2
Pub_Pokemon.publish(pokemon_msg)
rospy.loginfo("Publiish pokemon message[%s-%s-%d]",pokemon_msg.name,pokemon_msg.type,pokemon_msg.gender)
rate.sleep()
if __name__ == '__main__':
try:
pub_pokemon()
except rospy.ROSInterruptException:
pass
subscriber
import rospy
from learn_topic.msg import Pokemon
def pokemonInfoCallback(msg):
rospy.loginfo("Subscribe pokemon info: name:%s type:%s gender:%d",
msg.name,msg.type,msg.gender)
def sub_pokemon():
rospy.init_node('py_pokemon_sub_topic',anonymous=True)
rospy.Subscriber('/pokemon_info',Pokemon,pokemonInfoCallback)
rospy.spin()
if __name__ == '__main__':
sub_pokemon()
补充:ROS Master是负责给节点建立连接。如果多个节点链接完毕后,即使ROS Master断开也不影响节点之间的通讯,就是无法建立新的链接而已。