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/PoseStamped.h>
45 #include <geometry_msgs/PointStamped.h>
53 namespace task_constructor {
59 MoveTo(
const std::string& name =
"move to",
60 const solvers::PlannerInterfacePtr& planner = solvers::PlannerInterfacePtr());
62 void init(
const moveit::core::RobotModelConstPtr& robot_model)
override;
64 void setGroup(
const std::string& group) {
setProperty(
"group", group); }
67 void setIKFrame(
const Eigen::Isometry3d& pose,
const std::string& link);
69 void setIKFrame(
const T& pose,
const std::string& link) {
87 void setGoal(
const std::map<std::string, double>& joints);
89 void setPathConstraints(moveit_msgs::Constraints path_constraints) {
90 setProperty(
"path_constraints", std::move(path_constraints));
96 Interface::Direction dir)
override;
97 bool getJointStateGoal(
const boost::any& goal,
const core::JointModelGroup* jmg, moveit::core::RobotState& state);
98 bool getPoseGoal(
const boost::any& goal,
const planning_scene::PlanningScenePtr& scene,
99 Eigen::Isometry3d& target_eigen);
100 bool getPointGoal(
const boost::any& goal,
const Eigen::Isometry3d& ik_pose,
101 const planning_scene::PlanningScenePtr& scene, Eigen::Isometry3d& target_eigen);
104 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
void init(const moveit::core::RobotModelConstPtr &robot_model) override
Definition: move_to.cpp:92
void setIKFrame(const geometry_msgs::PoseStamped &pose)
setters for IK frame
Definition: move_to.h:66
void setGoal(const geometry_msgs::PointStamped &point)
move link to given point, keeping current orientation
Definition: move_to.h:78
void setGoal(const moveit_msgs::RobotState &robot_state)
move joints specified in msg to their target values
Definition: move_to.h:84
void setGoal(const std::string &named_joint_pose)
move joint model group to given named pose
Definition: move_to.h:81
void setGoal(const geometry_msgs::PoseStamped &pose)
move link to given pose
Definition: move_to.h:75