通过ROS发布里程计信息
- 参考ROS_WIKI
导航包使用tf来确定机器人在地图中的位置和建立传感器数据与静态地图的联系。然而tf不能提供任何关于机器人速度的信息 ,所以导航包要求任何的里程计源能通过ROS发布tf变换和包含速度信息的
nav_msgs/Odometry
类型的消息。
首先需要了解消息类型nav_msgs/Odometry
,该消息保存了机器人空间里评估的位置和速度信息,因此在编程时需要计算机器人当前的位置,并将机器人当期的位置以及速度信息同时更新到里程计消息中。
下面写代码实现发布里程计消息的功能,此处是人为设定速度,并且根据速度计算出位置。
#include <ros/ros.h>
#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();
}
}
这段代码实际上做了两件事:
- 发布当前机器人的坐标(tf坐标,便于订阅该tf坐标系的节点来处理坐标变换--例如在第一篇教程中实现的
base_laser → base_link
) - 发布当前机器人的速度(里程计,速度信息中包含了x,y轴方向上线速度以及角速度)
关于程序中,速度的注明:
- 速度信息是相对于机器人来说的(
base_link
坐标系,不能与odom
坐标系混淆),x轴方向是指向机器人前方的速度方向,y轴方向是垂直于机器人指向机器人左方的方向(右手定则)。 - 在程序中,设置的速度可以保证机器人做一个圆周运动,因为角速度不变,并且小车的线速度也不变。