Skip to content

Commit

Permalink
Do not allow traj execution from PlanningComponent (#1835)
Browse files Browse the repository at this point in the history
* Do not allow traj execution from PlanningComponent

* Deprecate, don't delete

* Get the group_name from RobotTrajectory

* Rebase
  • Loading branch information
AndyZe authored Jan 15, 2023
1 parent c6733bd commit 6711436
Show file tree
Hide file tree
Showing 4 changed files with 19 additions and 8 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -162,9 +162,6 @@ class MoveItCpp
const trajectory_execution_manager::TrajectoryExecutionManagerPtr& getTrajectoryExecutionManager() const;
trajectory_execution_manager::TrajectoryExecutionManagerPtr getTrajectoryExecutionManagerNonConst();

/** \brief Execute a trajectory on the planning group specified by group_name using the trajectory execution manager.
* If blocking is set to false, the execution is run in background and the function returns immediately. */

/** \brief Execute a trajectory on the planning group specified by group_name using the trajectory execution manager.
* \param [in] group_name MoveIt group to execute for.
* \param [in] robot_trajectory Contains trajectory info as well as metadata such as a RobotModel.
Expand All @@ -173,10 +170,15 @@ class MoveItCpp
* a controller. The exact behavior of finding a controller depends on which MoveItControllerManager plugin is active.
* \return moveit_controller_manager::ExecutionStatus::SUCCEEDED if successful
*/
moveit_controller_manager::ExecutionStatus
[[deprecated(
"MoveItCpp::execute() no longer requires a group_name parameter")]] moveit_controller_manager::ExecutionStatus
execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking = true, const std::vector<std::string>& controllers = std::vector<std::string>());

moveit_controller_manager::ExecutionStatus
execute(const robot_trajectory::RobotTrajectoryPtr& robot_trajectory, bool blocking = true,
const std::vector<std::string>& controllers = std::vector<std::string>());

/** \brief Utility to terminate the given planning pipeline */
bool terminatePlanningPipeline(const std::string& pipeline_name);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -202,7 +202,7 @@ class PlanningComponent

/** \brief Execute the latest computed solution trajectory computed by plan(). By default this function terminates
* after the execution is complete. The execution can be run in background by setting blocking to false. */
bool execute(bool blocking = true);
[[deprecated("Use MoveItCpp::execute()")]] bool execute(bool blocking = true);

/** \brief Return the last plan solution*/
const planning_interface::MotionPlanResponse& getLastMotionPlanResponse();
Expand Down
13 changes: 11 additions & 2 deletions moveit_ros/planning/moveit_cpp/src/moveit_cpp.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -217,15 +217,24 @@ trajectory_execution_manager::TrajectoryExecutionManagerPtr MoveItCpp::getTrajec
}

moveit_controller_manager::ExecutionStatus
MoveItCpp::execute(const std::string& group_name, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking, const std::vector<std::string>& controllers)
MoveItCpp::execute(const std::string& /* group_name */, const robot_trajectory::RobotTrajectoryPtr& robot_trajectory,
bool blocking, const std::vector<std::string>& /* controllers */)
{
return execute(robot_trajectory, blocking);
}

moveit_controller_manager::ExecutionStatus
MoveItCpp::execute(const robot_trajectory::RobotTrajectoryPtr& robot_trajectory, bool blocking,
const std::vector<std::string>& controllers)
{
if (!robot_trajectory)
{
RCLCPP_ERROR(LOGGER, "Robot trajectory is undefined");
return moveit_controller_manager::ExecutionStatus::ABORTED;
}

const std::string group_name = robot_trajectory->getGroupName();

// Check if there are controllers that can handle the execution
if (!trajectory_execution_manager_->ensureActiveControllersForGroup(group_name))
{
Expand Down
2 changes: 1 addition & 1 deletion moveit_ros/planning/moveit_cpp/src/planning_component.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -412,7 +412,7 @@ bool PlanningComponent::execute(bool blocking)
// RCLCPP_ERROR("Failed to parameterize trajectory");
// return false;
//}
return moveit_cpp_->execute(group_name_, last_plan_solution_.trajectory_, blocking);
return moveit_cpp_->execute(last_plan_solution_.trajectory_, blocking);
}

const planning_interface::MotionPlanResponse& PlanningComponent::getLastMotionPlanResponse()
Expand Down

0 comments on commit 6711436

Please sign in to comment.