Skip to content
This repository has been archived by the owner on Jun 21, 2023. It is now read-only.

Fix default QoS settings for services #100

Merged
merged 1 commit into from
Sep 20, 2015
Merged

Conversation

jacquelinekay
Copy link
Contributor

Connects to #96

See ros2/rmw_opensplice/pull/82 for description.

@jacquelinekay jacquelinekay added the in progress Actively being worked on (Kanban column) label Sep 9, 2015
@jacquelinekay jacquelinekay self-assigned this Sep 10, 2015
@jacquelinekay jacquelinekay added in review Waiting for review (Kanban column) and removed in progress Actively being worked on (Kanban column) labels Sep 10, 2015
@jacquelinekay jacquelinekay removed their assignment Sep 10, 2015
@dirk-thomas
Copy link
Member

I am not sure about the changes since the pub / sub equivalent of the code does something different (especially after #88):

Just from reading these two code parts it looks to me (on a first look) that they are contradicting each other.

I know this is not directly related to this PR but since this PR adds similar stuff for the services as for pub/sub I think those should be similar (or even the same).

@jacquelinekay
Copy link
Contributor Author

I'm not sure what you mean when you say these sections of code contradict each other.

These are the three differences I see:

  1. The QoS configuration code for publishers sets the policy for a DataWriter object. The equivalent for subscriptions sets the policy for a DataReader object. The equivalent for services and clients sets both a DataReader and a DataWriter, because both clients and services have a DataReader and DataWriter object.
  2. The service/client code casts the history policy depth as a DDS_Long, while the pub/sub code does not do any casting. I can take this out for the sake of similarity as I don't think it's required.
  3. The service/client code sets the durability policy to TRANSIENT_LOCAL. I can also take this out for the sake of similarity, though I need to confirm first that it's not needed to fix the bug.

@dirk-thomas
Copy link
Member

The first code block sets the history depth of the writer to the requested value unconditionally (if RMW_QOS_POLICY_DEPTH_SYSTEM_DEFAULT was not requested).

The second block increases the history of the reader to the requested queue size.

The two logics are significantly different in behavior and I think they should be considered to to the same conceptional thing instead. Currently the resulting behavior is not obvious and different for readers and writers.

@@ -934,6 +934,47 @@ rmw_create_client(
goto fail;
}

// For now, use the default QoS profile for services.
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I'd move this code to create_requester (in srv__type_support.cpp.template), pass a rmw_qos_profile_t to rmw_create_client and default it to rmw_qos_profile_services_default.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Alright, I'll make the necessary changes here and to rmw and rmw_opensplice. I'll leave the work to propagating the QoS profile to rclcpp until after this set gets merged, if that's ok.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

No problem, we can split work and I can deal with rclcpp if you're ok with that.

@jacquelinekay
Copy link
Contributor Author

Oh, I see, Dirk is talking about lines 269-282 (create_publisher) and 599-612 (create_subscription).

https://github.com/ros2/rmw_connext/blob/master/rmw_connext_cpp/src/functions.cpp#L269

https://github.com/ros2/rmw_connext/blob/master/rmw_connext_cpp/src/functions.cpp#L599

It looks to me like the existing behavior is the same for readers and writers, and I need to change my initialization of the service/client readers and writers to match. I'm still not sure why the "ensure history depth is at least the requested size" block is needed though; why isn't the first part (lines 265-267) sufficient?

@dirk-thomas
Copy link
Member

I was not referring to any difference between create_publisher and create_subscription. I was referring to the logic how the history depth of the data reader and writer is set.
For one value the code overrides the configuration from the xml - for the other the configuration can override the value specified in the code. I think we need to unify that and come up with a clear documentation / rational why we do it that way.

@wjwwood
Copy link
Member

wjwwood commented Sep 15, 2015

Is this discrepancy covered by ros2/rmw#13?

@esteve
Copy link
Member

esteve commented Sep 16, 2015

I've rebased on top of master and ran the tests in gtest-parameters several times on Linux and it seems any issues are now gone, clients are no longer stuck waiting for a response from servers.

@jacquelinekay
Copy link
Contributor Author

Regarding the discussion about how depth is set: can we table the discussion for now and merge these PRs, since they fix several issues with parameters and services?

DDS_DataWriterQos datawriter_qos;

if (!get_datareader_qos(participant, datareader_qos)) {
RMW_SET_ERROR_MSG("Unable to initialize datareader QoS");
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It looks like these error messages are being overwritten afterwards if the function return NULL.

@wjwwood
Copy link
Member

wjwwood commented Sep 17, 2015

I think it needs to be unified one way or the other before merging this, but I don't care which way it is unified. The discussion of which way they both should be can be tabled.

#include <rosidl_typesupport_connext_cpp/dds_utilities.hpp>

bool
get_datareader_qos(DDSDomainParticipant * participant, DDS_DataReaderQos & datareader_qos)
Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Moving / copying these functions from rmw into the rosidl package looks weird to me. It implies that every compiled message package embeds this logic. I would prefer if this stays in rmw and if the typesupport needs its somehow gets its passed as an argument.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is compiled into the library for this package, not into each message library:

https://github.com/ros2/rmw_connext/blob/fix_service_qos/rosidl_typesupport_connext_cpp/CMakeLists.txt#L33

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

It may be true that it should be in rmw_connext_cpp instead though. The question is where is it used from. If it is used from the message specific code, then it would need to be here or as you suggested moved to rmw and used there, passing the result to the message specific code.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Good point - I didn't notice that. Before the type support library only contained the identifier.

Without this change the reader / write qos was determined within rmw so it should be possible to keep it there.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

These functions are used in `srv__type_support.cpp.template, line 71:
https://github.com/ros2/rmw_connext/pull/100/files#diff-a2cb81bcab4593a61a1d8ad7a7308f25R71

I could change this function to take a DDSDataWriterQos struct and a DDSDataReaderQos struct, instead of an rmw_qos_profile, and initialize the DDS QoS structs in the rmw implementation before create_requester is called. Then the get_datareader/writer_qos functions would not need to be in the typesupport library.

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That sounds like a good way to go.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Done. The diff is much simpler now. Not sure what I was doing before; I think I was trying to make this implementation match the OpenSplice typesupport library.

}
datareader_qos.history.depth = static_cast<DDS_Long>(qos_profile.depth);
}

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Wouldn't it make sense to move all this code into the get_datareader_qos / get_datawriter_qos functions where all the other qos properties are set? That would also avoid have the same ~60 lines in four locations.

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

True, that would be a big improvement. Done in 65a3d43

@dirk-thomas
Copy link
Member

LGTM. Let's spin some CI jobs.

@dirk-thomas
Copy link
Member

+1

…and share code for setting DataReader/Writer QoS.
jacquelinekay added a commit that referenced this pull request Sep 20, 2015
Fix default QoS settings for services
@jacquelinekay jacquelinekay merged commit 030772b into master Sep 20, 2015
@jacquelinekay jacquelinekay deleted the fix_service_qos branch September 20, 2015 18:33
@jacquelinekay jacquelinekay removed the in review Waiting for review (Kanban column) label Sep 20, 2015
Sign up for free to subscribe to this conversation on GitHub. Already have an account? Sign in.
Labels
None yet
Projects
None yet
Development

Successfully merging this pull request may close these issues.

4 participants