moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_blender_transition_window.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 <algorithm>
38 #include <memory>
39 #include <math.h>
40 #include <tf2_eigen/tf2_eigen.hpp>
42 
43 namespace
44 {
45 static const rclcpp::Logger LOGGER =
46  rclcpp::get_logger("moveit.pilz_industrial_motion_planner.trajectory_blender_transition_window");
47 }
48 
50  const planning_scene::PlanningSceneConstPtr& planning_scene,
53 {
54  RCLCPP_INFO(LOGGER, "Start trajectory blending using transition window.");
55 
56  double sampling_time = 0.;
57  if (!validateRequest(req, sampling_time, res.error_code))
58  {
59  RCLCPP_ERROR(LOGGER, "Trajectory blend request is not valid.");
60  return false;
61  }
62 
63  // search for intersection points of the two trajectories with the blending
64  // sphere
65  // intersection points belongs to blend trajectory after blending
66  std::size_t first_intersection_index;
67  std::size_t second_intersection_index;
68  if (!searchIntersectionPoints(req, first_intersection_index, second_intersection_index))
69  {
70  RCLCPP_ERROR(LOGGER, "Blend radius too large.");
71  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
72  return false;
73  }
74 
75  // Select blending period and adjust the start and end point of the blend
76  // phase
77  std::size_t blend_align_index;
78  determineTrajectoryAlignment(req, first_intersection_index, second_intersection_index, blend_align_index);
79 
80  // blend the trajectories in Cartesian space
81  pilz_industrial_motion_planner::CartesianTrajectory blend_trajectory_cartesian;
82  blendTrajectoryCartesian(req, first_intersection_index, second_intersection_index, blend_align_index, sampling_time,
83  blend_trajectory_cartesian);
84 
85  // generate the blending trajectory in joint space
86  std::map<std::string, double> initial_joint_position, initial_joint_velocity;
87  for (const std::string& joint_name :
88  req.first_trajectory->getFirstWayPointPtr()->getJointModelGroup(req.group_name)->getActiveJointModelNames())
89  {
90  initial_joint_position[joint_name] =
91  req.first_trajectory->getWayPoint(first_intersection_index - 1).getVariablePosition(joint_name);
92  initial_joint_velocity[joint_name] =
93  req.first_trajectory->getWayPoint(first_intersection_index - 1).getVariableVelocity(joint_name);
94  }
95  trajectory_msgs::msg::JointTrajectory blend_joint_trajectory;
96  moveit_msgs::msg::MoveItErrorCodes error_code;
97 
98  if (!generateJointTrajectory(planning_scene, limits_.getJointLimitContainer(), blend_trajectory_cartesian,
99  req.group_name, req.link_name, initial_joint_position, initial_joint_velocity,
100  blend_joint_trajectory, error_code))
101  {
102  // LCOV_EXCL_START
103  RCLCPP_INFO(LOGGER, "Failed to generate joint trajectory for blending trajectory.");
104  res.error_code.val = error_code.val;
105  return false;
106  // LCOV_EXCL_STOP
107  }
108 
109  res.first_trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(req.first_trajectory->getRobotModel(),
110  req.first_trajectory->getGroup());
111  res.blend_trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(req.first_trajectory->getRobotModel(),
112  req.first_trajectory->getGroup());
113  res.second_trajectory = std::make_shared<robot_trajectory::RobotTrajectory>(req.first_trajectory->getRobotModel(),
114  req.first_trajectory->getGroup());
115 
116  // set the three trajectories after blending in response
117  // erase the points [first_intersection_index, back()] from the first
118  // trajectory
119  for (size_t i = 0; i < first_intersection_index; ++i)
120  {
121  res.first_trajectory->insertWayPoint(i, req.first_trajectory->getWayPoint(i),
122  req.first_trajectory->getWayPointDurationFromPrevious(i));
123  }
124 
125  // append the blend trajectory
126  res.blend_trajectory->setRobotTrajectoryMsg(req.first_trajectory->getFirstWayPoint(), blend_joint_trajectory);
127 
128  // copy the points [second_intersection_index, len] from the second trajectory
129  for (size_t i = second_intersection_index + 1; i < req.second_trajectory->getWayPointCount(); ++i)
130  {
131  res.second_trajectory->insertWayPoint(i - (second_intersection_index + 1), req.second_trajectory->getWayPoint(i),
132  req.second_trajectory->getWayPointDurationFromPrevious(i));
133  }
134 
135  // adjust the time from start
136  res.second_trajectory->setWayPointDurationFromPrevious(0, sampling_time);
137 
138  res.error_code.val = moveit_msgs::msg::MoveItErrorCodes::SUCCESS;
139  return true;
140 }
141 
142 bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::validateRequest(
143  const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, double& sampling_time,
144  moveit_msgs::msg::MoveItErrorCodes& error_code) const
145 {
146  RCLCPP_DEBUG(LOGGER, "Validate the trajectory blend request.");
147 
148  // check planning group
149  if (!req.first_trajectory->getRobotModel()->hasJointModelGroup(req.group_name))
150  {
151  RCLCPP_ERROR_STREAM(LOGGER, "Unknown planning group: " << req.group_name);
152  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_GROUP_NAME;
153  return false;
154  }
155 
156  // check link exists
157  if (!req.first_trajectory->getRobotModel()->hasLinkModel(req.link_name) &&
158  !req.first_trajectory->getLastWayPoint().hasAttachedBody(req.link_name))
159  {
160  RCLCPP_ERROR_STREAM(LOGGER, "Unknown link name: " << req.link_name);
161  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME;
162  return false;
163  }
164 
165  if (req.blend_radius <= 0)
166  {
167  RCLCPP_ERROR(LOGGER, "Blending radius must be positive");
168  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
169  return false;
170  }
171 
172  // end position of the first trajectory and start position of second
173  // trajectory must be the same
175  req.first_trajectory->getLastWayPoint(), req.second_trajectory->getFirstWayPoint(), req.group_name, EPSILON))
176  {
177  RCLCPP_ERROR_STREAM(
178  LOGGER, "During blending the last point of the preceding and the first point of the succeeding trajectory");
179  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
180  return false;
181  }
182 
183  // same uniform sampling time
185  EPSILON, sampling_time))
186  {
187  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
188  return false;
189  }
190 
191  // end position of the first trajectory and start position of second
192  // trajectory must have zero
193  // velocities/accelerations
195  EPSILON) ||
197  EPSILON))
198  {
199  RCLCPP_ERROR(LOGGER, "Intersection point of the blending trajectories has non-zero velocities/accelerations.");
200  error_code.val = moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN;
201  return false;
202  }
203 
204  return true;
205 }
206 
207 void pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::blendTrajectoryCartesian(
208  const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, const std::size_t first_interse_index,
209  const std::size_t second_interse_index, const std::size_t blend_align_index, double sampling_time,
211 {
212  // other fields of the trajectory
213  trajectory.group_name = req.group_name;
214  trajectory.link_name = req.link_name;
215 
216  // Pose on first trajectory
217  Eigen::Isometry3d blend_sample_pose1 =
218  req.first_trajectory->getWayPoint(first_interse_index).getFrameTransform(req.link_name);
219 
220  // Pose on second trajectory
221  Eigen::Isometry3d blend_sample_pose2 =
222  req.second_trajectory->getWayPoint(second_interse_index).getFrameTransform(req.link_name);
223 
224  // blend the trajectory
225  double blend_sample_num = second_interse_index + blend_align_index - first_interse_index + 1;
227  blend_sample_pose2 = req.second_trajectory->getFirstWayPoint().getFrameTransform(req.link_name);
228 
229  // Pose on blending trajectory
230  Eigen::Isometry3d blend_sample_pose;
231  for (std::size_t i = 0; i < blend_sample_num; ++i)
232  {
233  // if the first trajectory does not reach the last sample, update
234  if ((first_interse_index + i) < req.first_trajectory->getWayPointCount())
235  {
236  blend_sample_pose1 = req.first_trajectory->getWayPoint(first_interse_index + i).getFrameTransform(req.link_name);
237  }
238 
239  // if after the alignment, the second trajectory starts, update
240  if ((first_interse_index + i) > blend_align_index)
241  {
242  blend_sample_pose2 = req.second_trajectory->getWayPoint(first_interse_index + i - blend_align_index)
243  .getFrameTransform(req.link_name);
244  }
245 
246  double s = (i + 1) / blend_sample_num;
247  double alpha = 6 * std::pow(s, 5) - 15 * std::pow(s, 4) + 10 * std::pow(s, 3);
248 
249  // blend the translation
250  blend_sample_pose.translation() = blend_sample_pose1.translation() +
251  alpha * (blend_sample_pose2.translation() - blend_sample_pose1.translation());
252 
253  // blend the orientation
254  Eigen::Quaterniond start_quat(blend_sample_pose1.rotation());
255  Eigen::Quaterniond end_quat(blend_sample_pose2.rotation());
256  blend_sample_pose.linear() = start_quat.slerp(alpha, end_quat).toRotationMatrix();
257 
258  // push to the trajectory
259  waypoint.pose = tf2::toMsg(blend_sample_pose);
260  waypoint.time_from_start = rclcpp::Duration::from_seconds((i + 1.0) * sampling_time);
261  trajectory.points.push_back(waypoint);
262  }
263 }
264 
265 bool pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::searchIntersectionPoints(
266  const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, std::size_t& first_interse_index,
267  std::size_t& second_interse_index) const
268 {
269  RCLCPP_INFO(LOGGER, "Search for start and end point of blending trajectory.");
270 
271  // compute the position of the center of the blend sphere
272  // (last point of the first trajectory, first point of the second trajectory)
273  Eigen::Isometry3d circ_pose = req.first_trajectory->getLastWayPoint().getFrameTransform(req.link_name);
274 
275  // Searh for intersection points according to distance
276  if (!linearSearchIntersectionPoint(req.link_name, circ_pose.translation(), req.blend_radius, req.first_trajectory,
277  true, first_interse_index))
278  {
279  RCLCPP_ERROR_STREAM(LOGGER, "Intersection point of first trajectory not found.");
280  return false;
281  }
282  RCLCPP_INFO_STREAM(LOGGER, "Intersection point of first trajectory found, index: " << first_interse_index);
283 
284  if (!linearSearchIntersectionPoint(req.link_name, circ_pose.translation(), req.blend_radius, req.second_trajectory,
285  false, second_interse_index))
286  {
287  RCLCPP_ERROR_STREAM(LOGGER, "Intersection point of second trajectory not found.");
288  return false;
289  }
290 
291  RCLCPP_INFO_STREAM(LOGGER, "Intersection point of second trajectory found, index: " << second_interse_index);
292  return true;
293 }
294 
295 void pilz_industrial_motion_planner::TrajectoryBlenderTransitionWindow::determineTrajectoryAlignment(
296  const pilz_industrial_motion_planner::TrajectoryBlendRequest& req, std::size_t first_interse_index,
297  std::size_t second_interse_index, std::size_t& blend_align_index) const
298 {
299  size_t way_point_count_1 = req.first_trajectory->getWayPointCount() - first_interse_index;
300  size_t way_point_count_2 = second_interse_index + 1;
301 
302  if (way_point_count_1 > way_point_count_2)
303  {
304  blend_align_index = req.first_trajectory->getWayPointCount() - second_interse_index - 1;
305  }
306  else
307  {
308  blend_align_index = first_interse_index;
309  }
310 }
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
bool blend(const planning_scene::PlanningSceneConstPtr &planning_scene, const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, pilz_industrial_motion_planner::TrajectoryBlendResponse &res) override
Blend two trajectories using transition window. The trajectories have to be equally and uniformly dis...
const pilz_industrial_motion_planner::LimitsContainer limits_
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, const 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 linearSearchIntersectionPoint(const std::string &link_name, const Eigen::Vector3d &center_position, const double &r, const robot_trajectory::RobotTrajectoryPtr &traj, bool inverseOrder, std::size_t &index)
Performs a linear search for the intersection point of the trajectory with the blending radius.
bool isRobotStateStationary(const moveit::core::RobotState &state, const std::string &group, double EPSILON)
check if the robot state have zero velocity/acceleration
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
Determines the sampling time and checks that both trajectroies use the same sampling time.
bool isRobotStateEqual(const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const std::string &joint_group_name, double epsilon)
Check if the two robot states have the same joint position/velocity/acceleration.
This namespace includes the central class for representing planning contexts.
const rclcpp::Logger LOGGER
Definition: async_test.h:31
std::vector< CartesianTrajectoryPoint > points