Skip to content

Undefined behavior in subscription_options.hpp #1544

@zhoulaifu

Description

@zhoulaifu

Undefined behavior is detected by running a unit test from the tf2_ros package with Undefined Behavior Sanitizer (UBSAN, https://www.kernel.org/doc/html/v4.14/dev-tools/ubsan.html). The unit test used here is tf2_ros_test_message_filter from the geometry2 package.

Tested on ros2 eloquent. The error points to /opt/ros/eloquent/include/rclcpp/subscription_options.hpp:79:62: runtime error: reference binding to null pointer of type 'struct allocator'.

Below is the full error message.

root@b49ee72fcb7b:/opt/ros_ws# ./build/tf2_ros/tf2_ros_test_message_filter
[==========] Running 3 tests from 1 test case.
[----------] Global test environment set-up.
[----------] 3 tests from tf2_ros_message_filter
[ RUN      ] tf2_ros_message_filter.construction_and_destruction
[       OK ] tf2_ros_message_filter.construction_and_destruction (20 ms)
[ RUN      ] tf2_ros_message_filter.multiple_frames_and_time_tolerance
/opt/ros/eloquent/include/rclcpp/subscription_options.hpp:79:62: runtime error: reference binding to null pointer of type 'struct allocator'
/usr/include/c++/7/bits/shared_ptr.h:707:42: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/bits/move.h:74:36: runtime error: reference binding to null pointer of type 'struct allocator'
/usr/include/c++/7/bits/shared_ptr.h:691:39: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/bits/shared_ptr.h:344:64: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/bits/shared_ptr_base.h:1295:35: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/bits/shared_ptr_base.h:638:28: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/bits/shared_ptr_base.h:526:39: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/bits/alloc_traits.h:475:4: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/ext/new_allocator.h:136:46: runtime error: reference binding to null pointer of type 'struct type'
/usr/include/c++/7/ext/new_allocator.h:136:4: runtime error: reference binding to null pointer of type 'const struct allocator'

[INFO] [tf2_ros_message_filter]: filter callback: trigger(0)
[INFO] [tf2_ros_message_filter]: filter callback: trigger(2)
[INFO] [tf2_ros_message_filter]: filter callback: trigger(2)
[INFO] [tf2_ros_message_filter]: filter callback: trigger(4)
[INFO] [tf2_ros_message_filter]: filter callback: trigger(4)
[INFO] [tf2_ros_message_filter]: filter callback: trigger(6)
[       OK ] tf2_ros_message_filter.multiple_frames_and_time_tolerance (6043 ms)
[ RUN      ] tf2_ros_message_filter.failure_reason_string_conversion
[       OK ] tf2_ros_message_filter.failure_reason_string_conversion (0 ms)
[----------] 3 tests from tf2_ros_message_filter (6063 ms total)

[----------] Global test environment tear-down
[==========] 3 tests from 1 test case ran. (6063 ms total)
[  PASSED  ] 3 tests.

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't workinghelp wantedExtra attention is needed

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions