Skip to content

Commit

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

Signed-off-by: Dongya Jiang <[email protected]>

* Apply suggestions from code review

Co-authored-by: Robert Haschke <[email protected]>

---------

Signed-off-by: Dongya Jiang <[email protected]>
Co-authored-by: Robert Haschke <[email protected]>
  • Loading branch information
patrickKXMD and rhaschke authored Jan 12, 2025
1 parent 9f1a53d commit 3ec75ab
Show file tree
Hide file tree
Showing 4 changed files with 3 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -200,11 +200,6 @@ void initTrajectoryExecutionManager(py::module& m)
Stop whatever executions are active, if any.
)")

.def("clear", &trajectory_execution_manager::TrajectoryExecutionManager::clear,
R"(
Clear the trajectories to execute.
)")

.def("enable_execution_duration_monitoring",
&trajectory_execution_manager::TrajectoryExecutionManager::enableExecutionDurationMonitoring,
py::arg("flag"),
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -106,7 +106,6 @@ void MoveGroupExecuteTrajectoryAction::executePath(const std::shared_ptr<ExecTra
{
RCLCPP_INFO(getLogger(), "Execution request received");

context_->trajectory_execution_manager_->clear();
if (context_->trajectory_execution_manager_->push(goal->get_goal()->trajectory, goal->get_goal()->controller_names))
{
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 @@ -401,7 +401,6 @@ moveit_msgs::msg::MoveItErrorCodes plan_execution::PlanExecution::executeAndMoni
plan.plan_components[component_idx].trajectory->getRobotTrajectoryMsg(msg);
if (!trajectory_execution_manager_->push(msg, plan.plan_components[component_idx].controller_name))
{
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 @@ -186,9 +186,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 @@ -286,6 +283,9 @@ class MOVEIT_TRAJECTORY_EXECUTION_MANAGER_EXPORT TrajectoryExecutionManager
bool executePart(std::size_t part_index);
bool waitForRobotToStop(const TrajectoryExecutionContext& context, double wait_time = 1.0);

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

void stopExecutionInternal();

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

0 comments on commit 3ec75ab

Please sign in to comment.