MTC
cartesian_path.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: generate and validate a straight-line Cartesian path
37 */
38 
39 #pragma once
40 
41 #include <moveit/task_constructor/solvers/planner_interface.h>
42 #include <moveit/robot_state/cartesian_interpolator.h>
43 
44 namespace moveit {
45 namespace task_constructor {
46 namespace solvers {
47 
48 MOVEIT_CLASS_FORWARD(CartesianPath);
49 
52 {
53 public:
54  CartesianPath();
55 
56  void setIKFrame(const geometry_msgs::PoseStamped& pose) { setProperty("ik_frame", pose); }
57  void setIKFrame(const Eigen::Isometry3d& pose, const std::string& link);
58  void setIKFrame(const std::string& link) { setIKFrame(Eigen::Isometry3d::Identity(), link); }
59 
60  void setStepSize(double step_size) { setProperty("step_size", step_size); }
61  void setPrecision(const moveit::core::CartesianPrecision& precision) { setProperty("precision", precision); }
62  template <typename T = float>
63  void setJumpThreshold(double /*unused*/) {
64  static_assert(std::is_integral<T>::value, "setJumpThreshold() is deprecated. Replace with setPrecision.");
65  }
66  void setMinFraction(double min_fraction) { setProperty("min_fraction", min_fraction); }
67 
68  [[deprecated("Replace with setMaxVelocityScalingFactor")]] // clang-format off
69  void setMaxVelocityScaling(double factor) { setMaxVelocityScalingFactor(factor); } // clang-format on
70  [[deprecated("Replace with setMaxAccelerationScalingFactor")]] // clang-format off
71  void setMaxAccelerationScaling(double factor) { setMaxAccelerationScalingFactor(factor); } // clang-format on
72 
73  void init(const moveit::core::RobotModelConstPtr& robot_model) override;
74 
75  Result plan(const planning_scene::PlanningSceneConstPtr& from, const planning_scene::PlanningSceneConstPtr& to,
76  const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
77  const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
78 
79  Result plan(const planning_scene::PlanningSceneConstPtr& from, const moveit::core::LinkModel& link,
80  const Eigen::Isometry3d& offset, const Eigen::Isometry3d& target,
81  const moveit::core::JointModelGroup* jmg, double timeout, robot_trajectory::RobotTrajectoryPtr& result,
82  const moveit_msgs::Constraints& path_constraints = moveit_msgs::Constraints()) override;
83 };
84 } // namespace solvers
85 } // namespace task_constructor
86 } // namespace moveit
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()) override
plan trajectory between to robot states
Definition: cartesian_path.cpp:73
Definition: planner_interface.h:69