Skip to content

Commit

Permalink
issue-919 Fixed "memory leak" in action clients (#920)
Browse files Browse the repository at this point in the history
Whenever a call is made to `rclcpp_action::Client::wait_for_action_server`
a weak pointer to an Event object gets added to the graph_event_ vector
of the NodeGraph interface. This vector will be cleared on a node graph
change event, but if no such event occurs the weak pointer will be stuck
in the vector.  Furthermore, if client code issues repeated calls to
`wait_for_action_server` the vector will keep growing.

The fix moves the Event object creation right after the early return from
`wait_for_action_server` so that the Event object is not created in the
case that the server is known to be present and therefore there is no
need to wait for a node graph change event to occur.

Signed-off-by: Adrian Stere <astere@clearpath.ai>
Signed-off-by: Ivan Santiago Paunovic <ivanpauno@ekumenlabs.com>
  • Loading branch information
astere-cpr authored and ivanpauno committed Dec 5, 2019
1 parent 82f6dfa commit 8332e15
Showing 1 changed file with 1 addition and 1 deletion.
2 changes: 1 addition & 1 deletion rclcpp_action/src/client.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -165,11 +165,11 @@ ClientBase::wait_for_action_server_nanoseconds(std::chrono::nanoseconds timeout)
if (!node_ptr) {
throw rclcpp::exceptions::InvalidNodeError();
}
auto event = node_ptr->get_graph_event();
// check to see if the server is ready immediately
if (this->action_server_is_ready()) {
return true;
}
auto event = node_ptr->get_graph_event();
if (timeout == std::chrono::nanoseconds(0)) {
// check was non-blocking, return immediately
return false;
Expand Down

0 comments on commit 8332e15

Please sign in to comment.