moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_generator_lin.cpp
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 
36 
38 
39 #include <cassert>
40 #include <sstream>
41 #include <time.h>
43 #include <kdl/path_line.hpp>
44 #include <kdl/trajectory_segment.hpp>
45 #include <kdl/utilities/error.h>
46 #include <tf2/convert.h>
47 #include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
48 #include <rclcpp/logger.hpp>
49 #include <rclcpp/logging.hpp>
50 #include <tf2_eigen/tf2_eigen.hpp>
51 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
52 #include <moveit/utils/logger.hpp>
53 
55 {
56 namespace
57 {
58 rclcpp::Logger getLogger()
59 {
60  return moveit::getLogger("moveit.planners.pilz.trajectory_generator.lin");
61 }
62 } // namespace
63 TrajectoryGeneratorLIN::TrajectoryGeneratorLIN(const moveit::core::RobotModelConstPtr& robot_model,
64  const LimitsContainer& planner_limits, const std::string& /*group_name*/)
65  : TrajectoryGenerator::TrajectoryGenerator(robot_model, planner_limits)
66 {
68 }
69 
70 void TrajectoryGeneratorLIN::extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene,
73 {
74  RCLCPP_DEBUG(getLogger(), "Extract necessary information from motion plan request.");
75 
76  info.group_name = req.group_name;
77  moveit::core::RobotState robot_state = scene->getCurrentState();
78 
79  // goal given in joint space
80  if (!req.goal_constraints.front().joint_constraints.empty())
81  {
82  info.link_name = getSolverTipFrame(robot_model_->getJointModelGroup(req.group_name));
83 
84  if (req.goal_constraints.front().joint_constraints.size() !=
85  robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size())
86  {
87  std::ostringstream os;
88  os << "Number of joints in goal does not match number of joints of group "
89  "(Number joints goal: "
90  << req.goal_constraints.front().joint_constraints.size() << " | Number of joints of group: "
91  << robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size() << ')';
92  throw JointNumberMismatch(os.str());
93  }
94 
95  for (const auto& joint_item : req.goal_constraints.front().joint_constraints)
96  {
97  info.goal_joint_position[joint_item.joint_name] = joint_item.position;
98  }
99 
100  computeLinkFK(robot_state, info.link_name, info.goal_joint_position, info.goal_pose);
101  }
102  // goal given in Cartesian space
103  else
104  {
105  std::string frame_id;
106 
107  info.link_name = req.goal_constraints.front().position_constraints.front().link_name;
108  if (req.goal_constraints.front().position_constraints.front().header.frame_id.empty() ||
109  req.goal_constraints.front().orientation_constraints.front().header.frame_id.empty())
110  {
111  RCLCPP_WARN(getLogger(), "Frame id is not set in position/orientation constraints of "
112  "goal. Use model frame as default");
113  frame_id = robot_model_->getModelFrame();
114  }
115  else
116  {
117  frame_id = req.goal_constraints.front().position_constraints.front().header.frame_id;
118  }
119 
120  // goal pose with optional offset wrt. the planning frame
121  info.goal_pose = scene->getFrameTransform(frame_id) * getConstraintPose(req.goal_constraints.front());
122  frame_id = robot_model_->getModelFrame();
123 
124  // check goal pose ik before Cartesian motion plan starts
125  std::map<std::string, double> ik_solution;
126  if (!computePoseIK(scene, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position,
127  ik_solution))
128  {
129  std::ostringstream os;
130  os << "Failed to compute inverse kinematics for link: " << info.link_name << " of goal pose";
131  throw LinInverseForGoalIncalculable(os.str());
132  }
133  }
134 
135  // Ignored return value because at this point the function should always
136  // return 'true'.
137  computeLinkFK(robot_state, info.link_name, info.start_joint_position, info.start_pose);
138 }
139 
140 void TrajectoryGeneratorLIN::plan(const planning_scene::PlanningSceneConstPtr& scene,
141  const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
142  double sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory)
143 {
144  // create Cartesian path for lin
145  std::unique_ptr<KDL::Path> path(setPathLIN(plan_info.start_pose, plan_info.goal_pose));
146 
147  // create velocity profile
148  std::unique_ptr<KDL::VelocityProfile> vp(
149  cartesianTrapVelocityProfile(req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor, path));
150 
151  // combine path and velocity profile into Cartesian trajectory
152  // with the third parameter set to false, KDL::Trajectory_Segment does not
153  // take
154  // the ownship of Path and Velocity Profile
155  KDL::Trajectory_Segment cart_trajectory(path.get(), vp.get(), false);
156 
157  moveit_msgs::msg::MoveItErrorCodes error_code;
158  // sample the Cartesian trajectory and compute joint trajectory using inverse
159  // kinematics
160  if (!generateJointTrajectory(scene, planner_limits_.getJointLimitContainer(), cart_trajectory, plan_info.group_name,
161  plan_info.link_name, plan_info.start_joint_position, sampling_time, joint_trajectory,
162  error_code))
163  {
164  std::ostringstream os;
165  os << "Failed to generate valid joint trajectory from the Cartesian path";
166  throw LinTrajectoryConversionFailure(os.str(), error_code.val);
167  }
168 }
169 
170 std::unique_ptr<KDL::Path> TrajectoryGeneratorLIN::setPathLIN(const Eigen::Affine3d& start_pose,
171  const Eigen::Affine3d& goal_pose) const
172 {
173  RCLCPP_DEBUG(getLogger(), "Set Cartesian path for LIN command.");
174 
175  KDL::Frame kdl_start_pose, kdl_goal_pose;
176  tf2::transformEigenToKDL(start_pose, kdl_start_pose);
177  tf2::transformEigenToKDL(goal_pose, kdl_goal_pose);
178  double eqradius =
180  KDL::RotationalInterpolation* rot_interpo = new KDL::RotationalInterpolation_SingleAxis();
181 
182  return std::unique_ptr<KDL::Path>(
183  std::make_unique<KDL::Path_Line>(kdl_start_pose, kdl_goal_pose, rot_interpo, eqradius, true));
184 }
185 
186 } // 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.
void printCartesianLimits() const
Prints the cartesian limits set by user. Default values for limits are 0.0.
const cartesian_limits::Params & getCartesianLimits() const
Return the cartesian limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
TrajectoryGeneratorLIN(const moveit::core::RobotModelConstPtr &robot_model, const pilz_industrial_motion_planner::LimitsContainer &planner_limits, const std::string &group_name)
Constructor of LIN Trajectory Generator.
This class is used to extract needed information from motion plan request.
const moveit::core::RobotModelConstPtr robot_model_
const pilz_industrial_motion_planner::LimitsContainer planner_limits_
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
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
bool computeLinkFK(moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at a given robot state
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, double sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
bool computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
compute the inverse kinematics of a given pose, also check robot self collision
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Eigen::Isometry3d getConstraintPose(const geometry_msgs::msg::Point &position, const geometry_msgs::msg::Quaternion &orientation, const geometry_msgs::msg::Vector3 &offset)
Adapt goal pose, defined by position+orientation, to consider offset.