#include <manipulation_plan.h>
|
| 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) |
| |
Definition at line 117 of file manipulation_plan.h.
◆ ManipulationPlan()
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW pick_place::ManipulationPlan::ManipulationPlan |
( |
const ManipulationPlanSharedDataConstPtr & |
shared_data | ) |
|
|
inline |
◆ clear()
| void pick_place::ManipulationPlan::clear |
( |
| ) |
|
|
inline |
Restore this plan to a state that makes it look like it never was processed by the manipulation pipeline.
Definition at line 127 of file manipulation_plan.h.
◆ approach_
| moveit_msgs::GripperTranslation pick_place::ManipulationPlan::approach_ |
◆ approach_posture_
| trajectory_msgs::JointTrajectory pick_place::ManipulationPlan::approach_posture_ |
◆ approach_state_
| moveit::core::RobotStatePtr pick_place::ManipulationPlan::approach_state_ |
◆ error_code_
| moveit_msgs::MoveItErrorCodes pick_place::ManipulationPlan::error_code_ |
◆ goal_constraints_
| moveit_msgs::Constraints pick_place::ManipulationPlan::goal_constraints_ |
◆ goal_pose_
| geometry_msgs::PoseStamped pick_place::ManipulationPlan::goal_pose_ |
◆ goal_sampler_
| constraint_samplers::ConstraintSamplerPtr pick_place::ManipulationPlan::goal_sampler_ |
◆ id_
| std::size_t pick_place::ManipulationPlan::id_ |
◆ possible_goal_states_
| std::vector<moveit::core::RobotStatePtr> pick_place::ManipulationPlan::possible_goal_states_ |
◆ processing_stage_
| std::size_t pick_place::ManipulationPlan::processing_stage_ |
◆ retreat_
| moveit_msgs::GripperTranslation pick_place::ManipulationPlan::retreat_ |
◆ retreat_posture_
| trajectory_msgs::JointTrajectory pick_place::ManipulationPlan::retreat_posture_ |
◆ shared_data_
| ManipulationPlanSharedDataConstPtr pick_place::ManipulationPlan::shared_data_ |
◆ trajectories_
◆ transformed_goal_pose_
| Eigen::Isometry3d pick_place::ManipulationPlan::transformed_goal_pose_ |
The documentation for this struct was generated from the following file: