-
Notifications
You must be signed in to change notification settings - Fork 118
New issue
Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.
By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.
Already on GitHub? Sign in to your account
Example using QoS from XML file error: Change payload size larger than the history payload size #764
Comments
update: on Jazzy docker image the nodes don't give the error messages, and messages are exchanged. That's promising. However, I can't manage to externally modify the chatter qos, with e.g.
I still get
Are there any unit tests I can copy off? |
You can refer to https://github.com/ros2/rmw_fastrtps/?tab=readme-ov-file#ros-2-middleware-implementation-for-eprosimas-fast-dds. I tried it under the Jazzy version and got the same result as you. I'm not sure if there's an error in my configuration file. |
After checking the code, user-defined QoS by the code will override the QoS settings read from the configuration file. rmw_fastrtps/rmw_fastrtps_cpp/src/publisher.cpp Lines 239 to 265 in 8fb05aa
template<typename DDSEntityQos>
bool fill_entity_qos_from_profile(
const rmw_qos_profile_t & qos_policies,
DDSEntityQos & entity_qos)
{
...
switch (qos_policies.durability) {
case RMW_QOS_POLICY_DURABILITY_TRANSIENT_LOCAL:
entity_qos.durability().kind = eprosima::fastdds::dds::TRANSIENT_LOCAL_DURABILITY_QOS;
break;
case RMW_QOS_POLICY_DURABILITY_VOLATILE:
entity_qos.durability().kind = eprosima::fastdds::dds::VOLATILE_DURABILITY_QOS;
break;
case RMW_QOS_POLICY_DURABILITY_SYSTEM_DEFAULT:
break;
default:
RMW_SET_ERROR_MSG("Unknown QoS durability policy");
return false;
}
switch (qos_policies.reliability) {
case RMW_QOS_POLICY_RELIABILITY_BEST_EFFORT:
entity_qos.reliability().kind = eprosima::fastdds::dds::BEST_EFFORT_RELIABILITY_QOS;
break;
case RMW_QOS_POLICY_RELIABILITY_RELIABLE:
entity_qos.reliability().kind = eprosima::fastdds::dds::RELIABLE_RELIABILITY_QOS;
break;
case RMW_QOS_POLICY_RELIABILITY_SYSTEM_DEFAULT:
break;
default:
RMW_SET_ERROR_MSG("Unknown QoS reliability policy");
return false;
}
...
} |
This is the intended behaviour and it is documented here. From that section:
Which Qos profile are you using? Mind that Fast DDS and rmw_fastrtps are two different things (rmw_fastrtps being an adapter to use Fast DDS in ROS 2). In Fast DDS, as per DDS specification, the default reliability for writers in RELIABLE, whereas the default for readers in BEST EFFORT; I believe this is the case for all DDS vendors, as that is what the DDS spec requieres. When talking about rmw_fastrtps, the Qos are received from upper layers. In ROS 2, different profiles are defined which you can see here. Furthermore, each Qos has a SYSTEM_DEFAULT possible value which tells rmw_fastrtps to not change anything an let Fast DDS set the policies. It is with this configuration that the XML values for the ROS 2 defined Qos are applied. I haven't had the chance to run an experiment now, and it's been a while since I last did it. I'd appreciate if you could set all the Qos to SYTEM_DEFAULT and see whether the XML values are taken into consideration. |
Thanks. Yes, The document describes this situation. The talker from Demo_node_cpp used rmw_qos_profile_default. static const rmw_qos_profile_t rmw_qos_profile_default =
{
RMW_QOS_POLICY_HISTORY_KEEP_LAST,
10,
RMW_QOS_POLICY_RELIABILITY_RELIABLE,
RMW_QOS_POLICY_DURABILITY_VOLATILE,
RMW_QOS_DEADLINE_DEFAULT,
RMW_QOS_LIFESPAN_DEFAULT,
RMW_QOS_POLICY_LIVELINESS_SYSTEM_DEFAULT,
RMW_QOS_LIVELINESS_LEASE_DURATION_DEFAULT,
false
}; |
@Barry-Xu-2018 There is a rmw_qos_profile_system_default (note the additional |
Thanks. Talker and listener in demo_nodes_cpp doesn't use rmw_qos_profile_system_default. So we cannot directly use them to verify QoS setting from XML configuration. @dhood |
besides, this is consistent behavior with rmw_connextdds as well. if the application allows QoS override options to be configurable, we can override the QoS as following? root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 run quality_of_service_demo_cpp qos_overrides_talker
[INFO] [1718407800.397783163] [qos_overrides_talker]: Publishing an image, sent at [1718407800.397773]
[INFO] [1718407803.377167068] [qos_overrides_talker]: Publishing an image, sent at [1718407803.377161]
...
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 topic info -v /qos_overrides_chatter
Type: sensor_msgs/msg/Image
Publisher count: 1
Node name: qos_overrides_talker
Node namespace: /
Topic type: sensor_msgs/msg/Image
Topic type hash: RIHS01_d31d41a9a4c4bc8eae9be757b0beed306564f7526c88ea6a4588fb9582527d47
Endpoint type: PUBLISHER
GID: 01.0f.f5.91.44.9d.33.ba.00.00.00.00.00.00.14.03
QoS profile:
Reliability: RELIABLE
History (Depth): UNKNOWN
Durability: VOLATILE
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
Subscription count: 0
this can be overridden, root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 run quality_of_service_demo_cpp qos_overrides_talker --ros-args --params-file ./example_qos_overrides.yaml
[INFO] [1718407788.200066890] [qos_overrides_talker]: Publishing an image, sent at [1718407788.200057]
[INFO] [1718407791.209793863] [qos_overrides_talker]: Publishing an image, sent at [1718407791.209787]
...
root@tomoyafujita:~/ros2_ws/colcon_ws# ros2 topic info -v /qos_overrides_chatter
Type: sensor_msgs/msg/Image
Publisher count: 1
Node name: qos_overrides_talker
Node namespace: /
Topic type: sensor_msgs/msg/Image
Topic type hash: RIHS01_d31d41a9a4c4bc8eae9be757b0beed306564f7526c88ea6a4588fb9582527d47
Endpoint type: PUBLISHER
GID: 01.0f.f5.91.2f.9d.e5.18.00.00.00.00.00.00.14.03
QoS profile:
Reliability: BEST_EFFORT
History (Depth): UNKNOWN
Durability: TRANSIENT_LOCAL
Lifespan: Infinite
Deadline: Infinite
Liveliness: AUTOMATIC
Liveliness lease duration: Infinite
Subscription count: 0
qos_overrides_talker: # node name
ros__parameters: # All parameters are nested in this key
qos_overrides: # Parameter group for all qos overrides
/qos_overrides_chatter: # Parameter group for the topic
publisher: # Profile for publishers in the topic
# publisher_my_id: # Profile for publishers in the topic with id="my_id"
reliability: best_effort
durability: transient_local it really depends on the application and use case. see example https://github.com/ros2/demos/tree/rolling/quality_of_service_demo#qos-overrides @dhood what do you think? btw, i think we should add some tutorial and explanation about https://github.com/ros2/demos/tree/rolling/quality_of_service_demo#qos-overrides to https://github.com/ros2/ros2_documentation |
ros2/ros2_documentation#4549 is follow-up for documentation. |
it's great that there's a demo for testing the QoS pass through, that's what should probably be referenced in the fastrtps tutorial 🙂 Additional documentation will def be useful, but my concerns and feedback are more with fastrtps docs/behaviour than ros2 docs. To clarify, I already understand that it is not supposed to work unless the System Default is explicitly set, although I bet the pointers will be useful for someone who stumbles upon this thread someday! I'll summarise the issues as I see them, because I'm not sure that they've been addressed by the thread so far:
1 combined with 3 means that I cannot change the behaviour of system-default QoS topics within moveit back to using reliable qos, which is needed for my system (and any other system using moveit + fastrtps + humble that has the same errors) The good news for 1 is that somewhere between humble and Jazzy the behaviour has been fixed, I think |
@fujitatomoya I might have missed a point you were making about QoS overrides from parameters, it's a feature I haven't seen before so I mistook it as xml overrides. Can the demo you linked be used to manipulate topics using system default qos, eg this topic inside moveit? I think it can only be used to configure nodes I've created myself with those qos_overriding_options right? It's not a builtin behaviour of general ros2 nodes that can be used to configure library behaviour? |
your understanding is true. QoS cannot be overridden via these parameters unless qos_overriding_options are configured so. (unfortunately this is something we CANNOT do at this moment, i think.) so after all, i believe there is no way to reconfigure the QoS for the node with non-system-default QoS is configured. where i can see, we got a few things to consider,
i might be missing something like history and basic concept with the current design, so i would like to hear from other developers. thanks, |
I'm compelled to answer here
Again, this is not a bug. As explained here, when setting In particular, in Humble, <profiles xmlns="http://www.eprosima.com/XMLSchemas/fastRTPS_Profiles">
<!-- Default publisher profile -->
<data_writer profile_name="default publisher profile" is_default_profile="true">
<historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
</data_writer>
<!-- Default subscriber profile -->
<data_reader profile_name="default subscriber profile" is_default_profile="true">
<historyMemoryPolicy>DYNAMIC</historyMemoryPolicy>
</data_reader>
</profiles> The most important thing here is that in order to change any Qos other than Although I understand that this is all somehow convoluted, I thing a careful read of the documentation should be enough.
I'm not sure what you mean with I think what you mean is that with that example you cannot change the ROS 2 fixed Qos, is that correct? In that case, I'd say that the ROS 2 fixed Qos is simple a subset of all the available Qos configurable through XML. In that sense the example is very much valid for configuring almost every Fast DDS Qos expect for 7 of them (the ones exposed in ROS 2).
I can partially agree with what is said here:
|
from a quick glimpse it sounds like I've missed the distinction between FASTRTPS_DEFAULT_PROFILES_FILE and RMW_FASTRTPS_USE_QOS_FROM_XML - this response looks very helpful, thanks @EduPonz Let me read in detail and get back to you 👍 |
Hi, I am not sure if my doubt / error is similar to the discussion ongoing but it the closest relevant thing I could find.
Any help would be appreciated. Kind regards, |
You are correct, they are different
How are you trying to configure things? First of all, from here
Without the XML, it is difficult to deduce what's happening. One thing that may be useful depending on the ROS 2 version you're using would be to run:
|
Bug report
Hi team-
I am unable to override the default QoS which is important to replace best effort publishers with reliable ones, anywhere that ros libraries are using system default QoS, e.g. MoveIt, ros_control....
Perhaps the tutorial is out of date or I am using the wrong one, so I will focus the bug report on the demo nodes, but changing System Default QoS is my actual goal.
FYI, the ability to do this is critical to fixing regressions in our system after changing from cyclone to fastdds, because FastDDS is the only vendor that I see with Best Effort as System Default. (Took me a while to realise this was the culprit).
Thanks in advance!
Required Info:
Ubuntu 20.04
ros:humble docker image
FastDDS
rclcpp, at least
Steps to reproduce issue
Following the tutorial from https://fast-dds.docs.eprosima.com/en/v2.6.7/fastdds/ros2/ros2_configure.html#example inside the latest ros:humble docker image with fastrtps-2.6.7 gives error outputs, and no messages are received. Setting RMW_FASTRTPS_USE_QOS_FROM_XML to 0, they communicate.
The text was updated successfully, but these errors were encountered: