Skip to content

Commit 8460dda

Browse files
CihatAltiparmaksussybot5258
authored andcommitted
Make the destructors of the base classes of planning adapters virtual and close move_group gracefully (moveit#3435)
--------- Signed-off-by: CihatAltiparmak <cihataltiparmak1@gmail.com>
1 parent b5ca2ca commit 8460dda

File tree

12 files changed

+20
-1
lines changed

12 files changed

+20
-1
lines changed

moveit_core/planning_interface/include/moveit/planning_interface/planning_request_adapter.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@ MOVEIT_CLASS_FORWARD(PlanningRequestAdapter); // Defines PlanningRequestAdapter
5454
class PlanningRequestAdapter
5555
{
5656
public:
57+
virtual ~PlanningRequestAdapter() = default;
5758
/** @brief Initialize parameters using the passed Node and parameter namespace.
5859
* @param node Node instance used by the adapter
5960
* @param parameter_namespace Parameter namespace for adapter

moveit_core/planning_interface/include/moveit/planning_interface/planning_response_adapter.hpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -52,6 +52,7 @@ MOVEIT_CLASS_FORWARD(PlanningResponseAdapter); // Defines PlanningResponseAdapt
5252
class PlanningResponseAdapter
5353
{
5454
public:
55+
virtual ~PlanningResponseAdapter() = default;
5556
/** @brief Initialize parameters using the passed Node and parameter namespace.
5657
* @param node Node instance used by the adapter
5758
* @param parameter_namespace Parameter namespace for adapter

moveit_core/utils/src/logger.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ rclcpp::Logger& getGlobalRootLogger()
5555
auto name = fmt::format("moveit_{}", rsl::rng()());
5656
try
5757
{
58-
static auto* moveit_node = new rclcpp::Node(name);
58+
static rclcpp::Node::SharedPtr moveit_node = rclcpp::Node::make_shared(name);
5959
return moveit_node->get_logger();
6060
}
6161
catch (const std::exception& ex)

moveit_ros/planning/planning_request_adapter_plugins/src/check_for_stacked_constraints.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,8 @@ class CheckForStackedConstraints : public planning_interface::PlanningRequestAda
5656
{
5757
}
5858

59+
~CheckForStackedConstraints() override = default;
60+
5961
[[nodiscard]] std::string getDescription() const override
6062
{
6163
return std::string("CheckForStackedConstraints");

moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_bounds.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -66,6 +66,8 @@ class CheckStartStateBounds : public planning_interface::PlanningRequestAdapter
6666
{
6767
}
6868

69+
~CheckStartStateBounds() override = default;
70+
6971
void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
7072
{
7173
param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);

moveit_ros/planning/planning_request_adapter_plugins/src/check_start_state_collision.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -58,6 +58,8 @@ class CheckStartStateCollision : public planning_interface::PlanningRequestAdapt
5858
{
5959
}
6060

61+
~CheckStartStateCollision() override = default;
62+
6163
[[nodiscard]] std::string getDescription() const override
6264
{
6365
return std::string("CheckStartStateCollision");

moveit_ros/planning/planning_request_adapter_plugins/src/resolve_constraint_frames.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,7 @@ class ResolveConstraintFrames : public planning_interface::PlanningRequestAdapte
5353
{
5454
}
5555

56+
~ResolveConstraintFrames() override = default;
5657
[[nodiscard]] std::string getDescription() const override
5758
{
5859
return std::string("ResolveConstraintFrames");

moveit_ros/planning/planning_request_adapter_plugins/src/validate_workspace_bounds.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -57,6 +57,8 @@ class ValidateWorkspaceBounds : public planning_interface::PlanningRequestAdapte
5757
{
5858
}
5959

60+
~ValidateWorkspaceBounds() override = default;
61+
6062
void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
6163
{
6264
param_listener_ = std::make_unique<default_request_adapter_parameters::ParamListener>(node, parameter_namespace);

moveit_ros/planning/planning_response_adapter_plugins/src/add_ruckig_traj_smoothing.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,8 @@ class AddRuckigTrajectorySmoothing : public planning_interface::PlanningResponse
5656
{
5757
}
5858

59+
~AddRuckigTrajectorySmoothing() override = default;
60+
5961
[[nodiscard]] std::string getDescription() const override
6062
{
6163
return std::string("AddRuckigTrajectorySmoothing");

moveit_ros/planning/planning_response_adapter_plugins/src/add_time_optimal_parameterization.cpp

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -53,6 +53,8 @@ class AddTimeOptimalParameterization : public planning_interface::PlanningRespon
5353
{
5454
}
5555

56+
~AddTimeOptimalParameterization() override = default;
57+
5658
void initialize(const rclcpp::Node::SharedPtr& node, const std::string& parameter_namespace) override
5759
{
5860
param_listener_ = std::make_unique<default_response_adapter_parameters::ParamListener>(node, parameter_namespace);

0 commit comments

Comments
 (0)