rf2o_laser_odometry

https://github.com/MAPIRlab/rf2o_laser_odometry 

<launch>

  <node pkg="rf2o_laser_odometry" type="rf2o_laser_odometry_node" name="rf2o_laser_odometry" output="screen">
    <param name="laser_scan_topic" value="scan"/>        # topic where the lidar scans are being published
    <param name="odom_topic" value="odom_rf2o" />              # topic where tu publish the odometry estimations
    <param name="publish_tf" value="true" />                   # wheter or not to publish the tf::transform (base->odom)
    <param name="base_frame_id" value="base_link"/>            # frame_id (tf) of the mobile robot base. A tf transform from the laser_frame to the base_frame is mandatory
    <param name="odom_frame_id" value="odom" />                # frame_id (tf) to publish the odometry estimations    
    <param name="init_pose_from_topic" value="" /> # (Odom topic) Leave empty to start at point (0,0)
    <param name="freq" value="5.0"/>                            # Execution frequency.
    <param name="verbose" value="true" />                       # verbose
  </node>
  
</launch>

解决([rf2o] ERROR: Eigensolver couldn't find a solution. Pose is not updated) 如果激光扫描数据包含+/- Inf和/或NaNs,则无法计算odom协方差且没有任何反应 

https://github.com/artivis/rf2o_laser_odometry/commit/ae010765627e0446930599e3376a45ecaea2b422

@@ -292,7 +292,7 @@ void CLaserOdometry2D::createImagePyramid()
        //Inner pixels
        if ((u>1)&&(u<cols_i-2))
        {
          --  if (dcenter > 0.f)
          ++  if (std::isfinite(dcenter) && dcenter > 0.f)
          {
            float sum = 0.f;
            float weight = 0.f;
 @@ -316,7 +316,7 @@ void CLaserOdometry2D::createImagePyramid()
        //Boundary
        else
        {
          --  if (dcenter > 0.f)
          ++  if (std::isfinite(dcenter) && dcenter > 0.f)
          {
            float sum = 0.f;
            float weight = 0.f;

 

  • 3
    点赞
  • 11
    收藏
    觉得还不错? 一键收藏
  • 0
    评论

“相关推荐”对你有帮助么?

  • 非常没帮助
  • 没帮助
  • 一般
  • 有帮助
  • 非常有帮助
提交
评论
添加红包

请填写红包祝福语或标题

红包个数最小为10个

红包金额最低5元

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

抵扣说明:

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

余额充值