Skip to content

Commit

Permalink
move TrajectoryExecutionManager::clear() to private (backport #3226) (#…
Browse files Browse the repository at this point in the history
…3237)

(cherry picked from commit 3ec75ab)

Signed-off-by: Dongya Jiang <1983534+patrickKXMD@users.noreply.github.com>
Co-authored-by: Robert Haschke <rhaschke@users.noreply.github.com>
  • Loading branch information
mergify[bot] and rhaschke authored Jan 12, 2025
1 parent edddadb commit 5333395
Show file tree
Hide file tree
Showing 3 changed files with 3 additions and 5 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -107,7 +107,6 @@ void MoveGroupExecuteTrajectoryAction::executePath(const std::shared_ptr<ExecTra
{
RCLCPP_INFO(LOGGER, "Execution request received");

context_->trajectory_execution_manager_->clear();
if (context_->trajectory_execution_manager_->push(goal->get_goal()->trajectory))
{
setExecuteTrajectoryState(MONITOR, goal);
Expand Down
1 change: 0 additions & 1 deletion moveit_ros/planning/plan_execution/src/plan_execution.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -397,7 +397,6 @@ moveit_msgs::msg::MoveItErrorCodes plan_execution::PlanExecution::executeAndMoni
plan.plan_components_[i].trajectory_->getRobotTrajectoryMsg(msg);
if (!trajectory_execution_manager_->push(msg, plan.plan_components_[i].controller_names_))
{
trajectory_execution_manager_->clear();
RCLCPP_ERROR(LOGGER, "Apparently trajectory initialization failed");
execution_complete_ = true;
result.val = moveit_msgs::msg::MoveItErrorCodes::CONTROL_FAILED;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -221,9 +221,6 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager
/// Stop whatever executions are active, if any
void stopExecution(bool auto_clear = true);

/// Clear the trajectories to execute
void clear();

/// Enable or disable the monitoring of trajectory execution duration. If a controller takes
/// longer than expected, the trajectory is canceled
void enableExecutionDurationMonitoring(bool flag);
Expand Down Expand Up @@ -304,6 +301,9 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager
bool waitForRobotToStop(const TrajectoryExecutionContext& context, double wait_time = 1.0);
void continuousExecutionThread();

/// Clear the trajectories to execute
void clear();

void stopExecutionInternal();

void receiveEvent(const std_msgs::msg::String::ConstSharedPtr& event);
Expand Down

0 comments on commit 5333395

Please sign in to comment.