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

[rclcpp_action] Action client holds weak pointers to goal handles #1122

Merged
merged 5 commits into from
May 22, 2020
Merged
Changes from 1 commit
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
41 changes: 30 additions & 11 deletions rclcpp_action/include/rclcpp_action/client.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -342,6 +342,20 @@ class Client : public ClientBase
std::shared_future<typename GoalHandle::SharedPtr>
async_send_goal(const Goal & goal, const SendGoalOptions & options = SendGoalOptions())
{
// To prevent the list from growing out of control, forget about any goals
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
// with no more user references
{
std::lock_guard<std::mutex> guard(goal_handles_mutex_);
auto goal_handle_it = goal_handles_.begin();
while (goal_handle_it != goal_handles_.end()) {
if (!goal_handle_it->second.lock()) {
goal_handle_it = goal_handles_.erase(goal_handle_it);
} else {
++goal_handle_it;
}
}
}

// Put promise in the heap to move it around.
auto promise = std::make_shared<std::promise<typename GoalHandle::SharedPtr>>();
std::shared_future<typename GoalHandle::SharedPtr> future(promise->get_future());
Expand Down Expand Up @@ -494,7 +508,10 @@ class Client : public ClientBase
std::lock_guard<std::mutex> guard(goal_handles_mutex_);
auto it = goal_handles_.begin();
while (it != goal_handles_.end()) {
it->second->invalidate();
typename GoalHandle::SharedPtr goal_handle = it->second.lock();
if (goal_handle) {
goal_handle->invalidate();
}
it = goal_handles_.erase(it);
}
}
Expand Down Expand Up @@ -546,7 +563,12 @@ class Client : public ClientBase
"Received feedback for unknown goal. Ignoring...");
return;
}
typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id];
typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id].lock();
// Forget about the goal if there are no more user references
if (!goal_handle) {
goal_handles_.erase(goal_id);
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
return;
}
auto feedback = std::make_shared<Feedback>();
*feedback = feedback_message->feedback;
goal_handle->call_feedback_callback(goal_handle, feedback);
Expand Down Expand Up @@ -575,16 +597,13 @@ class Client : public ClientBase
"Received status for unknown goal. Ignoring...");
continue;
}
typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id];
goal_handle->set_status(status.status);
const int8_t goal_status = goal_handle->get_status();
if (
goal_status == GoalStatus::STATUS_SUCCEEDED ||
goal_status == GoalStatus::STATUS_CANCELED ||
goal_status == GoalStatus::STATUS_ABORTED)
{
typename GoalHandle::SharedPtr goal_handle = goal_handles_[goal_id].lock();
// Forget about the goal if there are no more user references
if (!goal_handle) {
jacobperron marked this conversation as resolved.
Show resolved Hide resolved
goal_handles_.erase(goal_id);
continue;
}
goal_handle->set_status(status.status);
}
}

Expand Down Expand Up @@ -639,7 +658,7 @@ class Client : public ClientBase
return future;
}

std::map<GoalUUID, typename GoalHandle::SharedPtr> goal_handles_;
std::map<GoalUUID, typename GoalHandle::WeakPtr> goal_handles_;
std::mutex goal_handles_mutex_;
};
} // namespace rclcpp_action
Expand Down