#include <manipulation_plan.h>
Public Member Functions | |
ManipulationPlanSharedData () | |
Public Attributes | |
moveit_msgs::AttachedCollisionObject | diff_attached_object_ |
const moveit::core::JointModelGroup * | end_effector_group_ |
const moveit::core::LinkModel * | ik_link_ |
unsigned int | max_goal_sampling_attempts_ |
bool | minimize_object_distance_ |
moveit_msgs::Constraints | path_constraints_ |
std::string | planner_id_ |
const moveit::core::JointModelGroup * | planning_group_ |
ros::WallTime | timeout_ |
Definition at line 87 of file manipulation_plan.h.
|
inline |
Definition at line 89 of file manipulation_plan.h.
moveit_msgs::AttachedCollisionObject pick_place::ManipulationPlanSharedData::diff_attached_object_ |
Definition at line 110 of file manipulation_plan.h.
const moveit::core::JointModelGroup* pick_place::ManipulationPlanSharedData::end_effector_group_ |
Definition at line 99 of file manipulation_plan.h.
const moveit::core::LinkModel* pick_place::ManipulationPlanSharedData::ik_link_ |
Definition at line 100 of file manipulation_plan.h.
unsigned int pick_place::ManipulationPlanSharedData::max_goal_sampling_attempts_ |
Definition at line 102 of file manipulation_plan.h.
bool pick_place::ManipulationPlanSharedData::minimize_object_distance_ |
Definition at line 106 of file manipulation_plan.h.
moveit_msgs::Constraints pick_place::ManipulationPlanSharedData::path_constraints_ |
Definition at line 108 of file manipulation_plan.h.
std::string pick_place::ManipulationPlanSharedData::planner_id_ |
Definition at line 104 of file manipulation_plan.h.
const moveit::core::JointModelGroup* pick_place::ManipulationPlanSharedData::planning_group_ |
Definition at line 98 of file manipulation_plan.h.
ros::WallTime pick_place::ManipulationPlanSharedData::timeout_ |
Definition at line 112 of file manipulation_plan.h.