ros2 / rclcpp

rclcpp (ROS Client Library for C++)
Apache License 2.0
514 stars 410 forks source link

`-fanalyzer` warning: possible null dereference when using TypeAdapters #2493

Closed roncapat closed 2 months ago

roncapat commented 2 months ago

Branch: iron GCC version: 11.4 OS: Ubuntu 22.04

Steps to reproduce:

build any rclcpp-dependent package using TypeAdapters with -fanalyzer flag.

See output below:

In member function ‘std::unique_ptr<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename rclcpp::detail::MessageDeleterHelper<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, AllocatorT>::Deleter> rclcpp::AnySubscriptionCallback<MessageT, AllocatorT>::convert_custom_type_to_ros_message_unique_ptr(const SubscribedType&) [with MessageT = rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >; AllocatorT = std::allocator<void>]’:
cc1plus: warning: use of possibly-NULL ‘*this.rclcpp::AnySubscriptionCallback<rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, std::allocator<void> >::ros_message_type_allocator_.__gnu_cxx::new_allocator<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >::allocate(1, 0)’ where non-null expected [CWE-690] [-Wanalyzer-possible-null-argument]
  ‘std::unique_ptr<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename rclcpp::detail::MessageDeleterHelper<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, AllocatorT>::Deleter> rclcpp::AnySubscriptionCallback<MessageT, AllocatorT>::convert_custom_type_to_ros_message_unique_ptr(const SubscribedType&) [with MessageT = rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >; AllocatorT = std::allocator<void>]’: event 1
    |
    |/home/user/ros2_iron/install/rclcpp/include/rclcpp/rclcpp/any_subscription_callback.hpp:474:3:
    |  474 |   convert_custom_type_to_ros_message_unique_ptr(const SubscribedType & msg)
    |      |   ^~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
    |      |   |
    |      |   (1) entry to ‘rclcpp::AnySubscriptionCallback<rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, std::allocator<void> >::convert_custom_type_to_ros_message_unique_ptr’
    |
  ‘std::unique_ptr<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename rclcpp::detail::MessageDeleterHelper<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, AllocatorT>::Deleter> rclcpp::AnySubscriptionCallback<MessageT, AllocatorT>::convert_custom_type_to_ros_message_unique_ptr(const SubscribedType&) [with MessageT = rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >; AllocatorT = std::allocator<void>]’: event 2
    |
    |/usr/include/c++/11/bits/alloc_traits.h:464:28:
    |  464 |       { return __a.allocate(__n); }
    |      |                ~~~~~~~~~~~~^~~~~
    |      |                            |
    |      |                            (2) calling ‘__gnu_cxx::new_allocator<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >::allocate’ from ‘rclcpp::AnySubscriptionCallback<rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, std::allocator<void> >::convert_custom_type_to_ros_message_unique_ptr’
    |
    +--> ‘_Tp* __gnu_cxx::new_allocator<_Tp>::allocate(__gnu_cxx::new_allocator<_Tp>::size_type, const void*) [with _Tp = nav_msgs::msg::OccupancyGrid_<std::allocator<void> >]’: events 3-6
           |
           |/usr/include/c++/11/ext/new_allocator.h:103:7:
           |  103 |       allocate(size_type __n, const void* = static_cast<const void*>(0))
           |      |       ^~~~~~~~
           |      |       |
           |      |       (3) entry to ‘__gnu_cxx::new_allocator<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >::allocate’
           |......
           |  111 |         if (__builtin_expect(__n > this->_M_max_size(), false))
           |      |         ~~
           |      |         |
           |      |         (4) following ‘false’ branch...
           |......
           |  127 |         return static_cast<_Tp*>(::operator new(__n * sizeof(_Tp)));
           |      |                                  ~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~~
           |      |                                                |
           |      |                                                (5) ...to here
           |      |                                                (6) this call could return NULL
           |
    <------+
    |
  ‘std::unique_ptr<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename rclcpp::detail::MessageDeleterHelper<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, AllocatorT>::Deleter> rclcpp::AnySubscriptionCallback<MessageT, AllocatorT>::convert_custom_type_to_ros_message_unique_ptr(const SubscribedType&) [with MessageT = rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >; AllocatorT = std::allocator<void>]’: event 7
    |
    |/usr/include/c++/11/bits/alloc_traits.h:464:28:
    |  464 |       { return __a.allocate(__n); }
    |      |                ~~~~~~~~~~~~^~~~~
    |      |                            |
    |      |                            (7) returning to ‘rclcpp::AnySubscriptionCallback<rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, std::allocator<void> >::convert_custom_type_to_ros_message_unique_ptr’ from ‘__gnu_cxx::new_allocator<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >::allocate’
    |
  ‘std::unique_ptr<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, typename rclcpp::detail::MessageDeleterHelper<typename rclcpp::TypeAdapter<MessageT>::ros_message_type, AllocatorT>::Deleter> rclcpp::AnySubscriptionCallback<MessageT, AllocatorT>::convert_custom_type_to_ros_message_unique_ptr(const SubscribedType&) [with MessageT = rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >; AllocatorT = std::allocator<void>]’: event 8
    |
    |cc1plus:
    | (8): argument 'this' (‘*this.rclcpp::AnySubscriptionCallback<rclcpp::TypeAdapter<StampedOccupancyGrid_CV, nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >, std::allocator<void> >::ros_message_type_allocator_.__gnu_cxx::new_allocator<nav_msgs::msg::OccupancyGrid_<std::allocator<void> > >::allocate(1, 0)’) from (6) could be NULL where non-null expected
    |
In file included from /home/user/ros2_iron/install/nav_msgs/include/nav_msgs/nav_msgs/msg/occupancy_grid.hpp:7,
                 from ---omitted---.cpp:15:
/home/user/ros2_iron/install/nav_msgs/include/nav_msgs/nav_msgs/msg/detail/occupancy_grid__struct.hpp:42:12: note: argument 'this' of ‘nav_msgs::msg::OccupancyGrid_<ContainerAllocator>::OccupancyGrid_(rosidl_runtime_cpp::MessageInitialization) [with ContainerAllocator = std::allocator<void>]’ must be non-null
   42 |   explicit OccupancyGrid_(rosidl_runtime_cpp::MessageInitialization _init = rosidl_runtime_cpp::MessageInitialization::ALL)

From what I can understand, this is due to: https://github.com/ros2/rclcpp/blob/04ea0bb00293387791522590b7347a2282cda290/rclcpp/include/rclcpp/any_subscription_callback.hpp#L452 not being checked against nullptr.

clalancette commented 2 months ago

Good find. If you'd like to open a PR to add a nullptr check and throw an exception, we'd be happy to review it. Please target the rolling branch first, then we can backport to iron and humble as necessary.

roncapat commented 2 months ago

@clalancette will do. Question for you: what could be a proper way to handle nullptr being returned? Throw an error?

clalancette commented 2 months ago

@clalancette will do. Question for you: what could be a proper way to handle nullptr being returned? Throw an error?

Yeah, I think throwing an exception here is probably the most consistent thing to do (we do that elsewhere in this file).

roncapat commented 2 months ago

C++ is not officially supported yet.

This means this could not be a bug, as std::allocator<void>::allocate() already throws std::bad_alloc.