-
Notifications
You must be signed in to change notification settings - Fork 11
通过ROS发布里程表信息
ericwen edited this page Apr 11, 2019
·
1 revision
- 描述:本教程提供了一个发布导航堆栈里程表信息的示例。它包括在ROS上发布nav_msgs/Odometry消息,以及在tf上从“odom”坐标系转换为“base_link”坐标系。
- 教程水平:初级 原文链接
- 导航堆栈使用tf来确定机器人在世界上的位置,并将传感器数据与静态地图关联。然而,tf并没有提供关于机器人速度的任何信息。因此,导航堆栈要求任何odometry源都要在ROS上发布包含速度信息的转换和nav_msgs/ odometry消息。本教程解释了nav_msgs/Odometry消息,并提供了分别用于发布消息和在ROS和tf上转换的示例代码。
- nav_msgs/Odometry信息存储了一个机器人在自由空间的位置和速度的估计:
# This represents an estimate of a position and velocity in free space.
# The pose in this message should be specified in the coordinate frame given by header.frame_id.
# The twist in this message should be specified in the coordinate frame given by the child_frame_id
Header header
string child_frame_id
geometry_msgs/PoseWithCovariance pose
geometry_msgs/TwistWithCovariance twist
- 此消息中的位姿对应于机器人在里程表框架中的估计位置,以及用于确定该位姿估计的可选协方差。这条信息中的扭曲与机器人在子帧(通常是移动基座的坐标系)中的速度相对应,同时还有一个可选的协方差,用于确定速度估计值。
- 正如在转换配置教程中所讨论的,“tf”软件库负责管理转换树中与机器人相关的坐标系之间的关系。因此,任何里程表源都必须发布关于它所管理的坐标系的信息。下面的代码假设您对tf有基本的了解,阅读转换配置教程就足够了。
- 在本节中,我们将编写一些示例代码,用于在ROS上发布nav_msgs/Odometry消息,并使用tf对一个假机器人进行转换,该机器人只是在一个圆圈中行驶。我们将首先完整地展示代码,并在下面逐一解释。 将依赖项添加到包的manifest.xml中(译者注:只有使用roscreate-pkg方式创建包才会有manifest.xml,同时编译的时候直接执行rosmake 包名 就OK,用catkin方式是没有这个文件的)
<depend package="tf"/>
<depend package="nav_msgs"/>
- (译者注:这两句代码也可以不用写,在执行
roscreate-pkg 包名 roscpp rospy tf std_msgs nav_msgs
时,直接写在依赖上就行)
#include <ros/ros.h>
2 #include <tf/transform_broadcaster.h>
3 #include <nav_msgs/Odometry.h>
4
5 int main(int argc, char** argv){
6 ros::init(argc, argv, "odometry_publisher");
7
8 ros::NodeHandle n;
9 ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
10 tf::TransformBroadcaster odom_broadcaster;
11
12 double x = 0.0;
13 double y = 0.0;
14 double th = 0.0;
15
16 double vx = 0.1;
17 double vy = -0.1;
18 double vth = 0.1;
19
20 ros::Time current_time, last_time;
21 current_time = ros::Time::now();
22 last_time = ros::Time::now();
23
24 ros::Rate r(1.0);
25 while(n.ok()){
26
27 ros::spinOnce(); // check for incoming messages
28 current_time = ros::Time::now();
29
30 //compute odometry in a typical way given the velocities of the robot
31 double dt = (current_time - last_time).toSec();
32 double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
33 double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
34 double delta_th = vth * dt;
35
36 x += delta_x;
37 y += delta_y;
38 th += delta_th;
39
40 //since all odometry is 6DOF we'll need a quaternion created from yaw
41 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
42
43 //first, we'll publish the transform over tf
44 geometry_msgs::TransformStamped odom_trans;
45 odom_trans.header.stamp = current_time;
46 odom_trans.header.frame_id = "odom";
47 odom_trans.child_frame_id = "base_link";
48
49 odom_trans.transform.translation.x = x;
50 odom_trans.transform.translation.y = y;
51 odom_trans.transform.translation.z = 0.0;
52 odom_trans.transform.rotation = odom_quat;
53
54 //send the transform
55 odom_broadcaster.sendTransform(odom_trans);
56
57 //next, we'll publish the odometry message over ROS
58 nav_msgs::Odometry odom;
59 odom.header.stamp = current_time;
60 odom.header.frame_id = "odom";
61
62 //set the position
63 odom.pose.pose.position.x = x;
64 odom.pose.pose.position.y = y;
65 odom.pose.pose.position.z = 0.0;
66 odom.pose.pose.orientation = odom_quat;
67
68 //set the velocity
69 odom.child_frame_id = "base_link";
70 odom.twist.twist.linear.x = vx;
71 odom.twist.twist.linear.y = vy;
72 odom.twist.twist.angular.z = vth;
73
74 //publish the message
75 odom_pub.publish(odom);
76
77 last_time = current_time;
78 r.sleep();
79 }
80 }
- 好了,现在您已经有机会查看所有内容,让我们详细分析代码的重要部分。
#include <tf/transform_broadcaster.h>
#include <nav_msgs/Odometry.h>
- 因为我们将发布从“odom”坐标系到“base_link”坐标系的转换和nav_msgs/Odometry消息,所以需要包含相关的头文件。
9 ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
10 tf::TransformBroadcaster odom_broadcaster;
- 我们需要同时创建一个ros::Publisher和一个tf:: transformbroadcast,以便能够分别使用ros和tf发送消息。
12 double x = 0.0;
13 double y = 0.0;
14 double th = 0.0;
- 我们假设机器人开始于“odom”坐标系的原点。
16 double vx = 0.1;
17 double vy = -0.1;
18 double vth = 0.1;
- 这里我们将设置一些速度,使“base_link”帧在“odom”帧中以0.1m/s的速度在x方向移动,-0.1m/s在y方向移动,0.1rad/s在th方向移动。这或多或少会导致我们的假机器人在一个圆圈里行驶。
24 ros::Rate r(1.0);
- 在本例中,我们将以1Hz的速率发布里程表信息以方便内省,大多数系统都希望以更高的速率发布里程表。
30 //compute odometry in a typical way given the velocities of the robot
31 double dt = (current_time - last_time).toSec();
32 double delta_x = (vx * cos(th) - vy * sin(th)) * dt;
33 double delta_y = (vx * sin(th) + vy * cos(th)) * dt;
34 double delta_th = vth * dt;
35
36 x += delta_x;
37 y += delta_y;
38 th += delta_th;
- 在这里,我们将根据我们设置的恒定速度来更新我们的里程表信息。当然,一个真正的里程表系统将对计算出的速度进行积分。
40 //since all odometry is 6DOF we'll need a quaternion created from yaw
41 geometry_msgs::Quaternion odom_quat = tf::createQuaternionMsgFromYaw(th);
- 我们通常尝试使用系统中所有消息的3D版本,以便在适当的时候允许2D和3D组件一起工作,并将必须创建的消息数量保持在最低水平。因此,有必要将里程计的偏航值转换为要通过线路发送的四元数。幸运的是,tf提供的函数允许从偏航值轻松创建四元数,并可以轻松地从四元数访问偏航值。
43 //first, we'll publish the transform over tf
44 geometry_msgs::TransformStamped odom_trans;
45 odom_trans.header.stamp = current_time;
46 odom_trans.header.frame_id = "odom";
47 odom_trans.child_frame_id = "base_link";
- 在这里,我们将创建一个转换消息,并通过tf发送出去。我们希望在current_time发布从“odom”帧到“base_link”帧的转换。因此,我们将相应地设置消息的头部和child_frame_id,确保使用“odom”作为父坐标帧,使用“base_link”作为子坐标帧。
49 odom_trans.transform.translation.x = x;
50 odom_trans.transform.translation.y = y;
51 odom_trans.transform.translation.z = 0.0;
52 odom_trans.transform.rotation = odom_quat;
53
54 //send the transform
55 odom_broadcaster.sendTransform(odom_trans);
- 在这里,我们从里程表数据填充转换消息,然后使用transformbroadcast发送转换。
57 //next, we'll publish the odometry message over ROS
58 nav_msgs::Odometry odom;
59 odom.header.stamp = current_time;
60 odom.header.frame_id = "odom";
- 我们还需要发布nav_msgs/Odometry消息,以便导航堆栈能够从中获得速度信息。我们将把消息的头部设置为current_time和“odom”坐标系。
62 //set the position
63 odom.pose.pose.position.x = x;
64 odom.pose.pose.position.y = y;
65 odom.pose.pose.position.z = 0.0;
66 odom.pose.pose.orientation = odom_quat;
67
68 //set the velocity
69 odom.child_frame_id = "base_link";
70 odom.twist.twist.linear.x = vx;
71 odom.twist.twist.linear.y = vy;
72 odom.twist.twist.angular.z = vth;
- 这将使用里程表数据填充消息并通过网络发送出去。我们将消息的child_frame_id设置为"base_link"帧,因为这是我们发送速度信息的坐标系。
Stay hungry,stay foolish.