Closed k-gupta closed 1 year ago
@k-gupta thanks for the issue. you could take a look at https://github.com/ros2/rmw_fastrtps/issues/579, especially this comment
Hey @fujitatomoya Thanks for looking into this. I had tried the suggestion from the issue you mentioned but I am seeing an error when I run it. I am just running the demo node - talker_loaned_message
. Is there something I am doing wrong? I am still pretty new to using ROS so I might be using the profiles incorrectly.
This is the error
terminate called after throwing an instance of 'eprosima::fastcdr::exception::NotEnoughMemoryException'
what(): Not enough memory in the buffer stream
The command I ran, this is running on Galactic. Also I am using the docker container not sure if that matters - ros/galactic-ros-core
FASTRTPS_DEFAULT_PROFILES_FILE=/ros/profile.xml RMW_FASTRTPS_USE_QOS_FROM_XML=1 RMW_IMPLEMENTATION=rmw_fastrtps_cpp ros2 run demo_nodes_cpp talker_loaned_message
My profile looks like this
<?xml version="1.0" encoding="UTF-8"?>
<dds xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
<profiles>
<data_writer profile_name="/chatter_pod">
<qos>
<data_sharing>
<kind>AUTOMATIC</kind>
</data_sharing>
</qos>
</data_writer>
<data_reader profile_name="/chatter_pod">
<qos>
<data_sharing>
<kind>AUTOMATIC</kind>
</data_sharing>
</qos>
</data_reader>
</profiles>
</dds>
Hi @k-gupta
The error you are seeing is to be expected the way you are configuring things, let me explain. By default, Fast DDS sets the history memory policy to PREALLOCATED
, which means that it allocates memory for a certain amount of samples of a fixed size. Since ROS 2 types tend to have unbounded sequences in them, rmw_fastrtps overrides this set with PREALLOCATED_WITH_REALLOC
, which allows Fast DDS to reallocate samples if the sequences go out of the preallocated bounds.
However, as explained here, when setting the environment variable RMW_FASTRTPS_USE_QOS_FROM_XML=1
, rmw_fastrtps does not override the history memory policy, so if a sequence goes is larger than the preallocated memory, then it cannot be de-serialized, since the setting prevents Fast DDS to reallocate the buffer. As suggested in the README.md, you can set the history memory policy in the XML as well (see this).
@k-gupta
probably you can try the following xml setting. (this works with rolling if the data is PoD.)
<?xml version="1.0" encoding="UTF-8" ?>
<profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
<!-- Default publisher profile -->
<data_writer profile_name="default publisher profile" is_default_profile="true">
<qos>
<publishMode>
<kind>SYNCHRONOUS</kind>
</publishMode>
<data_sharing>
<kind>AUTOMATIC</kind>
</data_sharing>
</qos>
<historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
</data_writer>
<data_reader profile_name="default subscription profile" is_default_profile="true">
<qos>
<data_sharing>
<kind>AUTOMATIC</kind>
</data_sharing>
</qos>
<historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
</data_reader>
</profiles>
then it cannot be de-serialized, since the setting prevents Fast DDS to reallocate the buffer.
nitpick, this means serialization since the problem is observed on publisher LoanedMessage
(stacktrace includes eprosima::fastcdr::Cdr::serialize(char const*)
).
@k-gupta
probably you can try the following xml setting. (this works with rolling if the data is PoD.)
@fujitatomoya thanks for your hints.
this configuration with ASYNCHRONOUS publisherMode also enables the datasharing
I am testing this in https://github.com/ZhenshengLee/performance_test you can see the test results in https://zhenshenglee.github.io/ros2_jetson_benchmarks/benchmark_results/galactic/pc_ros2_galactic_v5.13.0-41-generic_amd64/rmw_compare/
Thanks a lot for the info. We were able to fix this by setting the historyMemoryPolicy to PREALLOCATED_WITH_REALLOC. But we will also try to the setting you gave.
@k-gupta thanks. please close the issue once everything is confirmed and resolved.
Since Galactic is already E.O.L https://docs.ros.org/en/rolling/Releases.html, i will go ahead to close this issue.
We are trying to find an example on how to use zero copy with Fast RTPS. Is there a simple example somewhere that we can refer? We tried to use Galactic to do it but saw this error.
Currently used middleware can't loan messages. Local allocator will be used.