通過ROS發(fā)布里程計信息
- 參考ROS_WIKI
導航包使用tf來確定機器人在地圖中的位置和建立傳感器數(shù)據(jù)與靜態(tài)地圖的聯(lián)系。然而tf不能提供任何關于機器人速度的信息 ,所以導航包要求任何的里程計源能通過ROS發(fā)布tf變換和包含速度信息的
nav_msgs/Odometry類型的消息。
首先需要了解消息類型nav_msgs/Odometry,該消息保存了機器人空間里評估的位置和速度信息,因此在編程時需要計算機器人當前的位置,并將機器人當期的位置以及速度信息同時更新到里程計消息中。
下面寫代碼實現(xiàn)發(fā)布里程計消息的功能,此處是人為設定速度,并且根據(jù)速度計算出位置。
#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();
}
}
這段代碼實際上做了兩件事:
- 發(fā)布當前機器人的坐標(tf坐標,便于訂閱該tf坐標系的節(jié)點來處理坐標變換--例如在第一篇教程中實現(xiàn)的
base_laser → base_link) - 發(fā)布當前機器人的速度(里程計,速度信息中包含了x,y軸方向上線速度以及角速度)
關于程序中,速度的注明:
- 速度信息是相對于機器人來說的(
base_link坐標系,不能與odom坐標系混淆),x軸方向是指向機器人前方的速度方向,y軸方向是垂直于機器人指向機器人左方的方向(右手定則)。 - 在程序中,設置的速度可以保證機器人做一個圓周運動,因為角速度不變,并且小車的線速度也不變。