Fix memory leaks in rclcpp (#354)

* Make sure to delete service_handle when in the Service() destructor.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Make sure to delete the allocated rcl_node on error paths.

This all happens *before* we setup the shared_ptr destructor,
so we have to hand delete in the error paths.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>

* Move delete rcl_node up.

It turns out that we are always going to throw in that block,
and we never access rcl_node, so just delete it very early
on.

Signed-off-by: Chris Lalancette <clalancette@openrobotics.org>
This commit is contained in:
Chris Lalancette 2017-08-11 05:45:25 -07:00 committed by GitHub
parent 5e7aa50af6
commit cd839663b4
2 changed files with 3 additions and 0 deletions

View file

@ -172,6 +172,7 @@ public:
(std::cerr << ss.str()).flush();
rcl_reset_error();
}
delete service_handle_;
}
}

View file

@ -92,6 +92,8 @@ NodeBase::NodeBase(
// Finalize the interrupt guard condition.
finalize_notify_guard_condition();
delete rcl_node;
if (ret == RCL_RET_NODE_INVALID_NAME) {
rcl_reset_error(); // discard rcl_node_init error
int validation_result;