Go to the documentation of this file.
   41 #include <moveit_msgs/MoveItErrorCodes.h> 
   42 #include <boost/function.hpp> 
   46 struct ExecutableMotionPlan;
 
   49 struct ExecutableTrajectory
 
   55   ExecutableTrajectory(
const robot_trajectory::RobotTrajectoryPtr& trajectory, 
const std::string& description,
 
   56                        std::vector<std::string> controller_names = {})
 
   73 struct ExecutableMotionPlan
 
  
planning_scene::PlanningSceneConstPtr planning_scene_
 
robot_trajectory::RobotTrajectoryPtr executed_trajectory_
The trace of the trajectory recorded during execution.
 
planning_scene_monitor::PlanningSceneMonitorPtr planning_scene_monitor_
 
robot_trajectory::RobotTrajectoryPtr trajectory_
 
collision_detection::AllowedCollisionMatrixConstPtr allowed_collision_matrix_
 
bool trajectory_monitoring_
 
planning_scene::PlanningScenePtr copyPlanningScene()
 
std::vector< ExecutableTrajectory > plan_components_
 
boost::function< bool(const ExecutableMotionPlan *)> effect_on_success_
 
moveit_msgs::MoveItErrorCodes error_code_
An error code reflecting what went wrong (if anything)
 
This namespace includes functionality specific to the execution and monitoring of motion plans.
 
static PlanningScenePtr clone(const PlanningSceneConstPtr &scene)
 
A generic representation on what a computed motion plan looks like.
 
This is a convenience class for obtaining access to an instance of a locked PlanningScene.
 
boost::function< bool(ExecutableMotionPlan &)> ExecutableMotionPlanComputationFn
The signature of a function that can compute a motion plan.
 
std::vector< std::string > controller_names_
 
planning
Author(s): Ioan Sucan 
, Sachin Chitta 
autogenerated on Sat May 3 2025 02:26:19