moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_generator_circ.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 <eigen3/Eigen/Eigen>
38 #include <kdl/path.hpp>
39 #include <kdl/velocityprofile.hpp>
41 
43 
45 {
46 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(CircleNoPlane, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
47 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(CircleToSmall, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
48 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(CenterPointDifferentRadius, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
49 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(CircTrajectoryConversionFailure,
50  moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
51 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(UnknownPathConstraintName, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
52 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoPositionConstraints, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
53 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NoPrimitivePose, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
54 
55 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(UnknownLinkNameOfAuxiliaryPoint,
56  moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
57 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NumberOfConstraintsMismatch,
58  moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
59 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(CircJointMissingInStartState,
60  moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
61 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(CircInverseForGoalIncalculable, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
62 
73 {
74 public:
83  TrajectoryGeneratorCIRC(const moveit::core::RobotModelConstPtr& robot_model,
85  const std::string& group_name);
86 
87 private:
88  void cmdSpecificRequestValidation(const planning_interface::MotionPlanRequest& req) const override;
89 
90  void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene,
91  const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const final;
92 
93  void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
94  const MotionPlanInfo& plan_info, double sampling_time,
95  trajectory_msgs::msg::JointTrajectory& joint_trajectory) override;
96 
110  std::unique_ptr<KDL::Path> setPathCIRC(const MotionPlanInfo& info) const;
111 };
112 
113 } // namespace pilz_industrial_motion_planner
This class combines CartesianLimit and JointLimits into on single class.
This class implements a trajectory generator of arcs in Cartesian space. The arc is specified by a st...
TrajectoryGeneratorCIRC(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of CIRC Trajectory Generator.
This class is used to extract needed information from motion plan request.
CREATE_MOVEIT_ERROR_CODE_EXCEPTION(NegativeBlendRadiusException, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest