moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
trajectory_generator_circ.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
37
38#include <cassert>
39#include <sstream>
40
41#include <kdl/rotational_interpolation_sa.hpp>
42#include <kdl/trajectory_segment.hpp>
43#include <kdl/utilities/error.h>
44#include <kdl/utilities/utility.h>
46#include <rclcpp/logger.hpp>
47#include <rclcpp/logging.hpp>
48#include <tf2_eigen/tf2_eigen.hpp>
49#include <tf2_eigen_kdl/tf2_eigen_kdl.hpp>
50#include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
52
54{
55namespace
56{
57rclcpp::Logger getLogger()
58{
59 return moveit::getLogger("moveit.planners.pilz.trajectory_generator.circ");
60}
61} // namespace
62TrajectoryGeneratorCIRC::TrajectoryGeneratorCIRC(const moveit::core::RobotModelConstPtr& robot_model,
63 const LimitsContainer& planner_limits,
64 const std::string& /*group_name*/)
65 : TrajectoryGenerator::TrajectoryGenerator(robot_model, planner_limits)
66{
68}
69
70void TrajectoryGeneratorCIRC::cmdSpecificRequestValidation(const planning_interface::MotionPlanRequest& req) const
71{
72 if (!(req.path_constraints.name == "interim" || req.path_constraints.name == "center"))
73 {
74 std::ostringstream os;
75 os << "No path constraint named \"interim\" or \"center\" found (found "
76 "unknown constraint: "
77 << "\"req.path_constraints.name\""
78 << " instead)";
79 throw UnknownPathConstraintName(os.str());
80 }
81
82 if (req.path_constraints.position_constraints.size() != 1)
83 {
84 throw NoPositionConstraints("CIRC trajectory generator needs valid a position constraint");
85 }
86
87 if (req.path_constraints.position_constraints.front().constraint_region.primitive_poses.size() != 1)
88 {
89 throw NoPrimitivePose("CIRC trajectory generator needs valid a primitive pose");
90 }
91}
92
93void TrajectoryGeneratorCIRC::extractMotionPlanInfo(const planning_scene::PlanningSceneConstPtr& scene,
95 TrajectoryGenerator::MotionPlanInfo& info) const
96{
97 RCLCPP_DEBUG(getLogger(), "Extract necessary information from motion plan request.");
98
99 info.group_name = req.group_name;
100 moveit::core::RobotState robot_state = scene->getCurrentState();
101
102 // goal given in joint space
103 if (!req.goal_constraints.front().joint_constraints.empty())
104 {
105 // TODO: link name from goal constraint and path constraint
106 info.link_name = req.path_constraints.position_constraints.front().link_name;
107 if (!robot_model_->hasLinkModel(info.link_name))
108 {
109 throw UnknownLinkNameOfAuxiliaryPoint("Unknown link name of CIRC auxiliary point");
110 }
111
112 if (req.goal_constraints.front().joint_constraints.size() !=
113 robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size())
114 {
115 std::ostringstream os;
116 os << "Number of joint constraint = " << req.goal_constraints.front().joint_constraints.size()
117 << " not equal to active joints of group = "
118 << robot_model_->getJointModelGroup(req.group_name)->getActiveJointModelNames().size();
119 throw NumberOfConstraintsMismatch(os.str());
120 }
121
122 for (const auto& joint_item : req.goal_constraints.front().joint_constraints)
123 {
124 info.goal_joint_position[joint_item.joint_name] = joint_item.position;
125 }
126
127 computeLinkFK(robot_state, info.link_name, info.goal_joint_position, info.goal_pose);
128 }
129 // goal given in Cartesian space
130 else
131 {
132 std::string frame_id;
133 info.link_name = req.goal_constraints.front().position_constraints.front().link_name;
134 if (req.goal_constraints.front().position_constraints.front().header.frame_id.empty() ||
135 req.goal_constraints.front().orientation_constraints.front().header.frame_id.empty())
136 {
137 RCLCPP_WARN(getLogger(), "Frame id is not set in position/orientation constraints of "
138 "goal. Use model frame as default");
139 frame_id = robot_model_->getModelFrame();
140 }
141 else
142 {
143 frame_id = req.goal_constraints.front().position_constraints.front().header.frame_id;
144 }
145
146 // goal pose with optional offset wrt. the planning frame
147 info.goal_pose = scene->getFrameTransform(frame_id) * getConstraintPose(req.goal_constraints.front());
148 frame_id = robot_model_->getModelFrame();
149
150 // check goal pose ik before Cartesian motion plan starts
151 std::map<std::string, double> ik_solution;
152 if (!computePoseIK(scene, info.group_name, info.link_name, info.goal_pose, frame_id, info.start_joint_position,
153 ik_solution))
154 {
155 // LCOV_EXCL_START
156 std::ostringstream os;
157 os << "Failed to compute inverse kinematics for link: " << info.link_name << " of goal pose";
158 throw CircInverseForGoalIncalculable(os.str());
159 // LCOV_EXCL_STOP // not able to trigger here since lots of checks before
160 // are in place
161 }
162 }
163
164 computeLinkFK(robot_state, info.link_name, info.start_joint_position, info.start_pose);
165
166 // center point with wrt. the planning frame
167 std::string center_point_frame_id;
168
169 info.circ_path_point.first = req.path_constraints.name;
170 if (req.path_constraints.position_constraints.front().header.frame_id.empty())
171 {
172 RCLCPP_WARN(getLogger(), "Frame id is not set in position constraints of "
173 "path. Use model frame as default");
174 center_point_frame_id = robot_model_->getModelFrame();
175 }
176 else
177 {
178 center_point_frame_id = req.path_constraints.position_constraints.front().header.frame_id;
179 }
180
181 Eigen::Isometry3d center_point_pose;
182 tf2::fromMsg(req.path_constraints.position_constraints.front().constraint_region.primitive_poses.front(),
183 center_point_pose);
184
185 center_point_pose = scene->getFrameTransform(center_point_frame_id) * center_point_pose;
186
187 if (!req.goal_constraints.front().position_constraints.empty())
188 {
189 const moveit_msgs::msg::Constraints& goal = req.goal_constraints.front();
190 geometry_msgs::msg::Point center_point = tf2::toMsg(Eigen::Vector3d(center_point_pose.translation()));
191 info.circ_path_point.second = getConstraintPose(center_point, goal.orientation_constraints.front().orientation,
192 goal.position_constraints.front().target_point_offset)
193 .translation();
194 }
195 else
196 {
197 info.circ_path_point.second = center_point_pose.translation();
198 }
199}
200
201void TrajectoryGeneratorCIRC::plan(const planning_scene::PlanningSceneConstPtr& scene,
202 const planning_interface::MotionPlanRequest& req, const MotionPlanInfo& plan_info,
203 double sampling_time, trajectory_msgs::msg::JointTrajectory& joint_trajectory)
204{
205 std::unique_ptr<KDL::Path> cart_path(setPathCIRC(plan_info));
206 std::unique_ptr<KDL::VelocityProfile> vel_profile(
207 cartesianTrapVelocityProfile(req.max_velocity_scaling_factor, req.max_acceleration_scaling_factor, cart_path));
208
209 // combine path and velocity profile into Cartesian trajectory
210 // with the third parameter set to false, KDL::Trajectory_Segment does not
211 // take
212 // the ownship of Path and Velocity Profile
213 KDL::Trajectory_Segment cart_trajectory(cart_path.get(), vel_profile.get(), false);
214
215 moveit_msgs::msg::MoveItErrorCodes error_code;
216 // sample the Cartesian trajectory and compute joint trajectory using inverse
217 // kinematics
218 if (!generateJointTrajectory(scene, planner_limits_.getJointLimitContainer(), cart_trajectory, plan_info.group_name,
219 plan_info.link_name, plan_info.start_joint_position, sampling_time, joint_trajectory,
220 error_code))
221 {
222 throw CircTrajectoryConversionFailure("Failed to generate valid joint trajectory from the Cartesian path",
223 error_code.val);
224 }
225}
226
227std::unique_ptr<KDL::Path> TrajectoryGeneratorCIRC::setPathCIRC(const MotionPlanInfo& info) const
228{
229 RCLCPP_DEBUG(getLogger(), "Set Cartesian path for CIRC command.");
230
231 KDL::Frame start_pose, goal_pose;
232 tf2::transformEigenToKDL(info.start_pose, start_pose);
233 tf2::transformEigenToKDL(info.goal_pose, goal_pose);
234
235 const auto& eigen_path_point = info.circ_path_point.second;
236 const KDL::Vector path_point{ eigen_path_point.x(), eigen_path_point.y(), eigen_path_point.z() };
237
238 // pass the ratio of translational by rotational velocity as equivalent radius
239 // to get a trajectory with rotational speed, if no (or very little)
240 // translational distance
241 // The KDL::Path implementation chooses the motion with the longer duration
242 // (translation vs. rotation)
243 // and uses eqradius as scaling factor between the distances.
244 double eqradius =
246
247 try
248 {
249 if (info.circ_path_point.first == "center")
250 {
251 return PathCircleGenerator::circleFromCenter(start_pose, goal_pose, path_point, eqradius);
252 }
253 else // if (info.circ_path_point.first == "interim")
254 {
255 return PathCircleGenerator::circleFromInterim(start_pose, goal_pose, path_point, eqradius);
256 }
257 }
258 catch (KDL::Error_MotionPlanning_Circle_No_Plane& e)
259 {
260 std::ostringstream os;
261 os << "Failed to create path object for circle." << e.Description();
262 throw CircleNoPlane(os.str());
263 }
264 catch (KDL::Error_MotionPlanning_Circle_ToSmall& e)
265 {
266 std::ostringstream os;
267 os << "Failed to create path object for circle." << e.Description();
268 throw CircleToSmall(os.str());
269 }
271 {
272 std::ostringstream os;
273 os << "Failed to create path object for circle." << e.Description();
274 throw CenterPointDifferentRadius(os.str());
275 }
276
277 return nullptr;
278}
279
280} // 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.
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.
static std::unique_ptr< KDL::Path > circleFromCenter(const KDL::Frame &start_pose, const KDL::Frame &goal_pose, const KDL::Vector &center_point, double eqradius)
set the path circle from start, goal and center point
static std::unique_ptr< KDL::Path > circleFromInterim(const KDL::Frame &start_pose, const KDL::Frame &goal_pose, const KDL::Vector &interim_point, double eqradius)
set circle from start, goal and interim point
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.
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.