micro_ros_arduino: Message memory allocations -- via micro_ros_utilities_create_*_message_memory() APIs -- seemingly causing data corruption (buffer overflow?)

Issue template

I am encapsulating the microros rcl_service_t object within a C++ wrapper class, and I utilize micro_ros_utilities_create_static_message_memory() (and/or micro_ros_utilities_create_message_memory()) to setup the message memory etc within the object’s constructor.

Strangely, these allocation calls seem to be corrupting the memory of contiguous instance variables after the message field.

  • Hardware description: esp32
  • RTOS: arduino
  • Installation type: git clone
  • Version or commit hash: humble

Steps to reproduce the issue

My code is a bit more complex, so I didn’t prune all that code yet. But I was able to narrow it down to the scenario described in the snippets below. It will not compile, but hoping it might provide some rough clues as a starting point. If this is insufficient and you need a more specific repro, please let me know and I’ll put one together.

Service.h

template <class RequestType, class ResponseType> 
class ServiceWrapper<RequestType, ResponseType> 
{ 
public:    
   ServiceWrapper(
         const std::string& name, 
         rcl_node_t* node, 
         rosidl_service_type_support_t * service_type_support, 
         rosidl_message_type_support_t * request_type_support, 
         rosidl_message_type_support_t * response_type_support, 
         ServiceCallback callback) 
  : name(name) {         // <------- Name argument is copied over via this member-initialization-list

       RCCHECK(rclc_service_init_default(&this->service_data, node, service_type_support, name.c_str()));

       Serial.printf("'Name: %s'\n", this->name.c_str());               // <----------- Prints is as expected

       // ~~~~~~~ TROUBLE CAUSING CODE (either or both calls) ~~~~~~~~~~~
       assert(micro_ros_utilities_create_message_memory(
                        request_type_support,
                        &this->request_msg, 
                        micro_ros_utilities_memory_conf_default));
       assert(micro_ros_utilities_create_message_memory(
                        response_type_support,
                        &this->response_msg, 
                        micro_ros_utilities_memory_conf_default));

       Serial.printf("'Name: %s'\n", this->name.c_str());              // <------------- The name variable gets corrupted by now
   }

   virtual ~ServiceWrapper() {
        ... <deallocate messages memory> ...
   }

private:
   RequestType    request_msg;    
   ResponseType  response_msg;
   std::string          name;              // <--------- Gets corrupted
   rcl_service_t     service_data; 
};

The Request/Response types should probably be something complex, such as:

ConcreteRequestType

string<=150             name
string<=64[<=20]        some_other_strings
float64[<=20]           values

ConcreteResponseType

string<=250            status

ConcreteServiceType

ConcreteRequestType          request
---
ConcreteResponseType       response

Calling code:

...
ServiceWrapper<ConcreteRequestType, ConcreteResponseType> service(
      std::string("TestName"),
      node,
      ROSIDL_GET_SVC_TYPE_SUPPORT(my_package, srv, ConcreteServiceType),
      ROSIDL_GET_MSG_TYPE_SUPPORT(my_package, msg, ConcreteRequestType),
      ROSIDL_GET_MSG_TYPE_SUPPORT(my_package, msg, ConcreteResponseType),
      some_callback
);
...

Expected behavior

The name should remain the same between the 1st and 2nd Serial.print() invocations:

Name: 'TestName'
Name: 'TestName'

Actual behavior

Name: 'TestName'
Name: ''                     <======== EMPTY STRING

Additional information

If I pad the request_msg and response_msg fields with sufficiently sized message buffers, as below:

   RequestType        request_msg;
   uint8_t            __request_overflow_buffer__[128];    <== Haven't yet investigated the precise length required.
   ResponseType       response_msg;
   uint8_t            __response_overflow_buffer__[128];   <== Haven't yet investigated the precise length required.
   std::string        name;              
   rcl_service_t      service_data;   

… the name field does not get corrupted, suggesting there is some sort of buffer overflow happening. Note that the padding lengths attempted above are arbitrary … I didn’t narrow it down to an exact amount yet, but can do so if needed.

I attempted the above allocations using both these Micro-ROS APIs:

- micro_ros_utilities_create_message_memory()
- micro_ros_utilities_create_static_message_memory() [using corresponding byte blocks for storage]

… but get the exact same behaviors above.

About this issue

  • Original URL
  • State: closed
  • Created 2 years ago
  • Comments: 16 (9 by maintainers)

Most upvoted comments

As soon as you test the PR, we will merge

Thanks @pablogs9 ! Glad the message definition helped! I will try it out shortly. Had to switch over to something else at the moment, but am looking forward to getting back to verifying this asap this week. Will post an update then.