Open tschoepping opened 2 years ago
+1
this issue happend very early, see https://answers.ros.org/question/322950/messagepoolmemorystrategy-initialization-fails-with-sensor_msgsmsgimu, I also wonder to known if it is a design limit for memory management?
Seems that it isn't a bug.
Refer to the description of class MessagePoolMemoryStrategy, it said "Templating allows the program to determine the memory required for this object at compile time.".
For the message with non-fixed size, it cannot determine required memory at compile time. So message type is checked by rosidl_generator_traits::has_fixed_size
.
As @Barry-Xu-2018 this, seems to be by design for use with fixed-sized messages.
That said, I think part of the problem here is that when C++ templates fail to compile, it can be hard to figure out why. One possible way to improve this is to remove the std::enable_if
part of the template, and instead make the check for a fixed-size message a static_assert
. That should give us more control over the message, and make it easier for users to figure out why it is failing. That said, we haven't actually tried this out to see if it is feasible, so someone would need to do that.
Orthogonally but related, many of the core ROS 2 messages use std_msg/msg/Header
, which includes an unbounded string for the frame_id
. That means that many of the core ROS 2 messages probably can't be used with the MesasgePollMemoryStrategy
. It may be worthwhile to investigate whether we could make that a bounded string, and whether that would allow more messages to be used with this strategy.
Bug report
Required Info:
Steps to reproduce issue
Try to refer to the
rclcpp::strategies::message_pool_memory_strategy::MessagePoolMemoryStrategy<MessageT, Size, >
type with template argumentMessageT
being a type with non-fixed size. For instance, define a message type inBytes.msg
:Then use this type for the memory strategy:
Expected behavior
The code should compile.
Actual behavior
Compilation fails with error:
Additional information
When checking the class definition of
MessagePoolMemoryStrategy
the issue becomes apparent:The issue is caused by the way how
template< bool B, class T = void > struct enable_if
is used here. The resulting struct only has a membertype
ifB
istrue
. Otherwise, no membertype
is generated and as result, accessing::type
is invalid. So wheneverrosidl_generator_traits::has_fixed_size<MessageT>::value
evaluates tofalse
, compilation of will fail, since the code always tries to access thetype
, no matter what.A fix might look like this (not yet tested!):
Ideally the message pool should be scaled in a way to satisfy an upper bound for the size of individual messages. Unfortunately, I don't see how this can be achieved with the current API.
Disclaimer
I am not an experienced ROS(2) user. I just tried to implement some benchmarks in a real-time environment. Maybe the short answer to this issue is "RTFM", but I could barely find more documentation than the real-time examples provided with ROS2 and the according tutorials in the docs and since the code causing the compilation error is in fact flawed, I decided to submit this as an issue.