41 #include <moveit/task_constructor/stages/generate_pose.h>
44 namespace task_constructor {
52 void init(
const core::RobotModelConstPtr& robot_model)
override;
53 void compute()
override;
55 void setEndEffector(
const std::string& eef) {
setProperty(
"eef", eef); }
56 void setObject(
const std::string&
object) {
setProperty(
"object",
object); }
57 void setAngleDelta(
double delta) {
setProperty(
"angle_delta", delta); }
58 void setRotationAxis(
const Eigen::Vector3d& axis) {
setProperty(
"rotation_axis", axis); }
60 void setPreGraspPose(
const std::string& pregrasp) {
properties().
set(
"pregrasp", pregrasp); }
61 void setPreGraspPose(
const moveit_msgs::RobotState& pregrasp) {
properties().
set(
"pregrasp", pregrasp); }
62 void setGraspPose(
const std::string& grasp) {
properties().
set(
"grasp", grasp); }
63 void setGraspPose(
const moveit_msgs::RobotState& grasp) {
properties().
set(
"grasp", grasp); }
void set(const std::string &name, const T &value)
set (and, if neccessary, declare) the value of a property
Definition: properties.h:304
abstract base class for solutions (primitive and sequences)
Definition: storage.h:269
PropertyMap & properties()
Get the stage's property map.
Definition: stage.cpp:444
void setProperty(const std::string &name, const boost::any &value)
Set a previously declared property to a new value.
Definition: stage.cpp:448
Definition: generate_grasp_pose.h:48
void onNewSolution(const SolutionBase &s) override
called by monitored stage when a new solution was generated
Definition: generate_grasp_pose.cpp:130
Definition: generate_pose.h:50