pick_place.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
44 #include <moveit_msgs/PickupAction.h>
45 #include <moveit_msgs/PlaceAction.h>
46 #include <boost/noncopyable.hpp>
47 #include <memory>
48 
49 namespace pick_place
50 {
51 MOVEIT_CLASS_FORWARD(PickPlace); // Defines PickPlacePtr, ConstPtr, WeakPtr... etc
52 
53 class PickPlacePlanBase
54 {
55 public:
56  PickPlacePlanBase(const PickPlaceConstPtr& pick_place, const std::string& name);
58 
59  const std::vector<ManipulationPlanPtr>& getSuccessfulManipulationPlans() const
60  {
62  }
63  const std::vector<ManipulationPlanPtr>& getFailedManipulationPlans() const
64  {
66  }
67 
68  const moveit_msgs::MoveItErrorCodes& getErrorCode() const
69  {
70  return error_code_;
71  }
72 
73  double getLastPlanTime() const
74  {
75  return last_plan_time_;
76  }
77 
78 protected:
79  void initialize();
80  void waitForPipeline(const ros::WallTime& endtime);
81  void foundSolution();
82  void emptyQueue();
83 
84  PickPlaceConstPtr pick_place_;
86 
87  double last_plan_time_;
88  bool done_;
89  bool pushed_all_poses_;
90  boost::condition_variable done_condition_;
91  boost::mutex done_mutex_;
92  moveit_msgs::MoveItErrorCodes error_code_;
93 };
94 
95 MOVEIT_CLASS_FORWARD(PickPlan); // Defines PickPlanPtr, ConstPtr, WeakPtr... etc
96 
97 class PickPlan : public PickPlacePlanBase
98 {
99 public:
100  PickPlan(const PickPlaceConstPtr& pick_place);
101  bool plan(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::PickupGoal& goal);
102 };
103 
104 MOVEIT_CLASS_FORWARD(PlacePlan); // Defines PlacePlanPtr, ConstPtr, WeakPtr... etc
105 
106 class PlacePlan : public PickPlacePlanBase
107 {
108 public:
109  PlacePlan(const PickPlaceConstPtr& pick_place);
110  bool plan(const planning_scene::PlanningSceneConstPtr& planning_scene, const moveit_msgs::PlaceGoal& goal);
111 };
112 
113 class PickPlace : private boost::noncopyable, public std::enable_shared_from_this<PickPlace>
114 {
115 public:
116  static const std::string DISPLAY_PATH_TOPIC;
117  static const std::string DISPLAY_GRASP_TOPIC;
118 
119  // the amount of time (maximum) to wait for achieving a grasp posture
120  static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION; // seconds
121 
122  PickPlace(const planning_pipeline::PlanningPipelinePtr& planning_pipeline);
123 
124  const constraint_samplers::ConstraintSamplerManagerPtr& getConstraintsSamplerManager() const
125  {
126  return constraint_sampler_manager_loader_->getConstraintSamplerManager();
127  }
128 
129  const planning_pipeline::PlanningPipelinePtr& getPlanningPipeline() const
130  {
131  return planning_pipeline_;
132  }
133 
134  const moveit::core::RobotModelConstPtr& getRobotModel() const
135  {
136  return planning_pipeline_->getRobotModel();
137  }
138 
140  PickPlanPtr planPick(const planning_scene::PlanningSceneConstPtr& planning_scene,
141  const moveit_msgs::PickupGoal& goal) const;
142 
144  PlacePlanPtr planPlace(const planning_scene::PlanningSceneConstPtr& planning_scene,
145  const moveit_msgs::PlaceGoal& goal) const;
146 
147  void displayComputedMotionPlans(bool flag);
148  void displayProcessedGrasps(bool flag);
149 
150  void visualizePlan(const ManipulationPlanPtr& plan) const;
151 
152  void visualizeGrasp(const ManipulationPlanPtr& plan) const;
153 
154  void visualizeGrasps(const std::vector<ManipulationPlanPtr>& plans) const;
155 
156 private:
158  planning_pipeline::PlanningPipelinePtr planning_pipeline_;
160  bool display_grasps_;
163 
164  constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_;
165 };
166 } // namespace pick_place
pick_place::PickPlacePlanBase::error_code_
moveit_msgs::MoveItErrorCodes error_code_
Definition: pick_place.h:124
pick_place::PickPlace::getRobotModel
const moveit::core::RobotModelConstPtr & getRobotModel() const
Definition: pick_place.h:166
pick_place
Definition: approach_and_translate_stage.h:43
ros::Publisher
pick_place::PlacePlan::PlacePlan
PlacePlan(const PickPlaceConstPtr &pick_place)
Definition: place.cpp:80
pick_place::PickPlan::plan
bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal)
Definition: pick.cpp:99
pick_place::PickPlacePlanBase::pushed_all_poses_
bool pushed_all_poses_
Definition: pick_place.h:121
pick_place::PickPlacePlanBase::last_plan_time_
double last_plan_time_
Definition: pick_place.h:119
pick_place::PickPlace::displayProcessedGrasps
void displayProcessedGrasps(bool flag)
Definition: pick_place.cpp:131
pick_place::PickPlacePlanBase::done_mutex_
boost::mutex done_mutex_
Definition: pick_place.h:123
pick_place::PickPlacePlanBase::getFailedManipulationPlans
const std::vector< ManipulationPlanPtr > & getFailedManipulationPlans() const
Definition: pick_place.h:95
pick_place::PickPlace
Definition: pick_place.h:145
pick_place::PlacePlan
Definition: pick_place.h:138
pick_place::ManipulationPipeline
Represent the sequence of steps that are executed for a manipulation plan.
Definition: manipulation_pipeline.h:80
pick_place::PickPlace::display_grasps_
bool display_grasps_
Definition: pick_place.h:192
pick_place::ManipulationPipeline::getSuccessfulManipulationPlans
const std::vector< ManipulationPlanPtr > & getSuccessfulManipulationPlans() const
Definition: manipulation_pipeline.h:147
pick_place::PickPlace::nh_
ros::NodeHandle nh_
Definition: pick_place.h:189
pick_place::PickPlace::planning_pipeline_
planning_pipeline::PlanningPipelinePtr planning_pipeline_
Definition: pick_place.h:190
pick_place::PickPlacePlanBase::initialize
void initialize()
Definition: pick_place.cpp:109
pick_place::PickPlace::display_computed_motion_plans_
bool display_computed_motion_plans_
Definition: pick_place.h:191
pick_place::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(ManipulationStage)
pick_place::PickPlacePlanBase::pipeline_
ManipulationPipeline pipeline_
Definition: pick_place.h:117
pick_place::PickPlacePlanBase
Definition: pick_place.h:85
pick_place::PickPlacePlanBase::getLastPlanTime
double getLastPlanTime() const
Definition: pick_place.h:105
pick_place::PickPlacePlanBase::getErrorCode
const moveit_msgs::MoveItErrorCodes & getErrorCode() const
Definition: pick_place.h:100
pick_place::PickPlace::display_path_publisher_
ros::Publisher display_path_publisher_
Definition: pick_place.h:193
pick_place::PickPlan::PickPlan
PickPlan(const PickPlaceConstPtr &pick_place)
Definition: pick.cpp:78
pick_place::PickPlace::getPlanningPipeline
const planning_pipeline::PlanningPipelinePtr & getPlanningPipeline() const
Definition: pick_place.h:161
pick_place::PickPlace::constraint_sampler_manager_loader_
constraint_sampler_manager_loader::ConstraintSamplerManagerLoaderPtr constraint_sampler_manager_loader_
Definition: pick_place.h:196
pick_place::PickPlace::DISPLAY_GRASP_TOPIC
static const std::string DISPLAY_GRASP_TOPIC
Definition: pick_place.h:149
pick_place::PickPlace::planPick
PickPlanPtr planPick(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PickupGoal &goal) const
Plan the sequence of motions that perform a pickup action.
Definition: pick.cpp:262
pick_place::PickPlace::DISPLAY_PATH_TOPIC
static const std::string DISPLAY_PATH_TOPIC
Definition: pick_place.h:148
pick_place::PickPlacePlanBase::foundSolution
void foundSolution()
Definition: pick_place.cpp:92
pick_place::PickPlace::visualizeGrasp
void visualizeGrasp(const ManipulationPlanPtr &plan) const
Definition: pick_place.cpp:169
pick_place::PickPlacePlanBase::emptyQueue
void emptyQueue()
Definition: pick_place.cpp:99
pick_place::PickPlacePlanBase::done_condition_
boost::condition_variable done_condition_
Definition: pick_place.h:122
ros::WallTime
planning_pipeline.h
pick_place::PickPlacePlanBase::~PickPlacePlanBase
~PickPlacePlanBase()
pick_place::PickPlace::planPlace
PlacePlanPtr planPlace(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal) const
Plan the sequence of motions that perform a placement action.
Definition: place.cpp:424
planning_pipeline
pick_place::PickPlace::grasps_publisher_
ros::Publisher grasps_publisher_
Definition: pick_place.h:194
constraint_sampler_manager_loader.h
pick_place::PickPlace::DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
static const double DEFAULT_GRASP_POSTURE_COMPLETION_DURATION
Definition: pick_place.h:152
class_forward.h
pick_place::PickPlace::visualizeGrasps
void visualizeGrasps(const std::vector< ManipulationPlanPtr > &plans) const
Definition: pick_place.cpp:208
pick_place::PickPlace::displayComputedMotionPlans
void displayComputedMotionPlans(bool flag)
Definition: pick_place.cpp:140
pick_place::PickPlacePlanBase::getSuccessfulManipulationPlans
const std::vector< ManipulationPlanPtr > & getSuccessfulManipulationPlans() const
Definition: pick_place.h:91
manipulation_pipeline.h
planning_scene
pick_place::PickPlace::getConstraintsSamplerManager
const constraint_samplers::ConstraintSamplerManagerPtr & getConstraintsSamplerManager() const
Definition: pick_place.h:156
pick_place::PickPlace::visualizePlan
void visualizePlan(const ManipulationPlanPtr &plan) const
Definition: pick_place.cpp:149
pick_place::PlacePlan::plan
bool plan(const planning_scene::PlanningSceneConstPtr &planning_scene, const moveit_msgs::PlaceGoal &goal)
Definition: place.cpp:116
pick_place::PickPlacePlanBase::waitForPipeline
void waitForPipeline(const ros::WallTime &endtime)
Definition: pick_place.cpp:115
pick_place::PickPlacePlanBase::PickPlacePlanBase
PickPlacePlanBase(const PickPlaceConstPtr &pick_place, const std::string &name)
Definition: pick_place.cpp:83
pick_place_params.h
pick_place::PickPlace::PickPlace
PickPlace(const planning_pipeline::PlanningPipelinePtr &planning_pipeline)
Definition: pick_place.cpp:124
pick_place::PickPlacePlanBase::pick_place_
PickPlaceConstPtr pick_place_
Definition: pick_place.h:116
pick_place::ManipulationPipeline::getFailedManipulationPlans
const std::vector< ManipulationPlanPtr > & getFailedManipulationPlans() const
Definition: manipulation_pipeline.h:152
pick_place::PickPlan
Definition: pick_place.h:129
ros::NodeHandle
pick_place::PickPlacePlanBase::done_
bool done_
Definition: pick_place.h:120


manipulation
Author(s): Ioan Sucan , Sachin Chitta
autogenerated on Fri May 3 2024 02:29:51