MTC
pick.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018, Bielefeld University
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 Bielefeld University 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 /* Authors: Robert Haschke */
36 
37 #pragma once
38 
39 #include <moveit/macros/class_forward.h>
40 #include <moveit/task_constructor/container.h>
41 #include <geometry_msgs/TwistStamped.h>
42 
43 namespace moveit {
44 namespace task_constructor {
45 
46 namespace solvers {
47 MOVEIT_CLASS_FORWARD(CartesianPath);
48 }
49 
50 namespace stages {
51 
69 {
70  solvers::CartesianPathPtr cartesian_solver_;
71  Stage* grasp_stage_ = nullptr;
72  Stage* approach_stage_ = nullptr;
73  Stage* lift_stage_ = nullptr;
74 
75 public:
76  PickPlaceBase(Stage::pointer&& grasp_stage, const std::string& name, bool forward);
77 
78  void init(const moveit::core::RobotModelConstPtr& robot_model) override;
79 
80  void setEndEffector(const std::string& eef) { properties().set<std::string>("eef", eef); }
81  void setObject(const std::string& object) { properties().set<std::string>("object", object); }
82 
83  solvers::CartesianPathPtr cartesianSolver() { return cartesian_solver_; }
84 
85  void setApproachRetract(const geometry_msgs::TwistStamped& motion, double min_distance, double max_distance);
86 
87  void setLiftPlace(const geometry_msgs::TwistStamped& motion, double min_distance, double max_distance);
88  void setLiftPlace(const std::map<std::string, double>& joints);
89 };
90 
92 class Pick : public PickPlaceBase
93 {
94 public:
95  Pick(Stage::pointer&& grasp_stage = Stage::pointer(), const std::string& name = "pick")
96  : PickPlaceBase(std::move(grasp_stage), name, true) {}
97 
98  void setApproachMotion(const geometry_msgs::TwistStamped& motion, double min_distance, double max_distance) {
99  setApproachRetract(motion, min_distance, max_distance);
100  }
101 
102  void setLiftMotion(const geometry_msgs::TwistStamped& motion, double min_distance, double max_distance) {
103  setLiftPlace(motion, min_distance, max_distance);
104  }
105  void setLiftMotion(const std::map<std::string, double>& joints) { setLiftPlace(joints); }
106 };
107 
109 class Place : public PickPlaceBase
110 {
111 public:
112  Place(Stage::pointer&& ungrasp_stage = Stage::pointer(), const std::string& name = "place")
113  : PickPlaceBase(std::move(ungrasp_stage), name, false) {}
114 
115  void setRetractMotion(const geometry_msgs::TwistStamped& motion, double min_distance, double max_distance) {
116  setApproachRetract(motion, min_distance, max_distance);
117  }
118 
119  void setPlaceMotion(const geometry_msgs::TwistStamped& motion, double min_distance, double max_distance) {
120  setLiftPlace(motion, min_distance, max_distance);
121  }
122  void setPlaceMotion(const std::map<std::string, double>& joints) { setLiftPlace(joints); }
123 };
124 } // namespace stages
125 } // namespace task_constructor
126 } // namespace moveit
void set(const std::string &name, const T &value)
set (and, if neccessary, declare) the value of a property
Definition: properties.h:304
Definition: stage.h:147
PropertyMap & properties()
Get the stage's property map.
Definition: stage.cpp:444
void init(const moveit::core::RobotModelConstPtr &robot_model) override
Definition: pick.cpp:68
specialization of PickPlaceBase to realize picking
Definition: pick.h:93
specialization of PickPlaceBase to realize placing
Definition: pick.h:110