MTC
move_relative.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/TwistStamped.h>
45 #include <geometry_msgs/Vector3Stamped.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 
58 {
59 public:
60  MoveRelative(const std::string& name = "move relative",
61  const solvers::PlannerInterfacePtr& planner = solvers::PlannerInterfacePtr());
62 
63  void init(const moveit::core::RobotModelConstPtr& robot_model) override;
64 
65  void setGroup(const std::string& group) { setProperty("group", group); }
67  void setIKFrame(const geometry_msgs::PoseStamped& pose) { setProperty("ik_frame", pose); }
68  void setIKFrame(const Eigen::Isometry3d& pose, const std::string& link);
69  template <typename T>
70  void setIKFrame(const T& p, const std::string& link) {
71  Eigen::Isometry3d pose;
72  pose = p;
73  setIKFrame(pose, link);
74  }
75  void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
76 
78  void setMinDistance(double distance) { setProperty("min_distance", distance); }
79  void setMaxDistance(double distance) { setProperty("max_distance", distance); }
80  void setMinMaxDistance(double min_distance, double max_distance) {
81  setProperty("min_distance", min_distance);
82  setProperty("max_distance", max_distance);
83  }
84 
85  void setPathConstraints(moveit_msgs::Constraints path_constraints) {
86  setProperty("path_constraints", std::move(path_constraints));
87  }
88 
90  void setDirection(const geometry_msgs::TwistStamped& twist) { setProperty("direction", twist); }
92  void setDirection(const geometry_msgs::Vector3Stamped& direction) { setProperty("direction", direction); }
94  void setDirection(const std::map<std::string, double>& joint_deltas) { setProperty("direction", joint_deltas); }
95 
96 protected:
97  // return false if trajectory shouldn't be stored
98  bool compute(const InterfaceState& state, planning_scene::PlanningScenePtr& scene, SubTrajectory& trajectory,
99  Interface::Direction dir) override;
100 
101 protected:
102  solvers::PlannerInterfacePtr planner_;
103 };
104 } // namespace stages
105 } // namespace task_constructor
106 } // 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 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