41 #include <moveit_msgs/msg/move_it_error_codes.hpp>
46 struct ExecutableMotionPlan;
56 std::vector<std::string> controller_names = {})
This namespace includes functionality specific to the execution and monitoring of motion plans.
std::function< bool(ExecutableMotionPlan &)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
A generic representation on what a computed motion plan looks like.
moveit_msgs::msg::MoveItErrorCodes error_code_
An error code reflecting what went wrong (if anything)
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
robot_trajectory::RobotTrajectoryPtr executed_trajectory_
The trace of the trajectory recorded during execution.
planning_scene::PlanningSceneConstPtr planning_scene_
std::vector< ExecutableTrajectory > plan_components_
Representation of a trajectory that can be executed.
std::function< bool(const ExecutableMotionPlan *)> effect_on_success_
std::vector< std::string > controller_names_
robot_trajectory::RobotTrajectoryPtr trajectory_
bool trajectory_monitoring_
ExecutableTrajectory(const robot_trajectory::RobotTrajectoryPtr &trajectory, const std::string &description, std::vector< std::string > controller_names={})
collision_detection::AllowedCollisionMatrixConstPtr allowed_collision_matrix_