Skip to content

Validate Message Fields in Subscriptions for Sane & Well Populated Values #5610

@r0s4ngeles

Description

@r0s4ngeles

Security Summary

  • Severity

    • High (DoS / OOM from unauthenticated publisher)
  • Impact

    • Process OOM → Potential node crash → Robot control outage
  • Exploitability

    • Unauthenticated publisher on /map topic can trigger. (local network/remote depending on ROS network config)
    • Exploitable over local network/remote depending on ROS network config.
  • Suggested fix (short)

    • Add 64-bit checked multiplication.
    • Add reasonable max dims (e.g. MAX_MAP_CELLS = 100M).
    • Reject messages failing checks.
  • Patch preview / sample diff

    • Include minimal code snippet

      constexpr size_t MAX_MAP_CELLS = 100'000'000;
      constexpr uint32_t MAX_MAP_DIMENSION = 32768;
      
      // Use 64-bit arithmetic to prevent overflow
      uint64_t total_cells = static_cast<uint64_t>(width) * static_cast<uint64_t>(height);
      if (total_cells > MAX_MAP_CELLS || width > MAX_MAP_DIMENSION || height > MAX_MAP_DIMENSION) {
        RCLCPP_ERROR(get_logger(), "Map size exceeds limits");
        return nullptr;
      }
  • Tests added

    • Include unit/integration test that publishes oversized map and asserts node rejects instead of crash.
  • Labels

    • security, bug, needs-backport (if backport to release branches), urgent

Bug report

Required Info:

  • Operating System:
    • Ubuntu 22.04
  • ROS2 Version:
    • ROS2 Humble
  • Version or commit hash:
  • DDS implementation:
    • Fast DDS (rmw_fastrtps_cpp)

Steps to reproduce issue

  1. Build nav2_amcl with AddressSanitizer enabled for easier detection

  2. Run amcl node:

    ros2 run nav2_amcl amcl --ros-args -p use_sim_time:=false
  3. Configure and activate the node:

    ros2 lifecycle set /amcl configure
    ros2 lifecycle set /amcl activate
  4. Publish a malformed map message with large dimensions:

    ros2 topic pub --once /map nav_msgs/msg/OccupancyGrid "
    header:
      stamp:
        sec: 0
        nanosec: 0
      frame_id: map
    info:
      map_load_time:
        sec: 0
        nanosec: 0
      resolution: 0.05
      width: 65536
      height: 65536
      origin:
        position:
          x: 0.0
          y: 0.0
          z: 0.0
        orientation:
          x: 0.0
          y: 0.0
          z: 0.0
          w: 1.0
    data: []
    "

Expected behavior

The node should validate the map message and reject it with an appropriate error message when:

  • The dimensions would cause integer overflow during size calculations
  • The data array size doesn't match the declared width × height
  • The requested memory allocation is unreasonably large

Actual behavior

The amcl node crashes with an AddressSanitizer out-of-memory error:

=================================================================
==297928==ERROR: AddressSanitizer: allocator is out of memory trying to allocate 0x1000000000 bytes
    #0 0x7781406b4887 in __interceptor_malloc ../../../../src/libsanitizer/asan/asan_malloc_linux.cpp:145
    #1 0x77813eb2a490 in nav2_amcl::AmclNode::convertMap(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&) /home/test/ros2_ws/navigation2/nav2_amcl/src/amcl_node.cpp:1462
    #2 0x77813eb34360 in nav2_amcl::AmclNode::handleMapMessage(nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&) /home/test/ros2_ws/navigation2/nav2_amcl/src/amcl_node.cpp:1412
    #3 0x77813eb35031 in nav2_amcl::AmclNode::mapReceived(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >) /home/test/ros2_ws/navigation2/nav2_amcl/src/amcl_node.cpp:1390
    #4 0x77813ebbadb5 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> > >&&) /usr/include/c++/11/bits/invoke.h:74
    #5 0x77813ebbadb5 in std::__invoke_result<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> > > >::type std::__invoke<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> > > >(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> > >&&) /usr/include/c++/11/bits/invoke.h:96
    #6 0x77813ebbadb5 in void std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>::__call<void, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&, 0ul, 1ul>(std::tuple<std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&>&&, std::_Index_tuple<0ul, 1ul>) /usr/include/c++/11/functional:420
    #7 0x77813ebbadb5 in void std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>::operator()<std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, void>(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&) /usr/include/c++/11/functional:503
    #8 0x77813ebbadb5 in void std::__invoke_impl<void, std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >(std::__invoke_other, std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&) /usr/include/c++/11/bits/invoke.h:61
    #9 0x77813ebbadb5 in std::enable_if<is_invocable_r_v<void, std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, void>::type std::__invoke_r<void, std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >(std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&) /usr/include/c++/11/bits/invoke.h:111
    #10 0x77813ebbadb5 in std::_Function_handler<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >), std::_Bind<void (nav2_amcl::AmclNode::*(nav2_amcl::AmclNode*, std::_Placeholder<1>))(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)> >::_M_invoke(std::_Any_data const&, std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >&&) /usr/include/c++/11/bits/std_function.h:290
    #11 0x77813ebc6dd5 in std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>::operator()(std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >) const /usr/include/c++/11/bits/std_function.h:590
    #12 0x77813ebc6dd5 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:1&&)#1}::operator()<std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&>(std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&) const /opt/ros/humble/include/rclcpp/rclcpp/any_subscription_callback.hpp:556
    #13 0x77813ebc6dd5 in void std::__invoke_impl<void, 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:1&&)#1}, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&>(std::__invoke_other, 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:1&&)#1}&&, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&) /usr/include/c++/11/bits/invoke.h:61
    #14 0x77813ebc6dd5 in std::__invoke_result<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:1&&)#1}, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&>::type std::__invoke<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:1&&)#1}, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&>(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:1&&)#1}&&, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>&) /usr/include/c++/11/bits/invoke.h:96
    #15 0x77813ebc6dd5 in std::__detail::__variant::__gen_vtable_impl<std::__detail::__variant::_Multi_array<std::__detail::__variant::__deduce_visit_result<void> (*)(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:1&&)#1}&&, std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&)>, std::integer_sequence<unsigned long, 16ul> >::__visit_invoke(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:1&&)#1}&&, std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&) /usr/include/c++/11/variant:1016
    #16 0x77813ed664d5 in decltype(auto) std::__do_visit<std::__detail::__variant::__deduce_visit_result<void>, 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:1&&)#1}, std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&>(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:1&&)#1}&&, std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&) /usr/include/c++/11/variant:1727
    #17 0x77813ed664d5 in std::invoke_result<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:1&&)#1}, std::conditional<is_lvalue_reference_v<std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&>, std::variant_alternative<0ul, std::remove_reference<decltype (__as((declval<std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&>)()))>::type>::type&, std::variant_alternative<0ul, std::remove_reference<decltype (__as((declval<std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const>, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage const> const&, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >)>, std::function<void (std::shared_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, rclcpp::MessageInfo const&)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>)>, std::function<void (std::shared_ptr<rclcpp::SerializedMessage>, rclcpp::MessageInfo const&)> >&>)()))>::type>::type&&>::type>::type std::visit<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:1&&)#1}, std::variant<std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&)>, std::function<void (nav_msgs::msg::OccupancyGrid_<std::allocator<void> > const&, rclcpp::MessageInfo const&)>, std::function<void (rclcpp::SerializedMessage const&)>, std::function<void (rclcpp::SerializedMessage const&, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >)>, std::function<void (std::unique_ptr<nav_msgs::msg::OccupancyGrid_<std::allocator<void> >, std::default_delete<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > > >, rclcpp::MessageInfo const&)>, std::function<void (std::unique_ptr<rclcpp::SerializedMessage, std::default_delete<rclcpp::SerializedMessage> >)>, std::function<void (std::unique_ptr<rclcpp::S
    #18 0x77813ed664d5 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&) /opt/ros/humble/include/rclcpp/rclcpp/any_subscription_callback.hpp:504
    #19 0x77813ed664d5 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&) /opt/ros/humble/include/rclcpp/rclcpp/subscription.hpp:345
    #20 0x77813f9e8cbb in rclcpp::Executor::execute_subscription(std::shared_ptr<rclcpp::SubscriptionBase>) (/opt/ros/humble/lib/librclcpp.so+0xe7cbb)
    #21 0x186c1cc1d96aa3dc  (<unknown module>)

==297928==HINT: if you don't care about these errors you may set allocator_may_return_null=1
SUMMARY: AddressSanitizer: out-of-memory ../../../../src/libsanitizer/asan/asan_malloc_linux.cpp:145 in __interceptor_malloc
==297928==ABORTING

The node attempts to allocate 68.7 GB (0x1000000000 bytes) of memory and crashes.

Root Cause Analysis

Vulnerability Location: nav2_amcl/src/amcl_node.cpp:1462 in AmclNode::convertMap()

Attack Surface: The /map topic subscriber (nav_msgs::msg::OccupancyGrid)

Issue Details:

  1. Integer Overflow in Validation: When width = 65536 and height = 65536, the multiplication width × height overflows to 0 in 32-bit arithmetic:

    65536 × 65536 = 4,294,967,296 = 0x100000000 (overflows to 0 in uint32_t)
    
  2. Validation Bypass: The nav2_util::validateMsg() check passes because the overflow makes it appear that data.size() == 0 matches the expected size.

  3. Unsafe Memory Allocation: In convertMap(), the values are used directly without bounds checking:

       map->cells = reinterpret_cast<map_cell_t *>(
           malloc(sizeof(map_cell_t) * map->size_x * map->size_y));

Since sizeof(map_cell_t) = 16 bytes, this attempts to allocate:

16 × 65536 × 65536 = 68,719,476,736 bytes (64 GB)

Code Flow:

mapReceived() 
  → validateMsg() [passes due to overflow]
  → handleMapMessage()
    → convertMap()
      → malloc() [crashes with OOM]

Additional information

Metadata

Metadata

Assignees

No one assigned

    Labels

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions