-
Notifications
You must be signed in to change notification settings - Fork 1.5k
Closed
Description
Bug report
Required Info:
- Operating System:
- Ubuntu22.04
- ROS2 Version:
- humble
- Version or commit hash:
- the latest
- DDS implementation:
- defaulted
Steps to reproduce issue
Launch the navigation2 normally, as following steps:
#!/bin/bash
export ASAN_OPTIONS=halt_on_error=0:new_delete_type_mismatch=0:detect_leaks=0:log_pah=asan
source install/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 headless:=True use_rviz:=False use_composition:=False
Curious about how nav2 face to topic-interception, i keep sending demaged /map
msg onto topic /map
, which is like this:
ros2 topic pub /map nav_msgs/msg/OccupancyGrid "
header:
stamp:
sec: 0
nanosec: 0
frame_id: map
info:
map_load_time:
sec: 0
nanosec: 0
resolution: 0.05000000074505806
width: 384
height: 384
origin:
position:
x: -10.0
y: -10.0
z: 0.0
orientation:
x: 0.0
y: 0.0
z: 0.0
w: 1.0
data: [-1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1, -1] "
[notice] the real length of data is less than width*height
then, the asan report would occur.
Expected behavior
Actual behavior
The ASAN reporting a buffer-overflow bug to me, as following:
=================================================================
==14154==ERROR: AddressSanitizer: heap-buffer-overflow on address 0x6210000667f5 at pc 0x7b380c985c4a bp 0x7ffdb96543c0 sp 0x7ffdb96543b8
READ of size 1 at 0x6210000667f5 thread T0
#0 0x7b380c985c49 in nav2_amcl::AmclNode::convertMap(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&) (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x385c49) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#1 0x7b380c984f77 in nav2_amcl::AmclNode::handleMapMessage(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&) (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x384f77) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#2 0x7b380c984477 in nav2_amcl::AmclNode::mapReceived(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >) (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x384477) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#3 0x7b380ca7ea3e in void std::__invoke_impl<void, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >), nav2_amcl::AmclNode*&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >(std::__invoke_memfun_deref, void (nav2_amcl::AmclNode::*&)(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >), nav2_amcl::AmclNode*&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&) (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x47ea3e) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#4 0x7b380cac79b2 in auto rclcpp::AnySubscriptionCallback<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)::'lambda'(auto&&)::operator()<std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&>(auto&&) const (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x4c79b2) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#5 0x7b380cac489b in rclcpp::AnySubscriptionCallback<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> >::dispatch(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&) (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x4c489b) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#6 0x7b380ca8acac in rclcpp::Subscription<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void>, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, rclcpp::message_memory_strategy::MessageMemoryStrategy<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::allocator<void> > >::handle_message(std::shared_ptr<void>&, rclcpp::MessageInfo const&) (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x48acac) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d)
#7 0x7b380d97d7bb in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) (/opt/ros/humble/lib/librclcpp.so+0xe77bb) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
#8 0x7b380d97dfbe in rclcpp::Executor::execute_any_executable(rclcpp::AnyExecutable&) (/opt/ros/humble/lib/librclcpp.so+0xe7fbe) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
#9 0x7b380d9858af in rclcpp::executors::SingleThreadedExecutor::spin() (/opt/ros/humble/lib/librclcpp.so+0xef8af) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
#10 0x7b380d985ac4 in rclcpp::spin(std::shared_ptr<rclcpp::node_interfaces::NodeBaseInterface>) (/opt/ros/humble/lib/librclcpp.so+0xefac4) (BuildId: 4cca8a387f3c93d38a0567a8efc7cba9106f5d9a)
#11 0x5cf6d6474975 in main (/***/nav2_humble/install/nav2_amcl/lib/nav2_amcl/amcl+0xeb975) (BuildId: 9cab2dfb4fd0f7edff9ad0c4896458037daa0009)
#12 0x7b380bc29d8f in __libc_start_call_main csu/../sysdeps/nptl/libc_start_call_main.h:58:16
#13 0x7b380bc29e3f in __libc_start_main csu/../csu/libc-start.c:392:3
#14 0x5cf6d63b4514 in _start (/***/nav2_humble/install/nav2_amcl/lib/nav2_amcl/amcl+0x2b514) (BuildId: 9cab2dfb4fd0f7edff9ad0c4896458037daa0009)
0x6210000667f5 is located 0 bytes to the right of 4853-byte region [0x621000065500,0x6210000667f5)
allocated by thread T0 here:
#0 0x5cf6d647212d in operator new(unsigned long) (/***/nav2_humble/install/nav2_amcl/lib/nav2_amcl/amcl+0xe912d) (BuildId: 9cab2dfb4fd0f7edff9ad0c4896458037daa0009)
#1 0x7b380dc73fb9 in nav_msgs::msg::typesupport_fastrtps_cpp::cdr_deserialize(eprosima::fastcdr::Cdr&, nav_msgs::msg::OccupancyGrid_<std::allocator<void> >&) (/opt/ros/humble/lib/libnav_msgs__rosidl_typesupport_fastrtps_cpp.so+0x8fb9) (BuildId: d9989f748e1c94c608a4bedd7dfd0f7db1970877)
#2 0x7f0000000000 (<unknown module>)
SUMMARY: AddressSanitizer: heap-buffer-overflow (/***/nav2_humble/install/nav2_amcl/lib/libamcl_core.so+0x385c49) (BuildId: 093c184d6356ee01ad4bd31576c7ab18775c096d) in nav2_amcl::AmclNode::convertMap(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)
Shadow bytes around the buggy address:
0x0c4280004ca0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0x0c4280004cb0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0x0c4280004cc0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0x0c4280004cd0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
0x0c4280004ce0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00 00
=>0x0c4280004cf0: 00 00 00 00 00 00 00 00 00 00 00 00 00 00[05]fa
0x0c4280004d00: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
0x0c4280004d10: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
0x0c4280004d20: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
0x0c4280004d30: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
0x0c4280004d40: fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa fa
Shadow byte legend (one shadow byte represents 8 application bytes):
Addressable: 00
Partially addressable: 01 02 03 04 05 06 07
Heap left redzone: fa
Freed heap region: fd
Stack left redzone: f1
Stack mid redzone: f2
Stack right redzone: f3
Stack after return: f5
Stack use after scope: f8
Global redzone: f9
Global init order: f6
Poisoned by user: f7
Container overflow: fc
Array cookie: ac
Intra object redzone: bb
ASan internal: fe
Left alloca redzone: ca
Right alloca redzone: cb
==14154==ABORTING
Additional information
code analysis:
in function AmclNode::convertMap()
the for
use the size_x*size_y
as the boundary of the vector map_msg.data
// Convert to player format
for (int i = 0; i < map->size_x * map->size_y; i++) {
if (map_msg.data[i] == 0) {
map->cells[i].occ_state = -1;
} else if (map_msg.data[i] == 100) {
map->cells[i].occ_state = +1;
} else {
map->cells[i].occ_state = 0;
}
}
however, the real length of the vector map_msg.data
is up to the user's command which may be less than size_x*size_y
thus, it would bring a buffer-overflow because out of the boundary of the vector.
Metadata
Metadata
Assignees
Labels
No labels