ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange |
1 | initial version |
This error is due to recent change in gmapping package. This can be fixed by recompiling the gmapping package as follows:
$ wget http://packages.ros.org/ros/ubuntu/pool/main/r/ros-indigo-gmapping/ros-indigo-gmapping_1.3.7.orig.tar.gz $ mkdir -p ~/catkin_ws/src $ cd ~/catkin_ws/src $ catkin_init_workspace $ tar xvf ../../ros-indigo-gmapping_1.3.7.orig.tar.gz $ mv ros-indigo-gmapping-1.3.7/ gmapping $ gedit gmapping/src/slam_gmapping.cpp
Change line 409 from: if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > FLT_EPSILON) to: if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > 0.003) // this is the value for Kinect Save and close the file. Go back to commandline:
$ cd .. $ catkin_make $ sudo cp $ sudo cp devel/lib/gmapping/slam_gmapping* /opt/ros/indigo/lib/gmapping/
This works for me.
2 | No.2 Revision |
This error is due to recent change in gmapping package. This can be fixed by modifying and recompiling the gmapping package as follows:
$ wget http://packages.ros.org/ros/ubuntu/pool/main/r/ros-indigo-gmapping/ros-indigo-gmapping_1.3.7.orig.tar.gz
$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace
$ tar xvf ../../ros-indigo-gmapping_1.3.7.orig.tar.gz
$ mv ros-indigo-gmapping-1.3.7/ gmapping
$ gedit gmapping/src/slam_gmapping.cppgmapping/src/slam_gmapping.cpp
if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) >
if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > 0.003) // this is the value for $ cd ..
$ catkin_make
$ sudo cp
$ sudo cp devel/lib/gmapping/slam_gmapping* /opt/ros/indigo/lib/gmapping//opt/ros/indigo/lib/gmapping/
3 | No.3 Revision |
This error is due to recent change in gmapping package. This can be fixed by modifying and recompiling the gmapping package as follows:
$ wget http://packages.ros.org/ros/ubuntu/pool/main/r/ros-indigo-gmapping/ros-indigo-gmapping_1.3.7.orig.tar.gz
$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace
$ tar xvf ../../ros-indigo-gmapping_1.3.7.orig.tar.gz
$ mv ros-indigo-gmapping-1.3.7/ gmapping
$ gedit gmapping/src/slam_gmapping.cpp
Change line 409 from:
if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > FLT_EPSILON)
to:
if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > 0.003) // this is the value for Kinect
Save and close the file. Go back to commandline: $ cd ..
$ catkin_make
$ sudo cp
$ sudo cp devel/lib/gmapping/slam_gmapping* /opt/ros/indigo/lib/gmapping/
This works for me. 4 | No.4 Revision |
This error is due to recent change in gmapping package. This can be fixed by modifying and recompiling the gmapping package as follows:
$ wget http://packages.ros.org/ros/ubuntu/pool/main/r/ros-indigo-gmapping/ros-indigo-gmapping_1.3.7.orig.tar.gz
$ mkdir -p ~/catkin_ws/src
$ cd ~/catkin_ws/src
$ catkin_init_workspace
$ tar xvf ../../ros-indigo-gmapping_1.3.7.orig.tar.gz
$ mv ros-indigo-gmapping-1.3.7/ gmapping
$ gedit gmapping/src/slam_gmapping.cpp
Change line 409 from:
if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > FLT_EPSILON)
to:
if (fabs(fabs(scan.angle_min) - fabs(scan.angle_max)) > 0.003) // this is the value for Kinect
Save and close the file. Go back to commandline: $ cd ..
$ catkin_make
$ sudo cp devel/lib/gmapping/slam_gmapping* /opt/ros/indigo/lib/gmapping/
This works for me.