From fca8e9bd3f41e6bff5aadbf75c494b5cc3fa25ee Mon Sep 17 00:00:00 2001 From: Marco Magri <94347649+MarcoMagriDev@users.noreply.github.com> Date: Wed, 14 Dec 2022 20:26:42 +0100 Subject: [PATCH] fix: resolve bugs in MoveGroupSequenceAction class (main branch) (#1797) * fix: resolve bugs in MoveGroupSequenceAction class * style: adopt .clang-format Co-authored-by: Marco Magri --- .../src/move_group_sequence_action.cpp | 7 ++++--- 1 file changed, 4 insertions(+), 3 deletions(-) diff --git a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp index c3bbc43c59..3c58f8978a 100644 --- a/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp +++ b/moveit_planners/pilz_industrial_motion_planner/src/move_group_sequence_action.cpp @@ -56,7 +56,9 @@ namespace pilz_industrial_motion_planner static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.pilz_industrial_motion_planner.move_group_sequence_action"); -MoveGroupSequenceAction::MoveGroupSequenceAction() : MoveGroupCapability("SequenceAction") +MoveGroupSequenceAction::MoveGroupSequenceAction() + : MoveGroupCapability("SequenceAction") + , move_feedback_(std::make_shared()) { } @@ -93,7 +95,6 @@ void MoveGroupSequenceAction::executeSequenceCallback(const std::shared_ptrget_goal(); - goal_handle->execute(); setMoveState(move_group::PLANNING); @@ -162,7 +163,7 @@ void MoveGroupSequenceAction::executeSequenceCallbackPlanAndExecute( opt.replan_delay_ = goal->planning_options.replan_delay; opt.before_execution_callback_ = [this] { startMoveExecutionCallback(); }; - [this, &request = goal->request](plan_execution::ExecutableMotionPlan& plan) { + opt.plan_callback_ = [this, &request = goal->request](plan_execution::ExecutableMotionPlan& plan) { return planUsingSequenceManager(request, plan); };