Description
I observed a reproducible heap-use-after-free in PointCloudOctomapUpdater when OccupancyMapMonitor::stopMonitor() is called while PointCloud2 messages are being dispatched under a MultiThreadedExecutor.
The race appears to be between:
- a PointCloud2 subscription callback executing through
message_filters::Subscriber::cb() -> message_filters::Signal1::call(), and
- another executor callback calling
OccupancyMapMonitor::stopMonitor() -> PointCloudOctomapUpdater::stop() -> PointCloudOctomapUpdater::stopHelper(), which destroys the same message_filters::Subscriber.
In the ASan trace, the read occurs in message_filters::Signal1::call() while accessing the callback helper vector. The same object is freed through message_filters::Subscriber::~Subscriber(), called from PointCloudOctomapUpdater::stopHelper().
This looks like a callback teardown/lifetime race: stopHelper() tears down the subscriber/filter objects without waiting for already-dispatched subscription callbacks to finish.
ROS Distro
Humble
OS and version
Ubuntu 22.04
Source or binary build?
Source
If binary, which release version?
No response
If source, which branch?
No response
Which RMW are you using?
CycloneDDS
Steps to Reproduce
-
Build MoveIt2 Humble from source with AddressSanitizer enabled.
-
Configure an OccupancyMapMonitor with occupancy_map_monitor/PointCloudOctomapUpdater and a valid PointCloud2 input topic.
-
Run a reproducer node that:
- creates an
OccupancyMapMonitor,
- starts the monitor,
- publishes valid
sensor_msgs::msg::PointCloud2 messages on the configured topic,
- periodically calls
stopMonitor() and startMonitor() from another callback,
- runs under
rclcpp::executors::MultiThreadedExecutor.
-
Use a point cloud frame that matches the octomap target frame so that the message filter dispatches the callback.
-
Run the reproducer under ASan.
In my test, a high-frequency stop/start stress configuration reliably reproduced the heap-use-after-free with CycloneDDS. The main evidence is the clean ASan heap-use-after-free in message_filters::Signal1::call().
Expected behavior
Stopping the occupancy map monitor should safely tear down the PointCloud2 subscriber/filter objects.
PointCloudOctomapUpdater::stop() / stopHelper() should not destroy message_filters::Subscriber while an already-dispatched subscription callback is still using it.
Actual behavior
ASan reports a heap-use-after-free.
One executor worker is executing the PointCloud2 callback dispatch path:
message_filters::Subscriber::cb()
message_filters::SimpleFilter::signalMessage()
message_filters::Signal1::call()
At the same time, another executor worker calls:
OccupancyMapMonitor::stopMonitor()
PointCloudOctomapUpdater::stop()
PointCloudOctomapUpdater::stopHelper()
message_filters::Subscriber::~Subscriber()
The read happens in Signal1::call() while accessing the callback helper vector. The same message_filters::Subscriber object was freed by PointCloudOctomapUpdater::stopHelper().
Backtrace or Console output
==255184==ERROR: AddressSanitizer: heap-use-after-free on address 0x517000021f38
#1 message_filters::Signal1<sensor_msgs::msg::PointCloud2>::call(...)
/opt/ros/humble/include/message_filters/message_filters/signal1.h:111
#3 message_filters::Subscriber<sensor_msgs::msg::PointCloud2, rclcpp::Node>::cb(...)
/opt/ros/humble/include/message_filters/message_filters/subscriber.h:349
#4 message_filters::Subscriber<sensor_msgs::msg::PointCloud2, rclcpp::Node>::subscribe(...)::{lambda(...)#1}::operator()(...)
/opt/ros/humble/include/message_filters/message_filters/subscriber.h:288
freed by:
#1 message_filters::Subscriber<sensor_msgs::msg::PointCloud2, rclcpp::Node>::~Subscriber()
/opt/ros/humble/include/message_filters/message_filters/subscriber.h:208
#2 occupancy_map_monitor::PointCloudOctomapUpdater::stopHelper()
/home/a/moveit/src/moveit2/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp:147
#3 occupancy_map_monitor::PointCloudOctomapUpdater::stop()
/home/a/moveit/src/moveit2/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp:152
allocated by:
#1 occupancy_map_monitor::PointCloudOctomapUpdater::start()
/home/a/moveit/src/moveit2/moveit_ros/perception/pointcloud_octomap_updater/src/pointcloud_octomap_updater.cpp:126
SUMMARY: AddressSanitizer: heap-use-after-free
/usr/include/c++/11/bits/stl_vector.h:919
in std::vector<std::shared_ptr<message_filters::CallbackHelper1<sensor_msgs::msg::PointCloud2>>>::size() const
Description
I observed a reproducible heap-use-after-free in
PointCloudOctomapUpdaterwhenOccupancyMapMonitor::stopMonitor()is called while PointCloud2 messages are being dispatched under aMultiThreadedExecutor.The race appears to be between:
message_filters::Subscriber::cb()->message_filters::Signal1::call(), andOccupancyMapMonitor::stopMonitor()->PointCloudOctomapUpdater::stop()->PointCloudOctomapUpdater::stopHelper(), which destroys the samemessage_filters::Subscriber.In the ASan trace, the read occurs in
message_filters::Signal1::call()while accessing the callback helper vector. The same object is freed throughmessage_filters::Subscriber::~Subscriber(), called fromPointCloudOctomapUpdater::stopHelper().This looks like a callback teardown/lifetime race:
stopHelper()tears down the subscriber/filter objects without waiting for already-dispatched subscription callbacks to finish.ROS Distro
Humble
OS and version
Ubuntu 22.04
Source or binary build?
Source
If binary, which release version?
No response
If source, which branch?
No response
Which RMW are you using?
CycloneDDS
Steps to Reproduce
Build MoveIt2 Humble from source with AddressSanitizer enabled.
Configure an
OccupancyMapMonitorwithoccupancy_map_monitor/PointCloudOctomapUpdaterand a valid PointCloud2 input topic.Run a reproducer node that:
OccupancyMapMonitor,sensor_msgs::msg::PointCloud2messages on the configured topic,stopMonitor()andstartMonitor()from another callback,rclcpp::executors::MultiThreadedExecutor.Use a point cloud frame that matches the octomap target frame so that the message filter dispatches the callback.
Run the reproducer under ASan.
In my test, a high-frequency stop/start stress configuration reliably reproduced the heap-use-after-free with CycloneDDS. The main evidence is the clean ASan heap-use-after-free in
message_filters::Signal1::call().Expected behavior
Stopping the occupancy map monitor should safely tear down the PointCloud2 subscriber/filter objects.
PointCloudOctomapUpdater::stop()/stopHelper()should not destroymessage_filters::Subscriberwhile an already-dispatched subscription callback is still using it.Actual behavior
ASan reports a heap-use-after-free.
One executor worker is executing the PointCloud2 callback dispatch path:
message_filters::Subscriber::cb()message_filters::SimpleFilter::signalMessage()message_filters::Signal1::call()At the same time, another executor worker calls:
OccupancyMapMonitor::stopMonitor()PointCloudOctomapUpdater::stop()PointCloudOctomapUpdater::stopHelper()message_filters::Subscriber::~Subscriber()The read happens in
Signal1::call()while accessing the callback helper vector. The samemessage_filters::Subscriberobject was freed byPointCloudOctomapUpdater::stopHelper().Backtrace or Console output