introlab / rtabmap_ros

RTAB-Map's ROS package.
http://wiki.ros.org/rtabmap_ros
BSD 3-Clause "New" or "Revised" License
916 stars 549 forks source link

unstable sensor message could lead rtabmap_ros DoS #1138

Open GoesM opened 3 months ago

GoesM commented 3 months ago

Bug report

Environment

Description

Considering the possibility of unstable sensor data transmission in the ROS (Robot Operating System) working network environment in real-world applications, it may be advisable to discard certain sensor information that is deemed unreasonable due to instability rather than interrupting operations, in order to prevent the occurrence of Denial of Service (DoS) phenomena.

However, I found if rtabmap_ros received such a scan-message (whose range_max is less than range_min), it would exit current work

the demo of scan-message:

range_max: 0.5
range_min: 20.0
angle_increment: 0.0174930003
angle_max: 6.28000021
angle_min: 0
scan_time: 0
time_increment: 0
header:
  frame_id: base_scan
  stamp:
    nanosec: 395000000
    sec: 0
intensities:
- 0
- 0
- 0
- ...
ranges:
- 4.63112688
- 4.60988617
- 4.54179621
- ...

what happened to rtabmap_ros: image

Suggestion

Can we opt to discard such blatantly erroneous messages instead of aborting the current task at hand?

After all, the current mechanism makes it too easy for DoS incidents to occur.

matlabbe commented 3 months ago

I am not sure if the library itself should handle the possibility of DoS attacks (or any other attacks), I would expect the messaging library/provider (here ros2) to do it and just filter those messages so that rtabmap doesn't receive them (and fatal errors like above won't happen). Saying that, I am also not an expert in cybersecurity, if the only way to protect from this kind of attacks is in the source code using these bad messages, I may learn more about it.

In normal operation, these fatal errors are used to tell the users of rtabmap library that their topics are malformed or incompatible. They should fix that on their side. We don't handle the possibility that the message itself can been compromised by third party between the publisher and the receiver. Maybe it is a flaw of ROS2 DDS. From my experience, we often decouple ROS2 ecosystem from a local network to the internet (using web services) or use a VPN to avoid exposing the ros2 nodes directly to internet.

Note also that those fatal errors can happen through other dependencies used by rtabmap, such as PCL or OpenCV. We don't catch every exceptions from all libraries. Crashing is often better to debug issues if there are some.

Other interesting related links: https://discourse.ros.org/t/cybersecurity-in-the-ros-2-communication-middleware-targeting-the-top-6-dds-implementations/23254 https://discourse.ros.org/t/how-susceptible-is-ros2-to-cyber-attacks/33847/6 https://nvd.nist.gov/vuln/detail/CVE-2023-33565 https://dergipark.org.tr/en/download/article-file/1899879 https://design.ros2.org/articles/ros2_threat_model.html

GoesM commented 3 months ago

I used to discuss the relevant issues of msg-filter with the repository administrators of rclcpp. Currently, my understanding of this code architecture is that ROS primarily addresses problems caused by information disparity and mismatched timestamps, while rarely filtering specific field values.

In my understanding, this approach is reasonable because it aims to ensure developers have various ways to use messages. For instance, when representing angles from 0 to 360 degrees, we can use the special method of min>max to express the union of angles ranging (min,360) and (0,max). Therefore, it might not be very appropriate for such filtering to be implemented at the lower levels of ROS repositories. Thus, in my view, it might be more reasonable for downstream users to handle this information filtering mechanism.

Of course, whether modifications should be made to the repository entirely depends on your thoughts. The main purpose of my proposal is also to share my findings, and if you are willing to address this issue, I am also willing to submit a PR to help refine the code. I believe such changes would be beneficial for users of open-source code who may not be very familiar with software development.

GoesM commented 3 months ago

I believe such changes would be beneficial for users of open-source code who may not be very familiar with software development.

My personal viewpoint is that, instead of abruptly terminating rtabmap's operation after encountering a fatal error, we might have better alternatives:

when such error messages are received, we could simply issue a Warning to ensure that users are aware that erroneous scan messages have occurred. At the same time, for the continued operation of our algorithm, rtabmap could choose to discard this erroneous message. Additionally, rtabmap wouldn't need to exit the current workflow, thus giving the choice of whether to exit the rtabmap process to the user:

users could choose to save the previous mapping results and exit to inspect their data issues, or they could choose to ignore such issues and continue mapping. Providing users with more options like this might potentially be more beneficial ?

matlabbe commented 2 months ago

when such error messages are received, we could simply issue a Warning to ensure that users are aware that erroneous scan messages have occurred. At the same time, for the continued operation of our algorithm, rtabmap could choose to discard this erroneous message.

We do already some checks like this in MsgConversion when converting ros messages to rtabmap's internal format. If we find something not compatible with expected format, we show an error message and skip that message (without crashing). However, we don't check all members of a message that way and we may still assert on some. Here is an example when converting RGBD data: https://github.com/introlab/rtabmap_ros/blob/665735663ef7bf029c11c599c06a1fd727299e0c/rtabmap_conversions/src/MsgConversion.cpp#L2102-L2122

We assert at some places while return false with an error message on others. Here is another example related to LaserScan fatal error you mentioned: https://github.com/introlab/rtabmap_ros/blob/665735663ef7bf029c11c599c06a1fd727299e0c/rtabmap_conversions/src/MsgConversion.cpp#L2712-L2720 Based on the underlying library, we would need to add before (naively converting asserts in if):

if(!data.empty() && data.rows != 1) {
    ROS_ERROR("Invalid scan data format");
    return false;
}
if(!data.empty() && !(data.type() == CV_8UC1 || data.type() == CV_32FC2 || data.type() == CV_32FC3 || data.type() == CV_32FC(4) || data.type() == CV_32FC(5) || data.type() == CV_32FC(6)  || data.type() == CV_32FC(7))) {
    ROS_ERROR("Invalid scan data format");
    return false;
}
if(!outputInFrameId && scanLocalTransform.isNull()) {
    ROS_ERROR("Invalid scan data format");
    return false;
}
if(angleIncrement == 0.0f) {
    ROS_ERROR("Invalid scan data format");
    return false;
}
if(scan2dMsg.range_min>scan2dMsg.range_max) {
    ROS_ERROR("Invalid scan data format");
    return false;
}
if((scan2dMsg.angleIncrement>0 && scan2dMsg.angleMax<scan2dMsg.angleMin) || (scan2dMsg.angleIncrement<0 && scan2dMsg.angleMax>scan2dMsg.angleMin)) {
    ROS_ERROR("Invalid scan data format");
    return false;
}

// No assert should happen now, unless the upstream library adds a new one in the future.
scan = rtabmap::LaserScan( 
        data, 
        format, 
        scan2dMsg.range_min, 
        scan2dMsg.range_max, 
        scan2dMsg.angle_min, 
        scan2dMsg.angle_max, 
        scan2dMsg.angle_increment, 
        outputInFrameId?rtabmap::Transform::getIdentity():scanLocalTransform);

If anybody wants to take on these changes and make a pull request, I'll be happy to review it.

GoesM commented 2 months ago

If anybody wants to take on these changes and make a pull request, I'll be happy to review it.

So happy for hearing that !

and so sorry for that I come back lately.

I've open a PR #1151 for this issue : )