#include <manipulation_plan.h>
Public Member Functions | |
void | clear () |
Restore this plan to a state that makes it look like it never was processed by the manipulation pipeline. More... | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | ManipulationPlan (const ManipulationPlanSharedDataConstPtr &shared_data) |
Public Attributes | |
moveit_msgs::GripperTranslation | approach_ |
trajectory_msgs::JointTrajectory | approach_posture_ |
robot_state::RobotStatePtr | approach_state_ |
moveit_msgs::MoveItErrorCodes | error_code_ |
moveit_msgs::Constraints | goal_constraints_ |
geometry_msgs::PoseStamped | goal_pose_ |
constraint_samplers::ConstraintSamplerPtr | goal_sampler_ |
std::size_t | id_ |
std::vector< robot_state::RobotStatePtr > | possible_goal_states_ |
std::size_t | processing_stage_ |
moveit_msgs::GripperTranslation | retreat_ |
trajectory_msgs::JointTrajectory | retreat_posture_ |
ManipulationPlanSharedDataConstPtr | shared_data_ |
std::vector< plan_execution::ExecutableTrajectory > | trajectories_ |
Eigen::Affine3d | transformed_goal_pose_ |
Definition at line 86 of file manipulation_plan.h.
|
inline |
Definition at line 90 of file manipulation_plan.h.
|
inline |
Restore this plan to a state that makes it look like it never was processed by the manipulation pipeline.
Definition at line 96 of file manipulation_plan.h.
moveit_msgs::GripperTranslation pick_place::ManipulationPlan::approach_ |
Definition at line 109 of file manipulation_plan.h.
trajectory_msgs::JointTrajectory pick_place::ManipulationPlan::approach_posture_ |
Definition at line 115 of file manipulation_plan.h.
robot_state::RobotStatePtr pick_place::ManipulationPlan::approach_state_ |
Definition at line 131 of file manipulation_plan.h.
moveit_msgs::MoveItErrorCodes pick_place::ManipulationPlan::error_code_ |
Definition at line 137 of file manipulation_plan.h.
moveit_msgs::Constraints pick_place::ManipulationPlan::goal_constraints_ |
Definition at line 124 of file manipulation_plan.h.
geometry_msgs::PoseStamped pick_place::ManipulationPlan::goal_pose_ |
Definition at line 121 of file manipulation_plan.h.
constraint_samplers::ConstraintSamplerPtr pick_place::ManipulationPlan::goal_sampler_ |
Definition at line 127 of file manipulation_plan.h.
std::size_t pick_place::ManipulationPlan::id_ |
Definition at line 143 of file manipulation_plan.h.
std::vector<robot_state::RobotStatePtr> pick_place::ManipulationPlan::possible_goal_states_ |
Definition at line 129 of file manipulation_plan.h.
std::size_t pick_place::ManipulationPlan::processing_stage_ |
Definition at line 140 of file manipulation_plan.h.
moveit_msgs::GripperTranslation pick_place::ManipulationPlan::retreat_ |
Definition at line 112 of file manipulation_plan.h.
trajectory_msgs::JointTrajectory pick_place::ManipulationPlan::retreat_posture_ |
Definition at line 118 of file manipulation_plan.h.
ManipulationPlanSharedDataConstPtr pick_place::ManipulationPlan::shared_data_ |
Definition at line 106 of file manipulation_plan.h.
std::vector<plan_execution::ExecutableTrajectory> pick_place::ManipulationPlan::trajectories_ |
Definition at line 134 of file manipulation_plan.h.
Eigen::Affine3d pick_place::ManipulationPlan::transformed_goal_pose_ |
Definition at line 122 of file manipulation_plan.h.