Skip to content
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
19 changes: 11 additions & 8 deletions rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -262,7 +262,7 @@ class Client : public ClientBase
using GoalHandle = ClientGoalHandle<ActionT>;
using WrappedResult = typename GoalHandle::WrappedResult;
using GoalResponseCallback =
std::function<void (std::shared_future<typename GoalHandle::SharedPtr>)>;
std::function<void (typename GoalHandle::SharedPtr)>;
using FeedbackCallback = typename GoalHandle::FeedbackCallback;
using ResultCallback = typename GoalHandle::ResultCallback;
using CancelRequest = typename ActionT::Impl::CancelGoalService::Request;
Expand Down Expand Up @@ -360,7 +360,7 @@ class Client : public ClientBase
if (!goal_response->accepted) {
promise->set_value(nullptr);
if (options.goal_response_callback) {
options.goal_response_callback(future);
options.goal_response_callback(nullptr);
}
return;
}
Expand All @@ -370,13 +370,9 @@ class Client : public ClientBase
// Do not use std::make_shared as friendship cannot be forwarded.
std::shared_ptr<GoalHandle> goal_handle(
new GoalHandle(goal_info, options.feedback_callback, options.result_callback));
{
std::lock_guard<std::mutex> guard(goal_handles_mutex_);
goal_handles_[goal_handle->get_goal_id()] = goal_handle;
}
promise->set_value(goal_handle);

if (options.goal_response_callback) {
options.goal_response_callback(future);
options.goal_response_callback(goal_handle);
}

if (options.result_callback) {
Expand All @@ -387,6 +383,13 @@ class Client : public ClientBase
return;
}
}

{
std::lock_guard<std::mutex> guard(goal_handles_mutex_);
goal_handles_[goal_handle->get_goal_id()] = goal_handle;
}

promise->set_value(goal_handle);
});

// TODO(jacobperron): Encapsulate into it's own function and
Expand Down
3 changes: 1 addition & 2 deletions rclcpp_action/test/test_client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -435,9 +435,8 @@ TEST_F(TestClientAgainstServer, async_send_goal_with_goal_response_callback_wait
auto send_goal_ops = rclcpp_action::Client<ActionType>::SendGoalOptions();
send_goal_ops.goal_response_callback =
[&goal_response_received]
(std::shared_future<typename ActionGoalHandle::SharedPtr> future) mutable
(typename ActionGoalHandle::SharedPtr goal_handle) mutable
{
auto goal_handle = future.get();
if (goal_handle) {
goal_response_received = true;
}
Expand Down