37 #ifndef MOVEIT_PLAN_EXECUTION_PLAN_REPRESENTATION_ 38 #define MOVEIT_PLAN_EXECUTION_PLAN_REPRESENTATION_ 42 #include <moveit_msgs/MoveItErrorCodes.h> 43 #include <boost/function.hpp> 47 struct ExecutableMotionPlan;
56 ExecutableTrajectory(
const robot_trajectory::RobotTrajectoryPtr& trajectory,
const std::string& description)
collision_detection::AllowedCollisionMatrixConstPtr allowed_collision_matrix_
ExecutableTrajectory(const robot_trajectory::RobotTrajectoryPtr &trajectory, const std::string &description)
moveit_msgs::MoveItErrorCodes error_code_
An error code reflecting what went wrong (if anything)
Representation of a trajectory that can be executed.
boost::function< bool(ExecutableMotionPlan &plan)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
robot_trajectory::RobotTrajectoryPtr trajectory_
planning_scene::PlanningSceneConstPtr planning_scene_
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
robot_trajectory::RobotTrajectoryPtr executed_trajectory_
bool trajectory_monitoring_
This namespace includes functionality specific to the execution and monitoring of motion plans...
A generic representation on what a computed motion plan looks like.
boost::function< bool(const ExecutableMotionPlan *)> effect_on_success_
std::vector< ExecutableTrajectory > plan_components_