moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_generator.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 
37 #include <cassert>
38 
39 #include <tf2_eigen/tf2_eigen.hpp>
40 #include <tf2_kdl/tf2_kdl.hpp>
41 #include <boost/range/combine.hpp>
42 
43 #include <kdl/velocityprofile_trap.hpp>
45 #include <moveit/utils/logger.hpp>
46 
48 
50 {
51 namespace
52 {
53 rclcpp::Logger getLogger()
54 {
55  return moveit::getLogger("pilz_trajectory_generator");
56 }
57 } // namespace
58 
59 sensor_msgs::msg::JointState TrajectoryGenerator::filterGroupValues(const sensor_msgs::msg::JointState& robot_state,
60  const std::string& group) const
61 {
62  const std::vector<std::string>& group_joints{ robot_model_->getJointModelGroup(group)->getActiveJointModelNames() };
63  sensor_msgs::msg::JointState group_state;
64  group_state.name.reserve(group_joints.size());
65  group_state.position.reserve(group_joints.size());
66  group_state.velocity.reserve(group_joints.size());
67 
68  for (size_t i = 0; i < robot_state.name.size(); ++i)
69  {
70  if (std::find(group_joints.begin(), group_joints.end(), robot_state.name.at(i)) != group_joints.end())
71  {
72  group_state.name.push_back(robot_state.name.at(i));
73  group_state.position.push_back(robot_state.position.at(i));
74  if (i < robot_state.velocity.size())
75  {
76  group_state.velocity.push_back(robot_state.velocity.at(i));
77  }
78  }
79  }
80  return group_state;
81 }
82 
83 void TrajectoryGenerator::cmdSpecificRequestValidation(const planning_interface::MotionPlanRequest& /*req*/) const
84 {
85  // Empty implementation, in case the derived class does not want
86  // to provide a command specific request validation.
87 }
88 
89 void TrajectoryGenerator::checkVelocityScaling(double scaling_factor)
90 {
91  if (!isScalingFactorValid(scaling_factor))
92  {
93  std::ostringstream os;
94  os << "Velocity scaling not in range [" << MIN_SCALING_FACTOR << ", " << MAX_SCALING_FACTOR << "], "
95  << "actual value is: " << scaling_factor;
96  throw VelocityScalingIncorrect(os.str());
97  }
98 }
99 
100 void TrajectoryGenerator::checkAccelerationScaling(double scaling_factor)
101 {
102  if (!isScalingFactorValid(scaling_factor))
103  {
104  std::ostringstream os;
105  os << "Acceleration scaling not in range [" << MIN_SCALING_FACTOR << ", " << MAX_SCALING_FACTOR << "], "
106  << "actual value is: " << scaling_factor;
107  throw AccelerationScalingIncorrect(os.str());
108  }
109 }
110 
111 void TrajectoryGenerator::checkForValidGroupName(const std::string& group_name) const
112 {
113  if (!robot_model_->hasJointModelGroup(group_name))
114  {
115  std::ostringstream os;
116  os << "Unknown planning group: " << group_name;
117  throw UnknownPlanningGroup(os.str());
118  }
119 }
120 
121 void TrajectoryGenerator::checkStartState(const moveit_msgs::msg::RobotState& start_state,
122  const std::string& group) const
123 {
124  if (start_state.joint_state.name.empty())
125  {
126  throw NoJointNamesInStartState("No joint names for state state given");
127  }
128 
129  if (start_state.joint_state.name.size() != start_state.joint_state.position.size())
130  {
131  throw SizeMismatchInStartState("Joint state name and position do not match in start state");
132  }
133 
134  sensor_msgs::msg::JointState group_start_state{ filterGroupValues(start_state.joint_state, group) };
135 
136  // verify joint position limits
137  const JointLimitsContainer& limits{ planner_limits_.getJointLimitContainer() };
138  std::string error_msg;
139  for (auto joint : boost::combine(group_start_state.name, group_start_state.position))
140  {
141  if (!limits.verifyPositionLimit(joint.get<0>(), joint.get<1>()))
142  {
143  error_msg.append(error_msg.empty() ? "start state joints outside their position limits: " : ", ");
144  error_msg.append(joint.get<0>());
145  }
146  }
147  if (!error_msg.empty())
148  {
149  throw JointsOfStartStateOutOfRange(error_msg);
150  }
151 
152  // does not allow start velocity
153  if (!std::all_of(group_start_state.velocity.begin(), group_start_state.velocity.end(),
154  [](double v) { return std::fabs(v) < VELOCITY_TOLERANCE; }))
155  {
156  throw NonZeroVelocityInStartState("Trajectory Generator does not allow non-zero start velocity");
157  }
158 }
159 
160 void TrajectoryGenerator::checkJointGoalConstraint(const moveit_msgs::msg::Constraints& constraint,
161  const std::vector<std::string>& expected_joint_names,
162  const std::string& group_name) const
163 {
164  for (const auto& joint_constraint : constraint.joint_constraints)
165  {
166  const std::string& curr_joint_name{ joint_constraint.joint_name };
167  if (std::find(expected_joint_names.cbegin(), expected_joint_names.cend(), curr_joint_name) ==
168  expected_joint_names.cend())
169  {
170  std::ostringstream os;
171  os << "Cannot find joint \"" << curr_joint_name << "\" from start state in goal constraint";
172  throw StartStateGoalStateMismatch(os.str());
173  }
174 
175  if (!robot_model_->getJointModelGroup(group_name)->hasJointModel(curr_joint_name))
176  {
177  std::ostringstream os;
178  os << "Joint \"" << curr_joint_name << "\" does not belong to group \"" << group_name << '\"';
179  throw JointConstraintDoesNotBelongToGroup(os.str());
180  }
181 
182  if (!planner_limits_.getJointLimitContainer().verifyPositionLimit(curr_joint_name, joint_constraint.position))
183  {
184  std::ostringstream os;
185  os << "Joint \"" << curr_joint_name << "\" violates joint limits in goal constraints";
186  throw JointsOfGoalOutOfRange(os.str());
187  }
188  }
189 }
190 
191 void TrajectoryGenerator::checkCartesianGoalConstraint(const moveit_msgs::msg::Constraints& constraint,
192  const std::string& group_name) const
193 {
194  assert(constraint.position_constraints.size() == 1);
195  assert(constraint.orientation_constraints.size() == 1);
196  const moveit_msgs::msg::PositionConstraint& pos_constraint{ constraint.position_constraints.front() };
197  const moveit_msgs::msg::OrientationConstraint& ori_constraint{ constraint.orientation_constraints.front() };
198 
199  if (pos_constraint.link_name.empty())
200  {
201  throw PositionConstraintNameMissing("Link name of position constraint missing");
202  }
203 
204  if (ori_constraint.link_name.empty())
205  {
206  throw OrientationConstraintNameMissing("Link name of orientation constraint missing");
207  }
208 
209  if (pos_constraint.link_name != ori_constraint.link_name)
210  {
211  std::ostringstream os;
212  os << "Position and orientation constraint name do not match"
213  << "(Position constraint name: \"" << pos_constraint.link_name << "\" | Orientation constraint name: \""
214  << ori_constraint.link_name << "\")";
215  throw PositionOrientationConstraintNameMismatch(os.str());
216  }
217 
218  if (!robot_model_->getJointModelGroup(group_name)->canSetStateFromIK(pos_constraint.link_name))
219  {
220  std::ostringstream os;
221  os << "No IK solver available for link: \"" << pos_constraint.link_name << '\"';
222  throw NoIKSolverAvailable(os.str());
223  }
224 
225  if (pos_constraint.constraint_region.primitive_poses.empty())
226  {
227  throw NoPrimitivePoseGiven("Primitive pose in position constraints of goal missing");
228  }
229 }
230 
231 void TrajectoryGenerator::checkGoalConstraints(
232  const moveit_msgs::msg::MotionPlanRequest::_goal_constraints_type& goal_constraints,
233  const std::vector<std::string>& expected_joint_names, const std::string& group_name) const
234 {
235  if (goal_constraints.size() != 1)
236  {
237  std::ostringstream os;
238  os << "Exactly one goal constraint required, but " << goal_constraints.size() << " goal constraints given";
239  throw NotExactlyOneGoalConstraintGiven(os.str());
240  }
241 
242  const moveit_msgs::msg::Constraints& goal_con{ goal_constraints.front() };
243  if (!isOnlyOneGoalTypeGiven(goal_con))
244  {
245  throw OnlyOneGoalTypeAllowed("Only cartesian XOR joint goal allowed");
246  }
247 
248  if (isJointGoalGiven(goal_con))
249  {
250  checkJointGoalConstraint(goal_con, expected_joint_names, group_name);
251  }
252  else
253  {
254  checkCartesianGoalConstraint(goal_con, group_name);
255  }
256 }
257 
258 void TrajectoryGenerator::validateRequest(const planning_interface::MotionPlanRequest& req) const
259 {
260  checkVelocityScaling(req.max_velocity_scaling_factor);
261  checkAccelerationScaling(req.max_acceleration_scaling_factor);
262  checkForValidGroupName(req.group_name);
263  checkStartState(req.start_state, req.group_name);
264  checkGoalConstraints(req.goal_constraints, req.start_state.joint_state.name, req.group_name);
265 }
266 
267 void TrajectoryGenerator::setSuccessResponse(const moveit::core::RobotState& start_state, const std::string& group_name,
268  const trajectory_msgs::msg::JointTrajectory& joint_trajectory,
269  const rclcpp::Time& planning_start,
271 {
272  auto rt = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, group_name);
273  rt->setRobotTrajectoryMsg(start_state, joint_trajectory);
274 
275  res.trajectory = rt;
276  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
277  res.planning_time = (clock_->now() - planning_start).seconds();
278 }
279 
280 void TrajectoryGenerator::setFailureResponse(const rclcpp::Time& planning_start,
282 {
283  if (res.trajectory)
284  {
285  res.trajectory->clear();
286  }
287  res.planning_time = (clock_->now() - planning_start).seconds();
288 }
289 
290 std::unique_ptr<KDL::VelocityProfile>
291 TrajectoryGenerator::cartesianTrapVelocityProfile(double max_velocity_scaling_factor,
292  double max_acceleration_scaling_factor,
293  const std::unique_ptr<KDL::Path>& path) const
294 {
295  std::unique_ptr<KDL::VelocityProfile> vp_trans = std::make_unique<KDL::VelocityProfile_Trap>(
296  max_velocity_scaling_factor * planner_limits_.getCartesianLimits().max_trans_vel,
297  max_acceleration_scaling_factor * planner_limits_.getCartesianLimits().max_trans_acc);
298 
299  if (path->PathLength() > std::numeric_limits<double>::epsilon()) // avoid division by zero
300  {
301  vp_trans->SetProfile(0, path->PathLength());
302  }
303  else
304  {
305  vp_trans->SetProfile(0, std::numeric_limits<double>::epsilon());
306  }
307  return vp_trans;
308 }
309 
310 void TrajectoryGenerator::generate(const planning_scene::PlanningSceneConstPtr& scene,
312  planning_interface::MotionPlanResponse& res, double sampling_time)
313 {
314  RCLCPP_INFO_STREAM(getLogger(), "Generating " << req.planner_id << " trajectory...");
315  rclcpp::Time planning_begin = clock_->now();
316 
317  res.planner_id = req.planner_id;
318  try
319  {
320  validateRequest(req);
321  }
322  catch (const MoveItErrorCodeException& ex)
323  {
324  RCLCPP_ERROR_STREAM(getLogger(), ex.what());
325  res.error_code.val = ex.getErrorCode();
326  setFailureResponse(planning_begin, res);
327  return;
328  }
329 
330  try
331  {
332  cmdSpecificRequestValidation(req);
333  }
334  catch (const MoveItErrorCodeException& ex)
335  {
336  RCLCPP_ERROR_STREAM(getLogger(), ex.what());
337  res.error_code.val = ex.getErrorCode();
338  setFailureResponse(planning_begin, res);
339  return;
340  }
341 
342  MotionPlanInfo plan_info;
343  try
344  {
345  extractMotionPlanInfo(scene, req, plan_info);
346  }
347  catch (const MoveItErrorCodeException& ex)
348  {
349  RCLCPP_ERROR_STREAM(getLogger(), ex.what());
350  res.error_code.val = ex.getErrorCode();
351  setFailureResponse(planning_begin, res);
352  return;
353  }
354 
355  trajectory_msgs::msg::JointTrajectory joint_trajectory;
356  try
357  {
358  plan(scene, req, plan_info, sampling_time, joint_trajectory);
359  }
360  catch (const MoveItErrorCodeException& ex)
361  {
362  RCLCPP_ERROR_STREAM(getLogger(), ex.what());
363  res.error_code.val = ex.getErrorCode();
364  setFailureResponse(planning_begin, res);
365  return;
366  }
367 
368  moveit::core::RobotState start_state(scene->getCurrentState());
369  moveit::core::robotStateMsgToRobotState(req.start_state, start_state, true);
370  setSuccessResponse(start_state, req.group_name, joint_trajectory, planning_begin, res);
371 }
372 
373 } // namespace pilz_industrial_motion_planner
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
bool verifyPositionLimit(const std::string &joint_name, double joint_position) const
verify position limit of single joint
const cartesian_limits::Params & getCartesianLimits() const
Return the cartesian limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
Exception storing an moveit_msgs::msg::MoveItErrorCodes value.
virtual const moveit_msgs::msg::MoveItErrorCodes::_val_type & getErrorCode() const =0
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_
const std::unique_ptr< rclcpp::Clock > clock_
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
bool robotStateMsgToRobotState(const Transforms &tf, const moveit_msgs::msg::RobotState &robot_state, RobotState &state, bool copy_attached_bodies=true)
Convert a robot state msg (with accompanying extra transforms) to a MoveIt robot state.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
Response to a planning query.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory