Skip to content

Commit

Permalink
Default destructor for PlanningComponent (#1470) (#1645)
Browse files Browse the repository at this point in the history
Signed-off-by: Tyler Weaver <tyler@picknik.ai>
(cherry picked from commit f95e110)

Co-authored-by: Tyler Weaver <tyler@picknik.ai>
  • Loading branch information
mergify[bot] and tylerjw committed Oct 28, 2022
1 parent 5335920 commit 3207ffc
Show file tree
Hide file tree
Showing 2 changed files with 2 additions and 20 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -107,11 +107,11 @@ class PlanningComponent
PlanningComponent(const PlanningComponent&) = delete;
PlanningComponent& operator=(const PlanningComponent&) = delete;

PlanningComponent(PlanningComponent&& other) = default;
PlanningComponent(PlanningComponent&& other) = delete;
PlanningComponent& operator=(PlanningComponent&& other) = delete;

/** \brief Destructor */
~PlanningComponent();
~PlanningComponent() = default;

/** \brief Get the name of the planning group */
const std::string& getPlanningGroupName() const;
Expand Down Expand Up @@ -195,9 +195,6 @@ class PlanningComponent
// TODO(henningkayser): implement path/trajectory constraints
// std::unique_ptr<moveit_msgs::msg::Constraints> path_constraints_;
// std::unique_ptr<moveit_msgs::msg::TrajectoryConstraints> trajectory_constraints_;

/** \brief Reset all member variables */
void clearContents();
};
} // namespace moveit_cpp

Expand Down
15 changes: 0 additions & 15 deletions moveit_ros/planning/moveit_cpp/src/planning_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -81,12 +81,6 @@ PlanningComponent::PlanningComponent(const std::string& group_name, const rclcpp
planning_pipeline_names_ = moveit_cpp_->getPlanningPipelineNames(group_name);
}

PlanningComponent::~PlanningComponent()
{
RCLCPP_INFO(LOGGER, "Deleting PlanningComponent '%s'", group_name_.c_str());
clearContents();
}

const std::vector<std::string> PlanningComponent::getNamedTargetStates()
{
if (joint_model_group_)
Expand Down Expand Up @@ -319,13 +313,4 @@ const PlanningComponent::PlanSolutionPtr PlanningComponent::getLastPlanSolution(
{
return last_plan_solution_;
}

void PlanningComponent::clearContents()
{
considered_start_state_.reset();
last_plan_solution_.reset();
current_goal_constraints_.clear();
moveit_cpp_.reset();
planning_pipeline_names_.clear();
}
} // namespace moveit_cpp

0 comments on commit 3207ffc

Please sign in to comment.