Public Member Functions | Static Public Attributes | Private Attributes
pick_place::PickPlace Class Reference

#include <pick_place.h>

Inheritance diagram for pick_place::PickPlace:
Inheritance graph
[legend]

List of all members.

Public Member Functions

void displayComputedMotionPlans (bool flag)
void displayProcessedGrasps (bool flag)
const
constraint_samplers::ConstraintSamplerManagerPtr
getConstraintsSamplerManager () const
const
planning_pipeline::PlanningPipelinePtr & 
getPlanningPipeline () const
const
robot_model::RobotModelConstPtr
getRobotModel () const
 PickPlace (const planning_pipeline::PlanningPipelinePtr &planning_pipeline)
PickPlanPtr planPick (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal) const
 Plan the sequence of motions that perform a pickup action.
PlacePlanPtr planPlace (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) const
 Plan the sequence of motions that perform a placement action.
void visualizeGrasp (const ManipulationPlanPtr &plan) const
void visualizeGrasps (const std::vector< ManipulationPlanPtr > &plans) const
void visualizePlan (const ManipulationPlanPtr &plan) const

Static Public Attributes

static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION = 7.0
static const std::string DISPLAY_GRASP_TOPIC = "display_grasp_markers"
static const std::string DISPLAY_PATH_TOPIC = planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC

Private Attributes

constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
bool display_computed_motion_plans_
bool display_grasps_
ros::Publisher display_path_publisher_
ros::Publisher grasps_publisher_
ros::NodeHandle nh_
planning_pipeline::PlanningPipelinePtr planning_pipeline_

Detailed Description

Definition at line 122 of file pick_place.h.


Constructor & Destructor Documentation

pick_place::PickPlace::PickPlace ( const planning_pipeline::PlanningPipelinePtr &  planning_pipeline)

Definition at line 100 of file pick_place.cpp.


Member Function Documentation

Definition at line 119 of file pick_place.cpp.

Definition at line 109 of file pick_place.cpp.

Definition at line 135 of file pick_place.h.

const planning_pipeline::PlanningPipelinePtr& pick_place::PickPlace::getPlanningPipeline ( ) const [inline]

Definition at line 140 of file pick_place.h.

Definition at line 145 of file pick_place.h.

PickPlanPtr pick_place::PickPlace::planPick ( const planning_scene::PlanningSceneConstPtr planning_scene,
const moveit_msgs::PickupGoal &  goal 
) const

Plan the sequence of motions that perform a pickup action.

Definition at line 214 of file pick.cpp.

PlacePlanPtr pick_place::PickPlace::planPlace ( const planning_scene::PlanningSceneConstPtr planning_scene,
const moveit_msgs::PlaceGoal &  goal 
) const

Plan the sequence of motions that perform a placement action.

Definition at line 248 of file place.cpp.

Definition at line 149 of file pick_place.cpp.

void pick_place::PickPlace::visualizeGrasps ( const std::vector< ManipulationPlanPtr > &  plans) const

Definition at line 172 of file pick_place.cpp.

Definition at line 129 of file pick_place.cpp.


Member Data Documentation

Definition at line 174 of file pick_place.h.

Definition at line 131 of file pick_place.h.

Definition at line 169 of file pick_place.h.

const std::string pick_place::PickPlace::DISPLAY_GRASP_TOPIC = "display_grasp_markers" [static]

Definition at line 128 of file pick_place.h.

Definition at line 170 of file pick_place.h.

Definition at line 171 of file pick_place.h.

Definition at line 127 of file pick_place.h.

Definition at line 172 of file pick_place.h.

Definition at line 167 of file pick_place.h.

planning_pipeline::PlanningPipelinePtr pick_place::PickPlace::planning_pipeline_ [private]

Definition at line 168 of file pick_place.h.


The documentation for this class was generated from the following files:


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Mon Oct 6 2014 02:33:06