moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_generator.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
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 Pilz GmbH & Co. KG 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 #pragma once
36 
37 #include <sstream>
38 #include <string>
39 
40 #include <Eigen/Geometry>
41 #include <kdl/frames.hpp>
42 #include <kdl/trajectory.hpp>
46 
51 
53 {
54 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(TrajectoryGeneratorInvalidLimitsException,
55  moveit_msgs::msg::MoveItErrorCodes::FAILURE);
56 
57 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(VelocityScalingIncorrect, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
58 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(AccelerationScalingIncorrect,
59  moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
60 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(UnknownPlanningGroup, moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
61 
62 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoJointNamesInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
63 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(SizeMismatchInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
64 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(JointsOfStartStateOutOfRange,
65  moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
66 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NonZeroVelocityInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
67 
68 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NotExactlyOneGoalConstraintGiven,
69  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
70 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OnlyOneGoalTypeAllowed, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
71 
72 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(StartStateGoalStateMismatch,
73  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
74 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(JointConstraintDoesNotBelongToGroup,
75  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
76 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(JointsOfGoalOutOfRange, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
77 
78 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PositionConstraintNameMissing,
79  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
80 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OrientationConstraintNameMissing,
81  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
82 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PositionOrientationConstraintNameMismatch,
83  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
84 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoIKSolverAvailable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
85 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoPrimitivePoseGiven, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
86 
93 {
94 public:
95  TrajectoryGenerator(const moveit::core::RobotModelConstPtr& robot_model,
97  : robot_model_(robot_model), planner_limits_(planner_limits), clock_(std::make_unique<rclcpp::Clock>())
98  {
99  }
100 
101  virtual ~TrajectoryGenerator() = default;
102 
111  bool generate(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
112  planning_interface::MotionPlanResponse& res, double sampling_time = 0.1);
113 
114 protected:
119  {
120  public:
121  MotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req);
122 
123  std::string group_name;
124  std::string link_name;
125  Eigen::Isometry3d start_pose;
126  Eigen::Isometry3d goal_pose;
127  std::map<std::string, double> start_joint_position;
128  std::map<std::string, double> goal_joint_position;
129  std::pair<std::string, Eigen::Vector3d> circ_path_point;
130  planning_scene::PlanningSceneConstPtr start_scene; // scene with updated start state
131  };
132 
141  std::unique_ptr<KDL::VelocityProfile> cartesianTrapVelocityProfile(const double& max_velocity_scaling_factor,
142  const double& max_acceleration_scaling_factor,
143  const std::unique_ptr<KDL::Path>& path) const;
144 
145 private:
146  virtual void cmdSpecificRequestValidation(const planning_interface::MotionPlanRequest& req) const;
147 
157  virtual void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene,
158  const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const = 0;
159 
160  virtual void plan(const planning_scene::PlanningSceneConstPtr& scene,
161  const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
162  const double& sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory) = 0;
163 
164 private:
206  void validateRequest(const planning_interface::MotionPlanRequest& req, const moveit::core::RobotState& rstate) const;
207 
211  void setSuccessResponse(const moveit::core::RobotState& start_rs, const std::string& group_name,
212  const trajectory_msgs::msg::JointTrajectory& joint_trajectory,
213  const rclcpp::Time& planning_start, planning_interface::MotionPlanResponse& res) const;
214 
215  void setFailureResponse(const rclcpp::Time& planning_start, planning_interface::MotionPlanResponse& res) const;
216 
217  void checkForValidGroupName(const std::string& group_name) const;
218 
230  void checkStartState(const moveit_msgs::msg::RobotState& start_state, const std::string& group) const;
231 
232  void checkGoalConstraints(const moveit_msgs::msg::MotionPlanRequest::_goal_constraints_type& goal_constraints,
233  const std::string& group_name, const moveit::core::RobotState& rstate) const;
234 
235  void checkJointGoalConstraint(const moveit_msgs::msg::Constraints& constraint, const std::string& group_name) const;
236 
237  void checkCartesianGoalConstraint(const moveit_msgs::msg::Constraints& constraint,
238  const moveit::core::RobotState& robot_state,
239  const moveit::core::JointModelGroup* const jmg) const;
240 
241 private:
245  sensor_msgs::msg::JointState filterGroupValues(const sensor_msgs::msg::JointState& robot_state,
246  const std::string& group) const;
247 
251  static bool isScalingFactorValid(const double& scaling_factor);
252  static void checkVelocityScaling(const double& scaling_factor);
253  static void checkAccelerationScaling(const double& scaling_factor);
254 
259  static bool isCartesianGoalGiven(const moveit_msgs::msg::Constraints& constraint);
260 
264  static bool isJointGoalGiven(const moveit_msgs::msg::Constraints& constraint);
265 
270  static bool isOnlyOneGoalTypeGiven(const moveit_msgs::msg::Constraints& constraint);
271 
272 protected:
273  const moveit::core::RobotModelConstPtr robot_model_;
275  static constexpr double MIN_SCALING_FACTOR{ 0.0001 };
276  static constexpr double MAX_SCALING_FACTOR{ 1. };
277  static constexpr double VELOCITY_TOLERANCE{ 1e-8 };
278  const std::unique_ptr<rclcpp::Clock> clock_;
279 };
280 
281 inline bool TrajectoryGenerator::isScalingFactorValid(const double& scaling_factor)
282 {
283  return (scaling_factor > MIN_SCALING_FACTOR && scaling_factor <= MAX_SCALING_FACTOR);
284 }
285 
286 inline bool TrajectoryGenerator::isCartesianGoalGiven(const moveit_msgs::msg::Constraints& constraint)
287 {
288  return constraint.position_constraints.size() == 1 && constraint.orientation_constraints.size() == 1;
289 }
290 
291 inline bool TrajectoryGenerator::isJointGoalGiven(const moveit_msgs::msg::Constraints& constraint)
292 {
293  return !constraint.joint_constraints.empty();
294 }
295 
296 inline bool TrajectoryGenerator::isOnlyOneGoalTypeGiven(const moveit_msgs::msg::Constraints& constraint)
297 {
298  return (isJointGoalGiven(constraint) && !isCartesianGoalGiven(constraint)) ||
299  (!isJointGoalGiven(constraint) && isCartesianGoalGiven(constraint));
300 }
301 
302 } // namespace pilz_industrial_motion_planner
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
This class combines CartesianLimit and JointLimits into on single class.
This class is used to extract needed information from motion plan request.
MotionPlanInfo(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req)
const moveit::core::RobotModelConstPtr robot_model_
TrajectoryGenerator(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
bool generate(const planning_scene::PlanningSceneConstPtr &scene, const planning_interface::MotionPlanRequest &req, planning_interface::MotionPlanResponse &res, double sampling_time=0.1)
generate robot trajectory with given sampling time
std::unique_ptr< KDL::VelocityProfile > cartesianTrapVelocityProfile(const double &max_velocity_scaling_factor, const double &max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const
build cartesian velocity profile for the path
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
const std::unique_ptr< rclcpp::Clock > clock_
scene
Definition: pick.py:52
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
Definition: plan.py:1
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest