MTC
planner_interface.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: Robert Haschke
36  Desc: planner interface
37 */
38 
39 #pragma once
40 
41 #include <moveit/macros/class_forward.h>
42 #include <moveit_msgs/Constraints.h>
43 #include <moveit/task_constructor/properties.h>
44 #include <Eigen/Geometry>
45 
46 namespace planning_scene {
47 MOVEIT_CLASS_FORWARD(PlanningScene);
48 }
49 namespace robot_trajectory {
50 MOVEIT_CLASS_FORWARD(RobotTrajectory);
51 }
52 namespace trajectory_processing {
53 MOVEIT_CLASS_FORWARD(TimeParameterization);
54 }
55 namespace moveit {
56 namespace core {
57 MOVEIT_CLASS_FORWARD(LinkModel);
58 MOVEIT_CLASS_FORWARD(RobotModel);
59 MOVEIT_CLASS_FORWARD(JointModelGroup);
60 } // namespace core
61 } // namespace moveit
62 
63 namespace moveit {
64 namespace task_constructor {
65 namespace solvers {
66 
67 MOVEIT_CLASS_FORWARD(PlannerInterface);
69 {
70  // these properties take precedence over stage properties
71  PropertyMap properties_;
72 
73 public:
74  struct Result
75  {
76  bool success;
77  std::string message;
78 
79  operator bool() const { return success; }
80  };
81 
83  virtual ~PlannerInterface() {}
84 
85  PropertyMap& properties() { return properties_; }
86  const PropertyMap& properties() const { return properties_; }
87 
88  void setProperty(const std::string& name, const boost::any& value) { properties_.set(name, value); }
89  void setTimeout(double timeout) { properties_.set("timeout", timeout); }
90  void setMaxVelocityScalingFactor(double factor) { properties_.set("max_velocity_scaling_factor", factor); }
91  void setMaxAccelerationScalingFactor(double factor) { properties_.set("max_acceleration_scaling_factor", factor); }
92  void setTimeParameterization(const trajectory_processing::TimeParameterizationPtr& tp) {
93  properties_.set("time_parameterization", tp);
94  }
95 
96  virtual void init(const moveit::core::RobotModelConstPtr& robot_model) = 0;
97 
99  virtual Result plan(const planning_scene::PlanningSceneConstPtr& from,
100  const planning_scene::PlanningSceneConstPtr& to, const moveit::core::JointModelGroup* jmg,
101  double timeout, robot_trajectory::RobotTrajectoryPtr& result,
102  const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) = 0;
103 
105  virtual Result plan(const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
106  const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target,
107  const moveit::core::JointModelGroup* jmg, double timeout,
108  robot_trajectory::RobotTrajectoryPtr& result,
109  const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) = 0;
110 };
111 } // namespace solvers
112 } // namespace task_constructor
113 } // namespace moveit
Definition: properties.h:257
void set(const std::string &name, const T &value)
set (and, if neccessary, declare) the value of a property
Definition: properties.h:304
Definition: planner_interface.h:69
virtual Result plan(const planning_scene::PlanningSceneConstPtr &from, const moveit::core::LinkModel &link, const Eigen::Isometry3d &offset, const Eigen::Isometry3d &target, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints())=0
plan trajectory from current robot state to Cartesian target, such that pose(link)*offset == target
virtual Result plan(const planning_scene::PlanningSceneConstPtr &from, const planning_scene::PlanningSceneConstPtr &to, const moveit::core::JointModelGroup *jmg, double timeout, robot_trajectory::RobotTrajectoryPtr &result, const moveit_msgs::Constraints &path_constraints=moveit_msgs::Constraints())=0
plan trajectory between to robot states