39 #include <moveit/macros/class_forward.h>
40 #include <moveit/task_constructor/container.h>
41 #include <geometry_msgs/TwistStamped.h>
44 namespace task_constructor {
47 MOVEIT_CLASS_FORWARD(CartesianPath);
70 solvers::CartesianPathPtr cartesian_solver_;
71 Stage* grasp_stage_ =
nullptr;
72 Stage* approach_stage_ =
nullptr;
73 Stage* lift_stage_ =
nullptr;
76 PickPlaceBase(Stage::pointer&& grasp_stage,
const std::string& name,
bool forward);
78 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
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); }
83 solvers::CartesianPathPtr cartesianSolver() {
return cartesian_solver_; }
85 void setApproachRetract(
const geometry_msgs::TwistStamped& motion,
double min_distance,
double max_distance);
87 void setLiftPlace(
const geometry_msgs::TwistStamped& motion,
double min_distance,
double max_distance);
88 void setLiftPlace(
const std::map<std::string, double>& joints);
95 Pick(Stage::pointer&& grasp_stage = Stage::pointer(),
const std::string& name =
"pick")
98 void setApproachMotion(
const geometry_msgs::TwistStamped& motion,
double min_distance,
double max_distance) {
99 setApproachRetract(motion, min_distance, max_distance);
102 void setLiftMotion(
const geometry_msgs::TwistStamped& motion,
double min_distance,
double max_distance) {
103 setLiftPlace(motion, min_distance, max_distance);
105 void setLiftMotion(
const std::map<std::string, double>& joints) { setLiftPlace(joints); }
112 Place(Stage::pointer&& ungrasp_stage = Stage::pointer(),
const std::string& name =
"place")
115 void setRetractMotion(
const geometry_msgs::TwistStamped& motion,
double min_distance,
double max_distance) {
116 setApproachRetract(motion, min_distance, max_distance);
119 void setPlaceMotion(
const geometry_msgs::TwistStamped& motion,
double min_distance,
double max_distance) {
120 setLiftPlace(motion, min_distance, max_distance);
122 void setPlaceMotion(
const std::map<std::string, double>& joints) { setLiftPlace(joints); }
void set(const std::string &name, const T &value)
set (and, if neccessary, declare) the value of a property
Definition: properties.h:304
Definition: container.h:96
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