https://github.com/MAPIRlab/rf2o_laser_odometry
# topic where the lidar scans are being published# topic where tu publish the odometry estimations# wheter or not to publish the tf::transform (base->odom)# frame_id (tf) of the mobile robot base. A tf transform from the laser_frame to the base_frame is mandatory# frame_id (tf) to publish the odometry estimations # (Odom topic) Leave empty to start at point (0,0)# Execution frequency.# verbose
解决([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 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;
【rf2o_laser_odometry】