MTC
move_to.h
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2017, 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: Michael Goerner, Robert Haschke
36  Desc: Move to joint-state or Cartesian goal pose
37 */
38 
39 #pragma once
40 
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>
46 
47 namespace moveit {
48 namespace core {
49 class RobotState;
50 }
51 } // namespace moveit
52 namespace moveit {
53 namespace task_constructor {
54 namespace stages {
55 
57 {
58 public:
59  MoveTo(const std::string& name = "move to",
60  const solvers::PlannerInterfacePtr& planner = solvers::PlannerInterfacePtr());
61 
62  void init(const moveit::core::RobotModelConstPtr& robot_model) override;
63 
64  void setGroup(const std::string& group) { setProperty("group", group); }
66  void setIKFrame(const geometry_msgs::PoseStamped& pose) { setProperty("ik_frame", pose); }
67  void setIKFrame(const Eigen::Isometry3d& pose, const std::string& link);
68  template <typename T>
69  void setIKFrame(const T& pose, const std::string& link) {
70  setIKFrame(Eigen::Isometry3d(pose), link);
71  }
72  void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
73 
75  void setGoal(const geometry_msgs::PoseStamped& pose) { setProperty("goal", pose); }
76 
78  void setGoal(const geometry_msgs::PointStamped& point) { setProperty("goal", point); }
79 
81  void setGoal(const std::string& named_joint_pose) { setProperty("goal", named_joint_pose); }
82 
84  void setGoal(const moveit_msgs::RobotState& robot_state) { setProperty("goal", robot_state); }
85 
87  void setGoal(const std::map<std::string, double>& joints);
88 
89  void setPathConstraints(moveit_msgs::Constraints path_constraints) {
90  setProperty("path_constraints", std::move(path_constraints));
91  }
92 
93 protected:
94  // return false if trajectory shouldn't be stored
95  bool compute(const InterfaceState& state, planning_scene::PlanningScenePtr& scene, SubTrajectory& trajectory,
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);
102 
103 protected:
104  solvers::PlannerInterfacePtr planner_;
105 };
106 } // namespace stages
107 } // namespace task_constructor
108 } // namespace moveit
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