37 #ifndef MOVEIT_PICK_PLACE_MANIPULATION_PLAN_ 38 #define MOVEIT_PICK_PLACE_MANIPULATION_PLAN_ 44 #include <moveit_msgs/GripperTranslation.h> 45 #include <moveit_msgs/RobotState.h> 46 #include <moveit_msgs/RobotTrajectory.h> 47 #include <moveit_msgs/MoveItErrorCodes.h> 48 #include <moveit_msgs/Constraints.h> 91 : shared_data_(shared_data), processing_stage_(0)
98 goal_sampler_.reset();
99 trajectories_.clear();
100 approach_state_.reset();
101 possible_goal_states_.clear();
102 processing_stage_ = 0;
constraint_samplers::ConstraintSamplerPtr goal_sampler_
trajectory_msgs::JointTrajectory retreat_posture_
moveit_msgs::GripperTranslation retreat_
moveit_msgs::MoveItErrorCodes error_code_
moveit_msgs::GripperTranslation approach_
ManipulationPlanSharedData()
Eigen::Affine3d transformed_goal_pose_
std::size_t processing_stage_
moveit_msgs::AttachedCollisionObject diff_attached_object_
robot_state::RobotStatePtr approach_state_
void clear()
Restore this plan to a state that makes it look like it never was processed by the manipulation pipel...
MOVEIT_CLASS_FORWARD(ManipulationPlanSharedData)
moveit_msgs::Constraints goal_constraints_
const robot_model::JointModelGroup * end_effector_group_
trajectory_msgs::JointTrajectory approach_posture_
const robot_model::LinkModel * ik_link_
ManipulationPlanSharedDataConstPtr shared_data_
unsigned int max_goal_sampling_attempts_
EIGEN_MAKE_ALIGNED_OPERATOR_NEW ManipulationPlan(const ManipulationPlanSharedDataConstPtr &shared_data)
const robot_model::JointModelGroup * planning_group_
std::vector< robot_state::RobotStatePtr > possible_goal_states_
std::vector< plan_execution::ExecutableTrajectory > trajectories_
geometry_msgs::PoseStamped goal_pose_
moveit_msgs::Constraints path_constraints_
bool minimize_object_distance_