moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
trajectory_generator.hpp
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{
54CREATE_MOVEIT_ERROR_CODE_EXCEPTION(TrajectoryGeneratorInvalidLimitsException,
55 moveit_msgs::msg::MoveItErrorCodes::FAILURE);
56
57CREATE_MOVEIT_ERROR_CODE_EXCEPTION(VelocityScalingIncorrect, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
58CREATE_MOVEIT_ERROR_CODE_EXCEPTION(AccelerationScalingIncorrect,
59 moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
60CREATE_MOVEIT_ERROR_CODE_EXCEPTION(UnknownPlanningGroup, moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME);
61
62CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoJointNamesInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
63CREATE_MOVEIT_ERROR_CODE_EXCEPTION(SizeMismatchInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
64CREATE_MOVEIT_ERROR_CODE_EXCEPTION(JointsOfStartStateOutOfRange,
65 moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
66CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NonZeroVelocityInStartState, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
67
68CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NotExactlyOneGoalConstraintGiven,
69 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
70CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OnlyOneGoalTypeAllowed, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
71
72CREATE_MOVEIT_ERROR_CODE_EXCEPTION(StartStateGoalStateMismatch,
73 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
74CREATE_MOVEIT_ERROR_CODE_EXCEPTION(JointConstraintDoesNotBelongToGroup,
75 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
76CREATE_MOVEIT_ERROR_CODE_EXCEPTION(JointsOfGoalOutOfRange, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
77
78CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PositionConstraintNameMissing,
79 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
80CREATE_MOVEIT_ERROR_CODE_EXCEPTION(OrientationConstraintNameMissing,
81 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
82CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PositionOrientationConstraintNameMismatch,
83 moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
84CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoIKSolverAvailable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
85CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoPrimitivePoseGiven, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
86
93{
94public:
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
109 void generate(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
110 planning_interface::MotionPlanResponse& res, double sampling_time = 0.1);
111
112protected:
117 {
118 public:
119 MotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req);
120
121 std::string group_name;
122 std::string link_name;
123 Eigen::Isometry3d start_pose;
124 Eigen::Isometry3d goal_pose;
125 std::map<std::string, double> start_joint_position;
126 std::map<std::string, double> goal_joint_position;
127 std::pair<std::string, Eigen::Vector3d> circ_path_point;
128 planning_scene::PlanningSceneConstPtr start_scene; // scene with updated start state
129 };
130
139 std::unique_ptr<KDL::VelocityProfile> cartesianTrapVelocityProfile(double max_velocity_scaling_factor,
140 double max_acceleration_scaling_factor,
141 const std::unique_ptr<KDL::Path>& path) const;
142
143private:
144 virtual void cmdSpecificRequestValidation(const planning_interface::MotionPlanRequest& req) const;
145
155 virtual void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene,
156 const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const = 0;
157
158 virtual void plan(const planning_scene::PlanningSceneConstPtr& scene,
159 const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
160 double sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory) = 0;
161
162private:
204 void validateRequest(const planning_interface::MotionPlanRequest& req, const moveit::core::RobotState& rstate) const;
205
209 void setSuccessResponse(const moveit::core::RobotState& start_rs, const std::string& group_name,
210 const trajectory_msgs::msg::JointTrajectory& joint_trajectory,
211 const rclcpp::Time& planning_start, planning_interface::MotionPlanResponse& res) const;
212
213 void setFailureResponse(const rclcpp::Time& planning_start, planning_interface::MotionPlanResponse& res) const;
214
215 void checkForValidGroupName(const std::string& group_name) const;
216
228 void checkStartState(const moveit_msgs::msg::RobotState& start_state, const std::string& group) const;
229
230 void checkGoalConstraints(const moveit_msgs::msg::MotionPlanRequest::_goal_constraints_type& goal_constraints,
231 const std::string& group_name, const moveit::core::RobotState& rstate) const;
232
233 void checkJointGoalConstraint(const moveit_msgs::msg::Constraints& constraint, const std::string& group_name) const;
234
235 void checkCartesianGoalConstraint(const moveit_msgs::msg::Constraints& constraint,
236 const moveit::core::RobotState& robot_state,
237 const moveit::core::JointModelGroup* const jmg) const;
238
239private:
243 sensor_msgs::msg::JointState filterGroupValues(const sensor_msgs::msg::JointState& robot_state,
244 const std::string& group) const;
245
249 static bool isScalingFactorValid(double scaling_factor);
250 static void checkVelocityScaling(double scaling_factor);
251 static void checkAccelerationScaling(double scaling_factor);
252
257 static bool isCartesianGoalGiven(const moveit_msgs::msg::Constraints& constraint);
258
262 static bool isJointGoalGiven(const moveit_msgs::msg::Constraints& constraint);
263
268 static bool isOnlyOneGoalTypeGiven(const moveit_msgs::msg::Constraints& constraint);
269
270protected:
271 const moveit::core::RobotModelConstPtr robot_model_;
273 static constexpr double MIN_SCALING_FACTOR{ 0.0001 };
274 static constexpr double MAX_SCALING_FACTOR{ 1. };
275 static constexpr double VELOCITY_TOLERANCE{ 1e-8 };
276 const std::unique_ptr<rclcpp::Clock> clock_;
277};
278
279inline bool TrajectoryGenerator::isScalingFactorValid(double scaling_factor)
280{
281 return (scaling_factor > MIN_SCALING_FACTOR && scaling_factor <= MAX_SCALING_FACTOR);
282}
283
284inline bool TrajectoryGenerator::isCartesianGoalGiven(const moveit_msgs::msg::Constraints& constraint)
285{
286 return constraint.position_constraints.size() == 1 && constraint.orientation_constraints.size() == 1;
287}
288
289inline bool TrajectoryGenerator::isJointGoalGiven(const moveit_msgs::msg::Constraints& constraint)
290{
291 return !constraint.joint_constraints.empty();
292}
293
294inline bool TrajectoryGenerator::isOnlyOneGoalTypeGiven(const moveit_msgs::msg::Constraints& constraint)
295{
296 return (isJointGoalGiven(constraint) && !isCartesianGoalGiven(constraint)) ||
297 (!isJointGoalGiven(constraint) && isCartesianGoalGiven(constraint));
298}
299
300} // namespace pilz_industrial_motion_planner
Representation of a robot's state. This includes position, velocity, acceleration and effort.
This class combines CartesianLimit and JointLimits into on single class.
This class is used to extract needed information from motion plan request.
const moveit::core::RobotModelConstPtr robot_model_
TrajectoryGenerator(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
void 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(double max_velocity_scaling_factor, double max_acceleration_scaling_factor, const std::unique_ptr< KDL::Path > &path) const
build cartesian velocity profile for the path
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
#define CREATE_MOVEIT_ERROR_CODE_EXCEPTION(EXCEPTION_CLASS_NAME, ERROR_CODE)