Public Member Functions | Static Public Attributes | Private Attributes | List of all members
pick_place::PickPlace Class Reference

#include <pick_place.h>

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

Public Member Functions

void displayComputedMotionPlans (bool flag)
 
void displayProcessedGrasps (bool flag)
 
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintsSamplerManager () const
 
const planning_pipeline::PlanningPipelinePtr & getPlanningPipeline () const
 
const moveit::core::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. More...
 
PlacePlanPtr planPlace (const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) const
 Plan the sequence of motions that perform a placement action. More...
 
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 145 of file pick_place.h.

Constructor & Destructor Documentation

◆ PickPlace()

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

Definition at line 124 of file pick_place.cpp.

Member Function Documentation

◆ displayComputedMotionPlans()

void pick_place::PickPlace::displayComputedMotionPlans ( bool  flag)

Definition at line 140 of file pick_place.cpp.

◆ displayProcessedGrasps()

void pick_place::PickPlace::displayProcessedGrasps ( bool  flag)

Definition at line 131 of file pick_place.cpp.

◆ getConstraintsSamplerManager()

const constraint_samplers::ConstraintSamplerManagerPtr& pick_place::PickPlace::getConstraintsSamplerManager ( ) const
inline

Definition at line 156 of file pick_place.h.

◆ getPlanningPipeline()

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

Definition at line 161 of file pick_place.h.

◆ getRobotModel()

const moveit::core::RobotModelConstPtr& pick_place::PickPlace::getRobotModel ( ) const
inline

Definition at line 166 of file pick_place.h.

◆ planPick()

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 262 of file pick.cpp.

◆ planPlace()

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 424 of file place.cpp.

◆ visualizeGrasp()

void pick_place::PickPlace::visualizeGrasp ( const ManipulationPlanPtr &  plan) const

Definition at line 169 of file pick_place.cpp.

◆ visualizeGrasps()

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

Definition at line 208 of file pick_place.cpp.

◆ visualizePlan()

void pick_place::PickPlace::visualizePlan ( const ManipulationPlanPtr &  plan) const

Definition at line 149 of file pick_place.cpp.

Member Data Documentation

◆ constraint_sampler_manager_loader_

constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr pick_place::PickPlace::constraint_sampler_manager_loader_
private

Definition at line 196 of file pick_place.h.

◆ DEFAULT_GRASP_POSTURE_COMPLETION_DURATION

const double pick_place::PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION = 7.0
static

Definition at line 152 of file pick_place.h.

◆ display_computed_motion_plans_

bool pick_place::PickPlace::display_computed_motion_plans_
private

Definition at line 191 of file pick_place.h.

◆ DISPLAY_GRASP_TOPIC

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

Definition at line 149 of file pick_place.h.

◆ display_grasps_

bool pick_place::PickPlace::display_grasps_
private

Definition at line 192 of file pick_place.h.

◆ display_path_publisher_

ros::Publisher pick_place::PickPlace::display_path_publisher_
private

Definition at line 193 of file pick_place.h.

◆ DISPLAY_PATH_TOPIC

const std::string pick_place::PickPlace::DISPLAY_PATH_TOPIC = planning_pipeline::PlanningPipeline::DISPLAY_PATH_TOPIC
static

Definition at line 148 of file pick_place.h.

◆ grasps_publisher_

ros::Publisher pick_place::PickPlace::grasps_publisher_
private

Definition at line 194 of file pick_place.h.

◆ nh_

ros::NodeHandle pick_place::PickPlace::nh_
private

Definition at line 189 of file pick_place.h.

◆ planning_pipeline_

planning_pipeline::PlanningPipelinePtr pick_place::PickPlace::planning_pipeline_
private

Definition at line 190 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 Wed Feb 21 2024 03:26:13