Robotics StackExchange | Archived questions

Turtlebot gmapping demo crashes with low-end CPUs

Update:

It turns out that the problem has something to do with the instruction set available on the CPU. The exact same setup (booting from the same iso) works fine on a Core i7-3820, but dies on a Celeron 847. I suspect that the issue is similar to the Fuerte bug described here: https://github.com/ros-perception/perception_pcl/issues/10 . If anyone can suggest a workaround (that doesn't involve recompiling PCL across an entire teaching lab worth of machines), I would appreciate it.

Running the move_base node in gdb gives:

Program received signal SIGILL, Illegal instruction.
0x00007ffff35c9d3f in std::vector<double, std::allocator<double> >::_M_insert_aux(__gnu_cxx::__normal_iterator<double*, std::vector<double, std::allocator<double> > >, double const&) () from /usr/lib/libpcl_common.so.1.7

And valgrind shows the following:

vex amd64->IR: unhandled instruction bytes: 0xC5 0xFB 0x10 0x2 0xC5 0xFB 0x11 0x0
==16678== valgrind: Unrecognised instruction at address 0x944fd3f.
==16678==    at 0x944FD3F: std::vector<double, std::allocator<double> >::_M_insert_aux(__gnu_cxx::__normal_iterator<double*, std::vector<double, std::allocator<double> > >, double const&) (in /usr/lib/libpcl_common.so.1.7.0)
==16678==    by 0x1927C2AD: std::vector<double, std::allocator<double> >::push_back(double const&) (in /opt/ros/hydro/lib/libtrajectory_planner_ros.so)
==16678==    by 0x1928B2B2: base_local_planner::TrajectoryPlannerROS::loadYVels(ros::NodeHandle) (in /opt/ros/hydro/lib/libtrajectory_planner_ros.so)
==16678==    by 0x19289D89: base_local_planner::TrajectoryPlannerROS::initialize(std::string, tf::TransformListener*, costmap_2d::Costmap2DROS*) (in /opt/ros/hydro/lib/libtrajectory_planner_ros.so)
==16678==    by 0x4F567DA: move_base::MoveBase::MoveBase(tf::TransformListener&) (in /opt/ros/hydro/lib/libmove_base.so)
==16678==    by 0x40780B: main (in /opt/ros/hydro/lib/move_base/move_base)
==16678== Your program just tried to execute an instruction that Valgrind
==16678== did not recognise.  There are two possible reasons for this.
==16678== 1. Your program has a bug and erroneously jumped to a non-code
==16678==    location.  If you are running Memcheck and you just saw a
==16678==    warning about a bad jump, it's probably your program's fault.
==16678== 2. The instruction is legitimate but Valgrind doesn't handle it,
==16678==    i.e. it's Valgrind's fault.  If you think this is the case or
==16678==    you are not sure, please let us know and we'll try to fix it.
==16678== Either way, Valgrind will now raise a SIGILL signal which will
==16678== probably kill your program.
==16678== 
==16678== Process terminating with default action of signal 4 (SIGILL)
==16678==  Illegal opcode at address 0x944FD3F
==16678==    at 0x944FD3F: std::vector<double, std::allocator<double> >::_M_insert_aux(__gnu_cxx::__normal_iterator<double*, std::vector<double, std::allocator<double> > >, double const&) (in /usr/lib/libpcl_common.so.1.7.0)
==16678==    by 0x1927C2AD: std::vector<double, std::allocator<double> >::push_back(double const&) (in /opt/ros/hydro/lib/libtrajectory_planner_ros.so)
==16678==    by 0x1928B2B2: base_local_planner::TrajectoryPlannerROS::loadYVels(ros::NodeHandle) (in /opt/ros/hydro/lib/libtrajectory_planner_ros.so)
==16678==    by 0x19289D89: base_local_planner::TrajectoryPlannerROS::initialize(std::string, tf::TransformListener*, costmap_2d::Costmap2DROS*) (in /opt/ros/hydro/lib/libtrajectory_planner_ros.so)
==16678==    by 0x4F567DA: move_base::MoveBase::MoveBase(tf::TransformListener&) (in /opt/ros/hydro/lib/libmove_base.so)
==16678==    by 0x40780B: main (in /opt/ros/hydro/lib/move_base/move_base)
==16678== 

Original Post:

When I run:

roslaunch turtlebot_navigation gmapping_demo.launch

move_base dies without any helpful diagnostic information. I've tested this on multiple computers under Mint 14 (Ubuntu 12.10) and seen the same problem on each. The demo works fine when I use a different machine running Hydro on Mint 13 (Ubuntu 12.04), so it may be some interaction between the navigation stack and the Linux distribution? Here is the complete terminal output.

$ roslaunch turtlebot_navigation gmapping_demo.launch 
... logging to /home/robot/.ros/log/abb42a9a-7896-11e3-b523-dc85de8a135c/roslaunch-turtlebot-02-2742.log
Checking log directory for disk usage. This may take awhile.
Press Ctrl-C to interrupt
Done checking log file disk usage. Usage is <1GB.

started roslaunch server http://turtlebot-02:33427/

SUMMARY
========

PARAMETERS
 * /camera/camera_nodelet_manager/num_worker_threads
 * /camera/depth_registered_rectify_depth/interpolation
 * /camera/disparity_depth/max_range
 * /camera/disparity_depth/min_range
 * /camera/disparity_registered_hw/max_range
 * /camera/disparity_registered_hw/min_range
 * /camera/disparity_registered_sw/max_range
 * /camera/disparity_registered_sw/min_range
 * /camera/driver/depth_camera_info_url
 * /camera/driver/depth_frame_id
 * /camera/driver/depth_registration
 * /camera/driver/device_id
 * /camera/driver/rgb_camera_info_url
 * /camera/driver/rgb_frame_id
 * /depthimage_to_laserscan/output_frame_id
 * /depthimage_to_laserscan/range_min
 * /depthimage_to_laserscan/scan_height
 * /move_base/TrajectoryPlannerROS/acc_lim_theta
 * /move_base/TrajectoryPlannerROS/acc_lim_x
 * /move_base/TrajectoryPlannerROS/acc_lim_y
 * /move_base/TrajectoryPlannerROS/dwa
 * /move_base/TrajectoryPlannerROS/gdist_scale
 * /move_base/TrajectoryPlannerROS/heading_lookahead
 * /move_base/TrajectoryPlannerROS/holonomic_robot
 * /move_base/TrajectoryPlannerROS/max_vel_theta
 * /move_base/TrajectoryPlannerROS/max_vel_x
 * /move_base/TrajectoryPlannerROS/max_vel_y
 * /move_base/TrajectoryPlannerROS/meter_scoring
 * /move_base/TrajectoryPlannerROS/min_in_place_vel_theta
 * /move_base/TrajectoryPlannerROS/min_vel_theta
 * /move_base/TrajectoryPlannerROS/min_vel_x
 * /move_base/TrajectoryPlannerROS/min_vel_y
 * /move_base/TrajectoryPlannerROS/occdist_scale
 * /move_base/TrajectoryPlannerROS/oscillation_reset_dist
 * /move_base/TrajectoryPlannerROS/pdist_scale
 * /move_base/TrajectoryPlannerROS/sim_time
 * /move_base/TrajectoryPlannerROS/vtheta_samples
 * /move_base/TrajectoryPlannerROS/vx_samples
 * /move_base/TrajectoryPlannerROS/vy_samples
 * /move_base/TrajectoryPlannerROS/xy_goal_tolerance
 * /move_base/TrajectoryPlannerROS/yaw_goal_tolerance
 * /move_base/controller_frequency
 * /move_base/controller_patience
 * /move_base/global_costmap/bump/clearing
 * /move_base/global_costmap/bump/data_type
 * /move_base/global_costmap/bump/marking
 * /move_base/global_costmap/bump/max_obstacle_height
 * /move_base/global_costmap/bump/min_obstacle_height
 * /move_base/global_costmap/bump/topic
 * /move_base/global_costmap/global_frame
 * /move_base/global_costmap/inflation_radius
 * /move_base/global_costmap/map_type
 * /move_base/global_costmap/max_obstacle_height
 * /move_base/global_costmap/observation_sources
 * /move_base/global_costmap/obstacle_range
 * /move_base/global_costmap/origin_z
 * /move_base/global_costmap/publish_frequency
 * /move_base/global_costmap/publish_voxel_map
 * /move_base/global_costmap/raytrace_range
 * /move_base/global_costmap/robot_base_frame
 * /move_base/global_costmap/robot_radius
 * /move_base/global_costmap/scan/clearing
 * /move_base/global_costmap/scan/data_type
 * /move_base/global_costmap/scan/marking
 * /move_base/global_costmap/scan/max_obstacle_height
 * /move_base/global_costmap/scan/min_obstacle_height
 * /move_base/global_costmap/scan/topic
 * /move_base/global_costmap/static_map
 * /move_base/global_costmap/transform_tolerance
 * /move_base/global_costmap/update_frequency
 * /move_base/global_costmap/z_resolution
 * /move_base/global_costmap/z_voxels
 * /move_base/local_costmap/bump/clearing
 * /move_base/local_costmap/bump/data_type
 * /move_base/local_costmap/bump/marking
 * /move_base/local_costmap/bump/max_obstacle_height
 * /move_base/local_costmap/bump/min_obstacle_height
 * /move_base/local_costmap/bump/topic
 * /move_base/local_costmap/global_frame
 * /move_base/local_costmap/height
 * /move_base/local_costmap/inflation_radius
 * /move_base/local_costmap/map_type
 * /move_base/local_costmap/max_obstacle_height
 * /move_base/local_costmap/observation_sources
 * /move_base/local_costmap/obstacle_range
 * /move_base/local_costmap/origin_z
 * /move_base/local_costmap/publish_frequency
 * /move_base/local_costmap/publish_voxel_map
 * /move_base/local_costmap/raytrace_range
 * /move_base/local_costmap/resolution
 * /move_base/local_costmap/robot_base_frame
 * /move_base/local_costmap/robot_radius
 * /move_base/local_costmap/rolling_window
 * /move_base/local_costmap/scan/clearing
 * /move_base/local_costmap/scan/data_type
 * /move_base/local_costmap/scan/marking
 * /move_base/local_costmap/scan/max_obstacle_height
 * /move_base/local_costmap/scan/min_obstacle_height
 * /move_base/local_costmap/scan/topic
 * /move_base/local_costmap/static_map
 * /move_base/local_costmap/transform_tolerance
 * /move_base/local_costmap/update_frequency
 * /move_base/local_costmap/width
 * /move_base/local_costmap/z_resolution
 * /move_base/local_costmap/z_voxels
 * /move_base/oscillation_distance
 * /move_base/oscillation_timeout
 * /move_base/planner_frequency
 * /move_base/planner_patience
 * /move_base/shutdown_costmaps
 * /navigation_velocity_smoother/accel_lim_v
 * /navigation_velocity_smoother/accel_lim_w
 * /navigation_velocity_smoother/decel_factor
 * /navigation_velocity_smoother/frequency
 * /navigation_velocity_smoother/robot_feedback
 * /navigation_velocity_smoother/speed_lim_v
 * /navigation_velocity_smoother/speed_lim_w
 * /rosdistro
 * /rosversion
 * /slam_gmapping/angularUpdate
 * /slam_gmapping/astep
 * /slam_gmapping/base_frame
 * /slam_gmapping/delta
 * /slam_gmapping/iterations
 * /slam_gmapping/kernelSize
 * /slam_gmapping/lasamplerange
 * /slam_gmapping/lasamplestep
 * /slam_gmapping/linearUpdate
 * /slam_gmapping/llsamplerange
 * /slam_gmapping/llsamplestep
 * /slam_gmapping/lsigma
 * /slam_gmapping/lskip
 * /slam_gmapping/lstep
 * /slam_gmapping/map_update_interval
 * /slam_gmapping/maxRange
 * /slam_gmapping/maxUrange
 * /slam_gmapping/odom_frame
 * /slam_gmapping/ogain
 * /slam_gmapping/particles
 * /slam_gmapping/resampleThreshold
 * /slam_gmapping/sigma
 * /slam_gmapping/srr
 * /slam_gmapping/srt
 * /slam_gmapping/str
 * /slam_gmapping/stt
 * /slam_gmapping/temporalUpdate
 * /slam_gmapping/xmax
 * /slam_gmapping/xmin
 * /slam_gmapping/ymax
 * /slam_gmapping/ymin

NODES
  /camera/
    camera_nodelet_manager (nodelet/nodelet)
    depth_registered_rectify_depth (nodelet/nodelet)
    disparity_depth (nodelet/nodelet)
    disparity_registered_hw (nodelet/nodelet)
    disparity_registered_sw (nodelet/nodelet)
    driver (nodelet/nodelet)
    points_xyzrgb_hw_registered (nodelet/nodelet)
    points_xyzrgb_sw_registered (nodelet/nodelet)
    rectify_ir (nodelet/nodelet)
    register_depth_rgb (nodelet/nodelet)
  /
    depthimage_to_laserscan (nodelet/nodelet)
    kobuki_safety_controller (nodelet/nodelet)
    move_base (move_base/move_base)
    navigation_velocity_smoother (nodelet/nodelet)
    slam_gmapping (gmapping/slam_gmapping)

ROS_MASTER_URI=http://localhost:11311

core service [/rosout] found
process[camera/camera_nodelet_manager-1]: started with pid [2760]
[ INFO] [1389207474.144268425]: Initializing nodelet with 4 worker threads.
process[camera/driver-2]: started with pid [2797]
process[camera/rectify_ir-3]: started with pid [2814]
process[camera/register_depth_rgb-4]: started with pid [2829]
process[camera/points_xyzrgb_sw_registered-5]: started with pid [2844]
process[camera/depth_registered_rectify_depth-6]: started with pid [2859]
process[camera/points_xyzrgb_hw_registered-7]: started with pid [2874]
process[camera/disparity_depth-8]: started with pid [2893]
process[camera/disparity_registered_sw-9]: started with pid [2908]
process[camera/disparity_registered_hw-10]: started with pid [2923]
process[depthimage_to_laserscan-11]: started with pid [2938]
process[slam_gmapping-12]: started with pid [2953]
process[navigation_velocity_smoother-13]: started with pid [2975]
process[kobuki_safety_controller-14]: started with pid [3026]
process[move_base-15]: started with pid [3062]
[ INFO] [1389207476.852824770]: Number devices connected: 1
[ INFO] [1389207476.853918997]: 1. device on bus 002:07 is a SensorV2 (2ae) from PrimeSense (45e) with serial id '0000000000000000'
[ INFO] [1389207476.856372911]: Searching for device with index = 1
[ INFO] [1389207476.935964737]: Opened 'SensorV2' on bus 2:7 with serial number '0000000000000000'
[ INFO] [1389207477.236540336]: Loading from pre-hydro parameter style
[ INFO] [1389207477.369059244]: Using plugin "static_layer"
[ INFO] [1389207477.775912568]: Requesting the map...
[ INFO] [1389207478.461705149]: rgb_frame_id = '/camera_rgb_optical_frame' 
[ INFO] [1389207478.461988281]: depth_frame_id = '/camera_depth_optical_frame' 
[ WARN] [1389207478.476965331]: Camera calibration file /home/robot/.ros/camera_info/rgb_0000000000000000.yaml not found.
[ WARN] [1389207478.477381533]: Using default parameters for RGB camera calibration.
[ WARN] [1389207478.478390942]: Camera calibration file /home/robot/.ros/camera_info/depth_0000000000000000.yaml not found.
[ WARN] [1389207478.478703552]: Using default parameters for IR camera calibration.
[ INFO] [1389207485.066389499]: Laser is mounted upwards.
 -maxUrange 6 -maxUrange 8 -sigma     0.05 -kernelSize 1 -lstep 0.05 -lobsGain 3 -astep 0.05
 -srr 0.01 -srt 0.02 -str 0.01 -stt 0.02
 -linearUpdate 0.5 -angularUpdate 0.436 -resampleThreshold 0.5
 -xmin -1 -xmax 1 -ymin -1 -ymax 1 -delta 0.05 -particles 80
[ INFO] [1389207485.072083075]: Initialization complete
update frame 0
update ld=0 ad=0
Laser Pose= -0.087 0.0125 0
m_count 0
Registering First Scan
[ INFO] [1389207485.181133033]: Resizing costmap to 256 X 32 at 0.050000 m/pix
[ INFO] [1389207485.280308439]: Received a 256 X 32 map at 0.050000 m/pix
[ INFO] [1389207485.298528443]: Using plugin "obstacle_layer"
[ INFO] [1389207485.332207172]:     Subscribed to Topics: scan bump
[ INFO] [1389207485.556044953]: Using plugin "footprint_layer"
[ INFO] [1389207485.593022419]: Using plugin "inflation_layer"
[ INFO] [1389207486.117514263]: Loading from pre-hydro parameter style
[ INFO] [1389207486.254861852]: Using plugin "obstacle_layer"
[ INFO] [1389207486.392414463]:     Subscribed to Topics: scan bump
[ INFO] [1389207486.591112920]: Using plugin "footprint_layer"
[ INFO] [1389207486.612346810]: Using plugin "inflation_layer"
[ INFO] [1389207487.073399902]: Created local_planner base_local_planner/TrajectoryPlannerROS
[ INFO] [1389207487.140448816]: Sim period is set to 0.20
[move_base-15] process has died [pid 3062, exit code -4, cmd /opt/ros/hydro/lib/move_base/move_base cmd_vel:=navigation_velocity_smoother/raw_cmd_vel odom:=odom __name:=move_base __log:=/home/robot/.ros/log/abb42a9a-7896-11e3-b523-dc85de8a135c/move_base-15.log].
log file: /home/robot/.ros/log/abb42a9a-7896-11e3-b523-dc85de8a135c/move_base-15*.log

Asked by nsprague on 2014-01-08 08:11:02 UTC

Comments

Answers