Skip to content
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

add wait_for_action_server() for action clients #598

Merged
merged 4 commits into from
Dec 7, 2018

Conversation

wjwwood
Copy link
Member

@wjwwood wjwwood commented Dec 4, 2018

This is based on a glob of changes needed for me to write the action tests in test_communication. It will have to be rebased when #594 and #593 are merged.

c7c1738 is the only commit that is "new" to this pr.

Connects to ros2/system_tests#316

@wjwwood wjwwood added enhancement New feature or request in review Waiting for review (Kanban column) labels Dec 4, 2018
@wjwwood wjwwood self-assigned this Dec 4, 2018
@wjwwood wjwwood force-pushed the wjwwood/actions_test_communication branch 2 times, most recently from df989f0 to df248de Compare December 5, 2018 22:51
rclcpp_action/src/client.cpp Show resolved Hide resolved
rclcpp_action/src/client.cpp Outdated Show resolved Hide resolved
return true;
}
// server is not ready, loop if there is time left
time_to_wait = timeout - (std::chrono::steady_clock::now() - start);
Copy link
Contributor

@hidmic hidmic Dec 6, 2018

Choose a reason for hiding this comment

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

@wjwwood the only objection I have is that this line is assuming that timeout won't ever become largely negative. You may end up trying to wait for a negative time here if someone were to pass a large negative timeout.

Copy link
Member Author

Choose a reason for hiding this comment

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

Why would that be a problem? If timeout is a large negative (or a small one) then the while loop will exit just afte this and false will be returned.

(your link doesn't work for me btw)

Copy link
Contributor

@hidmic hidmic Dec 6, 2018

Choose a reason for hiding this comment

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

Why would it exit? If timeout < std::chrono::nanoseconds(0) holds, then it'll loop. Yes, I saw the client code too. Same observation.

(Fixed the link, not sure what happened)

Copy link
Member Author

Choose a reason for hiding this comment

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

Oh you're right.

So a large negative would be used to wait, but that timeout is passed here:

graph_cv_.wait_for(graph_lock, timeout, pred);

Which if negative will just wake up immediately.

So I think the code works, but maybe it could be more efficient. So I don't know what you would like to do differently here?

Copy link
Contributor

@hidmic hidmic Dec 6, 2018

Choose a reason for hiding this comment

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

Right, I checked std::condition_variable reference and it doesn't say much really, so I'd guess you're right about it waking up immediately. It makes for a sophisticated busy loop :). I'll push a commit with a slightly different approach, that I think achieves what the function intent is.

Copy link
Member Author

Choose a reason for hiding this comment

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

Sounds good to me, but we should also change the service one at the same time, since it actually has a lot of code utilizing it (via tests and stuff).

Signed-off-by: William Woodall <william@osrfoundation.org>
@wjwwood wjwwood force-pushed the wjwwood/actions_test_communication branch from df248de to be32a5f Compare December 6, 2018 19:19
@wjwwood
Copy link
Member Author

wjwwood commented Dec 6, 2018

W.r.t. to the waiting code, it was copied mostly verbatim from the existing wait for service code:

bool
ClientBase::wait_for_service_nanoseconds(std::chrono::nanoseconds timeout)
{
auto start = std::chrono::steady_clock::now();
// make an event to reuse, rather than create a new one each time
auto node_ptr = node_graph_.lock();
if (!node_ptr) {
throw InvalidNodeError();
}
auto event = node_ptr->get_graph_event();
// check to see if the server is ready immediately
if (this->service_is_ready()) {
return true;
}
if (timeout == std::chrono::nanoseconds(0)) {
// check was non-blocking, return immediately
return false;
}
// update the time even on the first loop to account for time spent in the first call
// to this->server_is_ready()
std::chrono::nanoseconds time_to_wait = timeout - (std::chrono::steady_clock::now() - start);
if (timeout > std::chrono::nanoseconds(0) && time_to_wait < std::chrono::nanoseconds(0)) {
// Do not allow the time_to_wait to become negative when timeout was originally positive.
// Setting time_to_wait to 0 will allow one non-blocking wait because of the do-while.
time_to_wait = std::chrono::nanoseconds(0);
}
// continue forever if timeout is negative, otherwise continue until out of time_to_wait
do {
if (!rclcpp::ok(this->context_)) {
return false;
}
// Limit each wait to 100ms to workaround an issue specific to the Connext RMW implementation.
// A race condition means that graph changes for services becoming available may trigger the
// wait set to wake up, but then not be reported as ready immediately after the wake up
// (see https://github.com/ros2/rmw_connext/issues/201)
// If no other graph events occur, the wait set will not be triggered again until the timeout
// has been reached, despite the service being available, so we artificially limit the wait
// time to limit the delay.
node_ptr->wait_for_graph_change(
event, std::min(time_to_wait, std::chrono::nanoseconds(RCL_MS_TO_NS(100))));
// Because of the aforementioned race condition, we check if the service is ready even if the
// graph event wasn't triggered.
event->check_and_clear();
if (this->service_is_ready()) {
return true;
}
// server is not ready, loop if there is time left
time_to_wait = timeout - (std::chrono::steady_clock::now() - start);
} while (time_to_wait > std::chrono::nanoseconds(0) || timeout < std::chrono::nanoseconds(0));
return false; // timeout exceeded while waiting for the server to be ready
}

So any comments about it will also apply to that code.

@sloretz sloretz merged commit 8bffd25 into master Dec 7, 2018
@sloretz sloretz deleted the wjwwood/actions_test_communication branch December 7, 2018 02:57
@sloretz sloretz removed the in review Waiting for review (Kanban column) label Dec 7, 2018
cho3 pushed a commit to cho3/rclcpp that referenced this pull request Jun 3, 2019
* add wait_for_action_server() for action clients

Signed-off-by: William Woodall <william@osrfoundation.org>

* Handle negative timeouts in wait_for_service() and wait_for_action_server() methods.

* Fix uncrustify errors.

* Ignore take failure on services for connext
nnmm pushed a commit to ApexAI/rclcpp that referenced this pull request Jul 9, 2022
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
enhancement New feature or request
Projects
None yet
Development

Successfully merging this pull request may close these issues.

None yet

3 participants