moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_generator_ptp.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 
38 
39 #include <eigen3/Eigen/Eigen>
43 
45 {
46 // TODO date type of units
47 
48 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PtpVelocityProfileSyncFailed, moveit_msgs::msg::MoveItErrorCodes::FAILURE);
49 CREATE_MOVEIT_ERROR_CODE_EXCEPTION(PtpNoIkSolutionForGoalPose, moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
50 
56 {
57 public:
63  TrajectoryGeneratorPTP(const moveit::core::RobotModelConstPtr& robot_model,
65  const std::string& group_name);
66 
67 private:
68  void extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene,
69  const planning_interface::MotionPlanRequest& req, MotionPlanInfo& info) const override;
70 
81  void planPTP(const std::map<std::string, double>& start_pos, const std::map<std::string, double>& goal_pos,
82  trajectory_msgs::msg::JointTrajectory& joint_trajectory, const double& velocity_scaling_factor,
83  const double& acceleration_scaling_factor, const double& sampling_time);
84 
85  void plan(const planning_scene::PlanningSceneConstPtr& scene, const planning_interface::MotionPlanRequest& req,
86  const MotionPlanInfo& plan_info, const double& sampling_time,
87  trajectory_msgs::msg::JointTrajectory& joint_trajectory) override;
88 
89 private:
90  const double MIN_MOVEMENT = 0.001;
92  // most strict joint limits
93  JointLimit most_strict_limit_;
94 };
95 
96 } // namespace pilz_industrial_motion_planner
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
This class implements a point-to-point trajectory generator based on VelocityProfileATrap.
TrajectoryGeneratorPTP(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of PTP Trajectory Generator.
This class is used to extract needed information from motion plan request.
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
Extends joint_limits_interface::JointLimits with a deceleration parameter.