摘要: 原创博客:转载请表明出处:http://www.cnblogs.com/zxouxuewei/
一。ROS使用tf来决定机器人的位置和静态地图中的传感器数据,但是tf中没有机器人的速度信息,所以导航功能包要求机器人 能够通过里程计信息源发布包含速度信息的里程计nav_msgs/Odometry 消息。 本篇将介绍nav_msgs/Odometry消息,并且通过代码实现消息的发布,以及tf树的变换。这里使用一个简单的例程,实现 nav_msgs/Odometry消息的发布和tf变换,通过伪造的数据,实现机器人圆周运动。
1.1.首先在你得ros工作空间中新建功能包,包含以下库:
catkin_create_pkg odom_tf_package std_msgs rospy roscpp sensor_msgs tf nav_msgs
1.2.在odom_tf_package/src下创建TF变换的代码文件:
touch odom_tf_node.cpp
源码如下:(建议初学者必须认真阅读代码,搞清所发布的话题上的消息和消息类型等)
#include <tf/transform_broadcaster.h> #include <nav_msgs/Odometry.h> int main(int argc, char** argv) { ros::init(argc, argv, "odometry_publisher"); ros::NodeHandle n; ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50); tf::TransformBroadcaster odom_broadcaster; double x = 0.0; double y = 0.0; double th = 0.0; double vx = 0.1; double vy = -0.1; double vth = 0.1; ros::Time current_time, last_time; current_time = ros::Time::now(); last_time = ros::Time::now(); ros::Rate r(1.0); while(n.ok()) { ros::spinOnce(); // check for incoming messages current_time = ros::Time::now(); //compute odometry in a typical way given the velocities of the robot double dt = (current_time - last_time).toSec(); double delta_x = (vx * cos(th) - vy * sin(th)) * dt; double delta_y = (vx * sin(th) + vy * cos(th)) * dt; double delta_th = vth * dt; x += delta_x; y += delta_y; th += delta_th; //since all odometry is 6DOF we'll need a quaternion created from yaw geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th); //first, we'll publish the transform over tf geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = current_time; odom_trans.header.frame_id = "odom"; odom_trans.child_frame_id = "base_link"; odom_trans.transform.translation.x = x; odom_trans.transform.translation.y = y; odom_trans.transform.translation.z = 0.0; odom_trans.transform.rotation = odom_quat; //send the transform odom_broadcaster.sendTransform(odom_trans); //next, we'll publish the odometry message over ROS nav_msgs::Odometry odom; odom.header.stamp = current_time; odom.header.frame_id = "odom"; //set the position odom.pose.pose.position.x = x; odom.pose.pose.position.y = y; odom.pose.pose.position.z = 0.0; odom.pose.pose.orientation = odom_quat; //set the velocity odom.child_frame_id = "base_link"; odom.twist.twist.linear.x = vx; odom.twist.twist.linear.y = vy; odom.twist.twist.angular.z = vth; //publish the message odom_pub.publish(odom); last_time = current_time; r.sleep(); } }
下面来剖析代码进行分析:
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
我们需要实现“odom”参考系到“base_link”参考系的变换,以及nav_msgs/Odometry消息的发布,所以首先需要包含相关的头文件。
ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50); tf::TransformBroadcaster odom_broadcaster;
定义一个消息发布者来发布“odom”消息,在定义一个tf广播,来发布tf变换信息。
double x = 0.0; double y = 0.0; double th = 0.0;
默认机器人的起始位置是odom参考系下的0点。
double vx = 0.1; double vy = -0.1; double vth = 0.1;
我们设置机器人的默认前进速度,让机器人的base_link参考系在odom参考系下以x轴方向0.1m/s,Y轴速度-0.1m/s,角速度0.1rad/s的状态移动,这种状态下,可以让机器人保持圆周运动。
ros::Rate r(1.0);
使用1Hz的频率发布odom消息,当然,在实际系统中,往往需要更快的速度进行发布。
//compute odometry in a typical way given the velocities of the robot double dt = (current_time - last_time).toSec(); double delta_x = (vx * cos(th) - vy * sin(th)) * dt; double delta_y = (vx * sin(th) + vy * cos(th)) * dt; double delta_th = vth * dt; x += delta_x; y += delta_y; th += delta_th;
使用我们设置的速度信息,来计算并更新里程计的信息,包括单位时间内机器人在x轴、y轴的坐标变化和角度的变化。在实际系统中,需要更具里程计的实际信息进行更新。
//since all odometry is 6DOF we'll need a quaternion created from yaw geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
为了兼容二维和三维的功能包,让消息结构更加通用,里程计的偏航角需要转换成四元数才能发布,辛运的是,ROS为我们提供了偏航角与四元数相互转换的功能。
//first, we'll publish the transform over tf geometry_msgs::TransformStamped odom_trans; odom_trans.header.stamp = current_time; odom_trans.header.frame_id = "odom"; odom_trans.child_frame_id = "base_link";
创建一个tf发布需要使用的TransformStamped类型消息,然后根据消息结构填充当前的时间戳、参考系id、子参考系id,注意两个参考系的id必须要是“odom”和“base_link”。
odom_trans.transform.translation.x = x; odom_trans.transform.translation.y = y; odom_trans.transform.translation.z = 0.0; odom_trans.transform.rotation = odom_quat;
填充里程计信息,然后发布tf变换的消息。
//next, we'll publish the odometry message over ROS nav_msgs::Odometry odom; odom.header.stamp = current_time;
我们还要发布nav_msgs/Odometry消息,让导航包获取机器人的速度。创建消息变量,然后填充时间戳。
//set the position odom.pose.pose.position.x = x; odom.pose.pose.position.y = y; odom.pose.pose.position.z = 0.0; odom.pose.pose.orientation = odom_quat; //set the velocity odom.child_frame_id = "base_link"; odom.twist.twist.linear.x = vx; odom.twist.twist.linear.y = vy; odom.twist.twist.angular.z = vth;
填充机器人的位置、速度,然后发布消息。注意,我们发布的是机器人本体的信息,所以参考系需要填"base_link"。
1.3.编译源码:在odom_tf_package/CMakeLists.txt添加编译选项:
add_executable(odom_tf_node src/odom_tf_node.cpp)
target_link_libraries(odom_tf_node ${catkin_LIBRARIES}
返回到你的工作空间的顶层目录下:
catkin_make
二。 在导航过程中,传感器的信息至关重要,这些传感器可以是激光雷达、摄像机、声纳、红外线、碰撞开关,但是归根结底,导航功能包要求机器人必须发布sensor_msgs/LaserScan或sensor_msgs/PointCloud格式的传感器信息,本篇将详细介绍如何使用代码发布所需要的消息。无论是 sensor_msgs/LaserScan,还是sensor_msgs/PointCloud ,都和ROS中tf帧信息等时间相关的消息一样,带标准格式的头信息。
#Standard metadata for higher-level flow data types #sequence ID: consecutively increasing ID uint32 seq #Two-integer timestamp that is expressed as: # * stamp.secs: seconds (stamp_secs) since epoch # * stamp.nsecs: nanoseconds since stamp_secs # time-handling sugar is provided by the client library time stamp #Frame this data is associated with # 0: no frame # 1: global frame string frame_id
以上是标准头信息的主要部分。seq是消息的顺序标识,不需要手动设置,发布节点在发布消息时,会自动累加。stamp 是消息中与数据相关联的时间戳,例如激光数据中,时间戳对应激光数据的采集时间点。frame_id 是消息中与数据相关联的参考系id,例如在在激光数据中,frame_id对应激光数据采集的参考系。
2.1.如何发布点云数据。
点云消息的结构
#This message holds a collection of 3d points, plus optional additional information about each point. #Each Point32 should be interpreted as a 3d point in the frame given in the header Header header geometry_msgs/Point32[] points #Array of 3d points ChannelFloat32[] channels #Each channel should have the same number of elements as points array, and the data in each channel should correspond 1:1 with each point
如上所示,点云消息的结构支持存储三维环境的点阵列,而且channels参数中,可以设置这些点云相关的数据,例如可以设置一个强度通道,存储每个点的数据强度,还可以设置一个系数通道,存储每个点的反射系数,等等。
2.2.通过代码发布点云数据
.在odom_tf_package/src下创建TF变换的代码文件:
touch point_kinect_node.cpp
源代码如下:
#include "ros/ros.h" #include <sensor_msgs/PointCloud.h> int main(int argc, char** argv) { ros::init(argc, argv, "point_cloud_publisher"); ros::NodeHandle n; ros::Publisher cloud_pub = n.advertise<sensor_msgs::PointCloud>("cloud", 50); unsigned int num_points = 100; int count = 0; ros::Rate r(1.0); while(n.ok()) { sensor_msgs::PointCloud cloud; cloud.header.stamp = ros::Time::now(); cloud.header.frame_id = "sensor_frame"; cloud.points.resize(num_points); //we'll also add an intensity channel to the cloud cloud.channels.resize(1); cloud.channels[0].name = "intensities"; cloud.channels[0].values.resize(num_points); //generate some fake data for our point cloud for(unsigned int i = 0; i < num_points; ++i) { cloud.points[i].x = 1 + count; cloud.points[i].y = 2 + count; cloud.points[i].z = 3 + count; cloud.channels[0].values[i] = 100 + count; } cloud_pub.publish(cloud); ++count; r.sleep(); } }
分解代码来分析:
#include <sensor_msgs/PointCloud.h>
首先也是要包含sensor_msgs/PointCloud消息结构。
ros::Publisher cloud_pub = n.advertise<sensor_msgs::PointCloud>("cloud", 50);
定义一个发布点云消息的发布者。
sensor_msgs::PointCloud cloud; cloud.header.stamp = ros::Time::now(); cloud.header.frame_id = "sensor_frame";
为点云消息填充头信息,包括时间戳和相关的参考系id。
cloud.points.resize(num_points);
设置存储点云数据的空间大小。
//we'll also add an intensity channel to the cloud cloud.channels.resize(1); cloud.channels[0].name = "intensities"; cloud.channels[0].values.resize(num_points);
设置一个名为“intensity“的强度通道,并且设置存储每个点强度信息的空间大小。
//generate some fake data for our point cloud for(unsigned int i = 0; i < num_points; ++i){ cloud.points[i].x = 1 + count; cloud.points[i].y = 2 + count; cloud.points[i].z = 3 + count; cloud.channels[0].values[i] = 100 + count;
将我们伪造的数据填充到点云消息结构当中。
cloud_pub.publish(cloud);
最后,发布点云数据。
2.3.编译源码:在odom_tf_package/CMakeLists.txt添加编译选项:
add_executable(point_kinect_node src/point_kinect_node.cpp)
target_link_libraries(point_kinect_node ${catkin_LIBRARIES}
返回到你的工作空间的顶层目录下:
catkin_make
三:测试代码:
roscore
rosrun odom_tf_package odom_tf_node
rosrun odom_tf_package point_kinect_node
rviz
3.1.rviz视图如下:tf变换和机器人移动信息.
3.2.查看发布的点云数据。
rostopic echo /cloud