ROS 主动蒙特卡罗粒子滤波定位算法 AMCL 解析-- map与odom坐标转换的方法

ROS AMCL 算法根据订阅到的地图数据配合激光扫描特征,使用粒子滤波获取最佳定位点,该点称为M(point on map), 它是相对于地图map上的坐标,也就是base_link相对map上的坐标。


odom 的原点是机器人启动时刻的位置,它在map上的位置或转换矩阵是未知的。但是AMCL可以根据最佳粒子的位置推算出 odom->map的tf转换信息并发布到 tf主题上。因为base_link->odom的tf转换信息是每时每刻都在发布的,所以它是已知的。


已知tf转换:

map->base_link

base_link->odom


下面的公式就可以推算:

map->odom = map->base_link - base_link->odom


看一下代码是怎么实现的:

      ROS_DEBUG("New pose: %6.3f %6.3f %6.3f",
               hyps[max_weight_hyp].pf_pose_mean.v[0],
               hyps[max_weight_hyp].pf_pose_mean.v[1],
               hyps[max_weight_hyp].pf_pose_mean.v[2]);

      // subtracting base to odom from map to base and send map to odom instead
      tf::Stamped<tf::Pose> odom_to_map;
      try
      {
        tf::Transform tmp_tf(tf::createQuaternionFromYaw(hyps[max_weight_hyp].pf_pose_mean.v[2]),
                             tf::Vector3(hyps[max_weight_hyp].pf_pose_mean.v[0],
                                         hyps[max_weight_hyp].pf_pose_mean.v[1],
                                         0.0));
        tf::Stamped<tf::Pose> tmp_tf_stamped (tmp_tf.inverse(),
                                              laser_scan->header.stamp,
                                              base_frame_id_);
        this->tf_->transformPose(odom_frame_id_,
                                 tmp_tf_stamped,
                                 odom_to_map);
      }
      catch(tf::TransformException)
      {
        ROS_DEBUG("Failed to subtract base to odom transform");
        return;
      }

      latest_tf_ = tf::Transform(tf::Quaternion(odom_to_map.getRotation()),
                                 tf::Point(odom_to_map.getOrigin()));
      latest_tf_valid_ = true;

      if (tf_broadcast_ == true)
      {
        // We want to send a transform that is good up until a
        // tolerance time so that odom can be used
        ros::Time transform_expiration = (laser_scan->header.stamp +
                                          transform_tolerance_);
        tf::StampedTransform tmp_tf_stamped(latest_tf_.inverse(),
                                            transform_expiration,
                                            global_frame_id_, odom_frame_id_);
        this->tfb_->sendTransform(tmp_tf_stamped);
        sent_first_transform_ = true;
      }

hyps[max_weight_hyp].pf_pose_mean.v[0], [1], [2] 就代表了Mp

第10行   tmp_tf = 从map原点看base_link的位置

第14行   tmp_tf.inverse()  = 以为Mp为原点,map原点的位置,就是在base_link坐标系下map 原点的位置

第17行   进行 base_link坐标系下的点转换到odom坐标系,也就是把map原点转换到odom坐标系下,等于从odom原点看map原点的位置。放到latest_tf_变量里面。

第37行   发布tf转换关系,latest_tf_.inverse() 得到的是从map原点看odom原点的位置,也就是 odom->map的转换关系


总结

从W的原点看A所在的位置坐标 p,就是A->W转换矩阵,称为WAT.   Ap为A坐标系的点, 它在W上的坐标  WpWAT*Ap

如果在GMapping中未找到map-odom变换(通常是地图坐标系到机器人 odom (Odometry) 坐标系的转换),你可以通过以下步骤手动创建或者从其他外部数据源获取: 1. **使用外部传感器**: - 确保你的机器人配备了提供精确 odometry 数据的传感器,如激光雷达、imu 或 wheel encoders。这些设备的数据可以用于计算 odometry 变换。 2. **数据融合**: - 如果你有多套传感器数据,可能需要将它们融合在一起,比如使用 EKF(Extended Kalman Filter)来估计 odometry 变换。ORB-SLAM 或者 LOAM 等 SLAM 系统也可以生成这样的数据。 3. **IMU预集成**: - 如果你的机器人有 IMU,你可以在 Gmapping 初始化之前先预集成一段时间的数据,这可以帮助提供 odometry 变换的初始估计。 4. **利用ROS包**: - ROS 提供了一些工具包,如 `tf`(Transform Feedback)和 `tf2_ros`,可以用来处理和广播 Odometry 变换。查看这些包的文档,了解如何发布和订阅 odometry tf 变换。 5. **手动设置**: - 如果你的机器人环境简单,你可以手工计算并硬编码 map 和 odometry 的相对位置作为静态变换。但在实际应用中,这种方法不太稳定。 一旦得到 odometry 变换,将其发布为 `/odom`话题,并在 GMapping 中配置为输入源。确保在 GMapping 的 launch 文件中指定正确的 topic 名称,例如: ```xml <node pkg="gmapping" type="gmapping" name="g_mapping" output="screen"> <remap from="scan" to="/your_laser_scan_topic"/> <remap from="initialpose" to="/initial_pose_topic"/> <param name="odom_frame_id" value="odom"/> <!-- ... --> </node> ``` 这里的`odom_frame_id`参数应设置为你已有的 odometry 关联的帧 ID。
评论 10
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

当前余额3.43前往充值 >
需支付:10.00
成就一亿技术人!
领取后你会自动成为博主和红包主的粉丝 规则
hope_wisdom
发出的红包
实付
使用余额支付
点击重新获取
扫码支付
钱包余额 0

抵扣说明:

1.余额是钱包充值的虚拟货币,按照1:1的比例进行支付金额的抵扣。
2.余额无法直接购买下载,可以购买VIP、付费专栏及课程。

余额充值