机器人操作系统ROS:从入门到放弃(三) 发布接收不同消息2 - 简书
三、发布接收不同消息2
上一讲我们讲了如何发布接收int,float和array类型的消息,这些也都算是c++自有的消息,被归纳在ROS中的std_msgs这个命名空间下。
这讲我们来看看如何发布接收ROS自己独特的message类型:PoseStamped.
Pose好理解,就是机器人的位姿(position and orientation),那么Stamped呢?Stamped表示时间戳(timestamped)。
ROS, geometry message:
里面又有一大堆不同类型的消息,你以后都可能用到.但这儿我们就用PoseStamped举例了,位姿加时间还是比较有代表性.
找到页面中的PoseStamped
并点击进入,会发现下面的内容
pub_poseStamped.cpp
在pub_sub_test/src
中创建一个名字叫pub_poseStamped.cpp
的文件.在文件中写入下面的内容.
#include "ros/ros.h"
#include "geometry_msgs/PoseStamped.h" //include posestamp head file
#include <cmath>//for sqrt() function
int main(int argc, char **argv)
{
ros::init(argc, argv, "talker");
ros::NodeHandle n;
ros::Publisher chatter_pub = n.advertise<geometry_msgs::PoseStamped>("chatter", 10); //initialize chatter
ros::Rate loop_rate(10);
//generate pose by ourselves.
double positionX, positionY, positionZ;
double orientationX, orientationY, orientationZ, orientationW;
//We just make the robot has fixed orientation. Normally quaternion needs to be normalized, which means x^2 + y^2 + z^2 +w^2 = 1
double fixedOrientation = 0.1;
orientationX = fixedOrientation ;
orientationY = fixedOrientation ;
orientationZ = fixedOrientation ;
orientationW = sqrt(1.0 - 3.0*fixedOrientation*fixedOrientation);
double count = 0.0;
while (ros::ok())
{
//We just make the position x,y,z all the same. The X,Y,Z increase linearly
positionX = count;
positionY = count;
positionZ = count;
geometry_msgs::PoseStamped msg;
//assign value to poseStamped
//First assign value to "header".
ros::Time currentTime = ros::Time::now();
msg.header.stamp = currentTime;
//Then assign value to "pose", which has member position and orientation
msg.pose.position.x = positionX;
msg.pose.position.y = positionY;
msg.pose.position.z = positionY;
msg.pose.orientation.x = orientationX;
msg.pose.orientation.y = orientationY;
msg.pose.orientation.z = orientationZ;
msg.pose.orientation.w = orientationW;
ROS_INFO("we publish the robot's position and orientaion");
ROS_INFO("the position(x,y,z) is %f , %f, %f", msg.pose.position.x, msg.pose.position.y, msg.pose.position.z);
ROS_INFO("the orientation(x,y,z,w) is %f , %f, %f, %f", msg.pose.orientation.x, msg.pose.orientation.y, msg.pose.orientation.z, msg.pose.orientation.w);
ROS_INFO("the time we get the pose is %f", msg.header.stamp.sec + 1e-9*msg.header.stamp.nsec);
std::cout<<"\n \n"<<std::endl; //add two more blank row so that we can see the message more clearly
chatter_pub.publish(msg);
ros::spinOnce();
loop_rate.sleep();
++count;
}
return 0;
}
咱们在发布器的代码中fixedOrientation
的变量,赋值0.1,然后分别赋值给创建的double类型变量orientationX,Y,Z,W
.在循环中,orientationX,Y,Z,W
在分别赋值给我们创建的msg的成员变量msg.pose.orientation.x y z w
.为什么能这么赋值?通过上面数据结构那张图我们了解到的msg.pose.orientation.x y z w
都是float64类型的变量,赋值了他们几个就可以定义pose的orientation了.orientation是相同的数,那么机器人就没有旋转.
那么pose的position的x y z我们直接赋值了count,count在循环中递增,那么XYZ都同时递增且相同.如果我们画一个三维坐标轴XYZ的话,那么咱么这儿模拟的机器人的运动状态,相当于机器人沿着坐标轴对角线匀速直线行驶.
sub_poseStamped.cpp
同样位置再创建一个sub_poseStamped.cpp
.写入下面内容.
#include "ros/ros.h"
#include "geometry_msgs/PoseStamped.h"
void chatterCallback(const geometry_msgs::PoseStamped::ConstPtr& msg) //Note it is geometry_msgs::PoseStamped, not std_msgs::PoseStamped
{
ROS_INFO("I heard the pose from the robot");
ROS_INFO("the position(x,y,z) is %f , %f, %f", msg->pose.position.x, msg->pose.position.y, msg->pose.position.z);
ROS_INFO("the orientation(x,y,z,w) is %f , %f, %f, %f", msg->pose.orientation.x, msg->pose.orientation.y, msg->pose.orientation.z, msg->pose.orientation.w);
ROS_INFO("the time we get the pose is %f", msg->header.stamp.sec + 1e-9*msg->header.stamp.nsec);
std::cout<<"\n \n"<<std::endl; //add two more blank row so that we can see the message more clearly
}
int main(int argc, char **argv)
{
ros::init(argc, argv, "listener");
ros::NodeHandle n;
ros::Subscriber sub = n.subscribe("chatter", 10, chatterCallback);
ros::spin();
return 0;
}
编译出错
同样再CMakeLists.txt文件中添加 两个文件的内容,保存后退出编译。
添加依赖
在新建package的时候 添加了几个依赖,如果日后的项目越来越多,需要的依赖也就越多,那么怎么再继续添加新的依赖呢?????
添加新的依赖项,要改动CMakeLists.txt文件和 package.xml文件
打开CMakeLists.txt,发现就在最前面几行,有下面的内容.
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
)
括号中的内容正好一一对应我们创建package时添加的依赖项,那么想都不用想啦,肯定要在后面添加geometry_msgs,变成下面的样子,保存退出.
find_package(catkin REQUIRED COMPONENTS
roscpp
rospy
std_msgs
geometry_msgs
)
添加完成后,保存退出.之后打开位于同一目录下的package.xml
.(直接双击打开可能不能修改其中内容,还是用gedit什么的打开).打开之后,在文档下方,你可以看到一下内容
<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>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
啊哈,又有std_msgs, rospy, roscpp
,只不过每个出现了三次,那么同样,不用管什么意思,我们只需要按照这个文档里相同的语法让geometry_msgs
出现三次就行了.更改之后该文件同样位置变成下面的内容。
<build_depend>roscpp</build_depend>
<build_depend>rospy</build_depend>
<build_depend>std_msgs</build_depend>
<build_depend>geometry_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>
<build_export_depend>geometry_msgs</build_export_depend>
<exec_depend>roscpp</exec_depend>
<exec_depend>rospy</exec_depend>
<exec_depend>std_msgs</exec_depend>
<exec_depend>geometry_msgs</exec_depend>
保存退出.这时候再用catkin_make编译,就成功了.改变上面两个文档的内容就相当于我们在创建package时添加了依赖项geometry_msgs
.编译成功之后,跑程序的方法和以前的例子一样。
总结
这一讲我们讲述了一个稍微复杂一点的message类型:poseStamped.我们需要通过ROS wiki的帮助知道它包含什么数据成员,了解它包含的数据成员之后,利用类对象引用数据成员的方法(就像msg.pose.orientation)的方法,就可以调用或者赋值相应类型的成员了.因为我们手上没有传感器,我们自己产生了double类型的变量赋值,从最底层float64 x y z之类的开始赋值,模拟机器人的运动.但其实如果一个好的定位传感器自己有ROS的接口的话,很可能直接产生geometry_msgs/Point
类型的变量,假设名字叫currentPosition
,那么我们通过msg.pose.position = currentPosition
给pose的位置赋值就可以了,因为pose.position
也是geometry_msgs/Point
类型的变量.这个大家接触具体的传感器就知道了.
那么目前我们总共聊了怎么发布string,int8,array和poseStamped.