41 #include <moveit/task_constructor/stage.h>
42 #include <moveit/task_constructor/solvers/planner_interface.h>
43 #include <moveit_msgs/Constraints.h>
44 #include <geometry_msgs/TwistStamped.h>
45 #include <geometry_msgs/Vector3Stamped.h>
53 namespace task_constructor {
61 const solvers::PlannerInterfacePtr& planner = solvers::PlannerInterfacePtr());
63 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
65 void setGroup(
const std::string& group) {
setProperty(
"group", group); }
68 void setIKFrame(
const Eigen::Isometry3d& pose,
const std::string& link);
70 void setIKFrame(
const T& p,
const std::string& link) {
71 Eigen::Isometry3d pose;
79 void setMaxDistance(
double distance) {
setProperty(
"max_distance", distance); }
80 void setMinMaxDistance(
double min_distance,
double max_distance) {
85 void setPathConstraints(moveit_msgs::Constraints path_constraints) {
86 setProperty(
"path_constraints", std::move(path_constraints));
99 Interface::Direction dir)
override;
102 solvers::PlannerInterfacePtr planner_;
void setProperty(const std::string &name, const boost::any &value)
Set a previously declared property to a new value.
Definition: stage.cpp:448
SubTrajectory connects interface states of ComputeStages.
Definition: storage.h:348
Definition: move_relative.h:58
void setMinDistance(double distance)
set minimum / maximum distance to move
Definition: move_relative.h:78
void setDirection(const std::map< std::string, double > &joint_deltas)
move specified joint variables by given amount
Definition: move_relative.h:94
void setDirection(const geometry_msgs::TwistStamped &twist)
perform twist motion on specified link
Definition: move_relative.h:90
void init(const moveit::core::RobotModelConstPtr &robot_model) override
Definition: move_relative.cpp:77
void setDirection(const geometry_msgs::Vector3Stamped &direction)
translate link along given direction
Definition: move_relative.h:92
void setIKFrame(const geometry_msgs::PoseStamped &pose)
setters for IK frame
Definition: move_relative.h:67