writer:lIcht email:lIcht.gzl@gmail.com date: 2019.11.24
最近在ros小车底层通讯搭建的时候遇到了问题:小车无法获取实际的里程计,但是需要迫切的搭建tf树来构建上层通讯架构。所以需要一个假的里程计信息来使上层工具包能正常跑起来。
解决思路:由于小车的地盘最终是要根据move_base发出的cmd_vel命令消息对速度进行控制,所以想到由此cmd_vel速度消息直接得到里程计信息(不根据实际的轮速反馈),实现发布/odom主题的发布以及/odom坐标到/base_footprint坐标的tf转换。
fake_odom.cpp:
xxxxxxxxxx
float vx;
float vy;
float vth;
void callback(const geometry_msgs::Twist& vel)
{
float linear_scale = 1.06;
vx = (vel.linear.x/1200) * linear_scale;
vy = (vel.linear.y/1200) * linear_scale;
vth = (vel.angular.z/1200);
}
int main(int argc, char** argv){
ros::init(argc, argv, "odometry_publisher");
float x = 0.0;
float y = 0.0;
float th = 0.0;
ros::NodeHandle n;
ros::Publisher odom_pub = n.advertise<nav_msgs::Odometry>("odom", 50);
//订阅cmd_vel速度指令主题,并进入回调函数处理
ros::Subscriber velocity = n.subscribe("cmd_vel", 50, callback);
tf::TransformBroadcaster odom_broadcaster;
ros::Time current_time, last_time;
current_time = ros::Time::now();
last_time = ros::Time::now();
ros::Rate r(10);
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_footprint";
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_footprint";
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();
}
}
cmd_vel消息数据格式:
xxxxxxxxxx
rostopic pub /mobile_base_controller/cmd_vel geometry_msgs/Twist:
//可看作结构体 linear和angular为<vector>类型,x,y,z为float类型
linear:
x: 0.5
y: 0.0
z: 0.0
angular:
x: 0.0
y: 0.0
z: 0.0
假里程计信息配合雷达信息跑gmapping SLAM的效果(能正常建图与维护动态tf):