Skip to content

Commit

Permalink
fix: resolve bugs in MoveGroupSequenceAction class (main branch) (#1797
Browse files Browse the repository at this point in the history
…) (#1809)

* fix: resolve bugs in MoveGroupSequenceAction class

* style: adopt .clang-format

Co-authored-by: Marco Magri <marco.magri@fraunhofer.it>
(cherry picked from commit fca8e9b)

Co-authored-by: Marco Magri <94347649+MarcoMagriDev@users.noreply.github.com>
  • Loading branch information
mergify[bot] and MarcoMagriDev committed Dec 15, 2022
1 parent e65f457 commit 8674b3a
Showing 1 changed file with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -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<moveit_msgs::action::MoveGroupSequence::Feedback>())
{
}

Expand Down Expand Up @@ -93,7 +95,6 @@ void MoveGroupSequenceAction::executeSequenceCallback(const std::shared_ptr<Move
// Notify that goal is being executed
goal_handle_ = goal_handle;
const auto goal = goal_handle->get_goal();
goal_handle->execute();

setMoveState(move_group::PLANNING);

Expand Down Expand Up @@ -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);
};

Expand Down

0 comments on commit 8674b3a

Please sign in to comment.