ros-navigation / navigation2

ROS 2 Navigation Framework and System
https://nav2.org/
Other
2.34k stars 1.21k forks source link

heap-buffer-overflow bug caused by user misconfiguration (amcl:laser_likelihood_max_dist= -nan) #4337

Closed GoesM closed 2 months ago

GoesM commented 2 months ago

this issue is mainly for adding ticket for https://github.com/ros-navigation/navigation2/issues/4005

Bug report

Required Info:

Steps to reproduce issue

Here is our launch command:

source install/setup.bash
source /opt/ros/humble/setup.bash
export TURTLEBOT3_MODEL=waffle
export GAZEBO_MODEL_PATH=$GAZEBO_MODEL_PATH:/opt/ros/humble/share/turtlebot3_gazebo/models
ros2 launch nav2_bringup tb3_simulation_launch.py params_file:=my_nav2_params.yaml

there's only one difference between my_nav2_params.yaml and defaulted nav2_params.yaml:

#my_nav2_params.yaml
......
nav2_amcl
      ......
    laser_likelihood_max_dist: -nan
    ......

Expected behavior

no bug occurs

Actual behavior

face to the asan report:

=================================================================
==65990==ERROR: AddressSanitizer: requested allocation size 0xffffffffffffffff (0x800 after adjustments for alignment, red zones etc.) exceeds maximum supported size of 0x10000000000 (thread T11)
    #0 0x56255025c23d in operator new[](unsigned long) (/home/***/nav2_humble/install/nav2_amcl/lib/nav2_amcl/amcl+0xe923d) (BuildId: 9cab2dfb4fd0f7edff9ad0c4896458037daa0009)
    #1 0x7fa1fd4d96be in CachedDistanceMap::CachedDistanceMap(double, double) (/home/***/nav2_humble/install/nav2_amcl/lib/libmap_lib.so+0xa6be) (BuildId: dd3ddde7b007251175de34827c6f22dd7c789e0b)
    #2 0x7fa1fd4ebead in nav2_amcl::LikelihoodFieldModel::LikelihoodFieldModel(double, double, double, double, unsigned long, map_t*) (/home/***/nav2_humble/install/nav2_amcl/lib/libsensors_lib.so+0x6ead) (BuildId: a774b5c01ee612defddcf9cef0d3735ab8aecc3d)
    #3 0x7fa1fdb78dea in nav2_amcl::AmclNode::addNewScanner(int&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, std::__cxx11::basic_string<char, std::char_traits<char>, std::allocator<char> > const&, geometry_msgs::msg::PoseStamped_<std::allocator<void> >&) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x378dea) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #4 0x7fa1fdb7653f in nav2_amcl::AmclNode::laserReceived(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x37653f) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #5 0x7fa1fdd406a9 in void std::__invoke_impl<void, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), nav2_amcl::AmclNode*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&>(std::__invoke_memfun_deref, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const>), nav2_amcl::AmclNode*&, std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x5406a9) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #6 0x7fa1fdd3fe35 in message_filters::CallbackHelper1T<std::shared_ptr<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&, bool) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x53fe35) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #7 0x7fa1fdcf342b in message_filters::Signal1<sensor_msgs::msg::LaserScan_<std::allocator<void> > >::call(message_filters::MessageEvent<sensor_msgs::msg::LaserScan_<std::allocator<void> > const> const&) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x4f342b) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #8 0x7fa1fdd38790 in tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::transformReadyCallback(tf2_ros::TransformStampedFuture const&, unsigned long) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x538790) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #9 0x7fa1fdd3cc6e in std::_Function_handler<void (tf2_ros::TransformStampedFuture const&), std::_Bind<void (tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>::* (tf2_ros::MessageFilter<sensor_msgs::msg::LaserScan_<std::allocator<void> >, tf2_ros::Buffer>*, std::_Placeholder<1>, unsigned long))(tf2_ros::TransformStampedFuture const&, unsigned long)> >::_M_invoke(std::_Any_data const&, tf2_ros::TransformStampedFuture const&) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x53cc6e) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #10 0x7fa1fef62e8d  (/opt/ros/humble/lib/libtf2_ros.so+0x4fe8d) (BuildId: 5fe744f3037178d67abb96013375a405993407b9)
    #11 0x7fa1f4d51c5f  (<unknown module>)

SUMMARY: AddressSanitizer: allocation-size-too-big (/home/***/nav2_humble/install/nav2_amcl/lib/nav2_amcl/amcl+0xe923d) (BuildId: 9cab2dfb4fd0f7edff9ad0c4896458037daa0009) in operator new[](unsigned long)
Thread T11 created by T0 here:
    #0 0x56255020a7dc in __interceptor_pthread_create (/home/***/nav2_humble/install/nav2_amcl/lib/nav2_amcl/amcl+0x977dc) (BuildId: 9cab2dfb4fd0f7edff9ad0c4896458037daa0009)
    #1 0x7fa1fd2dc328 in std::thread::_M_start_thread(std::unique_ptr<std::thread::_State, std::default_delete<std::thread::_State> >, void (*)()) (/lib/x86_64-linux-gnu/libstdc++.so.6+0xdc328) (BuildId: e37fe1a879783838de78cbc8c80621fa685d58a2)
    #2 0x7fa1fdcd3359 in std::_Sp_counted_ptr_inplace<tf2_ros::TransformListener, std::allocator<tf2_ros::TransformListener>, (__gnu_cxx::_Lock_policy)2>::_Sp_counted_ptr_inplace<tf2_ros::Buffer&>(std::allocator<tf2_ros::TransformListener>, tf2_ros::Buffer&) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x4d3359) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #3 0x7fa1fdb60ad2 in nav2_amcl::AmclNode::initTransforms() (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x360ad2) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #4 0x7fa1fdb59aa9 in nav2_amcl::AmclNode::on_configure(rclcpp_lifecycle::State const&) (/home/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x359aa9) (BuildId: fcf524e51612a7063856b255b0200fa30f1c8a67)
    #5 0x7fa1fea19b8c  (/opt/ros/humble/lib/librclcpp_lifecycle.so+0x28b8c) (BuildId: 012115a5136d65f945feb1fe7a699e9903b4add1)

==65990==ABORTING

Additional information

I think we should add check for values like .nan and inf .