moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_utils.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 
35 #include <gtest/gtest.h>
38 #include <tf2_eigen/tf2_eigen.hpp>
39 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
40 
41 #include <rclcpp/logger.hpp>
42 #include "test_utils.h"
43 
44 // Logger
45 static const rclcpp::Logger LOGGER = rclcpp::get_logger("pilz_industrial_motion_planner.test_utils");
46 
48 testutils::createFakeLimits(const std::vector<std::string>& joint_names)
49 {
51 
52  for (const std::string& name : joint_names)
53  {
55  limit.has_position_limits = true;
56  limit.max_position = 2.967;
57  limit.min_position = -2.967;
58  limit.has_velocity_limits = true;
59  limit.max_velocity = 1;
60  limit.has_acceleration_limits = true;
61  limit.max_acceleration = 0.5;
62  limit.has_deceleration_limits = true;
63  limit.max_deceleration = -1;
64 
65  container.addLimit(name, limit);
66  }
67 
68  return container;
69 }
70 
71 bool testutils::getExpectedGoalPose(const moveit::core::RobotModelConstPtr& robot_model,
72  const planning_interface::MotionPlanRequest& req, std::string& link_name,
73  Eigen::Isometry3d& goal_pose_expect)
74 {
75  // ++++++++++++++++++++++++++++++++++
76  // + Get goal from joint constraint +
77  // ++++++++++++++++++++++++++++++++++
78  if (!req.goal_constraints.front().joint_constraints.empty())
79  {
80  std::map<std::string, double> goal_joint_position;
81 
82  // initializing all joints of the model
83  for (const auto& joint_name : robot_model->getVariableNames())
84  {
85  goal_joint_position[joint_name] = 0;
86  }
87 
88  for (const auto& joint_item : req.goal_constraints.front().joint_constraints)
89  {
90  goal_joint_position[joint_item.joint_name] = joint_item.position;
91  }
92 
93  link_name = robot_model->getJointModelGroup(req.group_name)->getSolverInstance()->getTipFrame();
94 
95  if (!computeLinkFK(robot_model, link_name, goal_joint_position, goal_pose_expect))
96  {
97  std::cerr << "Failed to compute forward kinematics for link in goal "
98  "constraints \n";
99  return false;
100  }
101  return true;
102  }
103 
104  // ++++++++++++++++++++++++++++++++++++++
105  // + Get goal from cartesian constraint +
106  // ++++++++++++++++++++++++++++++++++++++
107  // TODO frame id
108  link_name = req.goal_constraints.front().position_constraints.front().link_name;
109  geometry_msgs::msg::Pose goal_pose_msg;
110  goal_pose_msg.position =
111  req.goal_constraints.front().position_constraints.front().constraint_region.primitive_poses.front().position;
112  goal_pose_msg.orientation = req.goal_constraints.front().orientation_constraints.front().orientation;
113  normalizeQuaternion(goal_pose_msg.orientation);
114  tf2::fromMsg(goal_pose_msg, goal_pose_expect);
115  return true;
116 }
117 
118 bool testutils::isGoalReached(const trajectory_msgs::msg::JointTrajectory& trajectory,
119  const std::vector<moveit_msgs::msg::JointConstraint>& goal,
120  const double joint_position_tolerance, const double joint_velocity_tolerance)
121 {
122  trajectory_msgs::msg::JointTrajectoryPoint last_point = trajectory.points.back();
123 
124  for (unsigned int i = 0; i < trajectory.joint_names.size(); ++i)
125  {
126  if (fabs(last_point.velocities.at(i)) > joint_velocity_tolerance)
127  {
128  std::cerr << "[ Fail ] goal has non zero velocity."
129  << " Joint Name: " << trajectory.joint_names.at(i) << "; Velocity: " << last_point.velocities.at(i)
130  << '\n';
131  return false;
132  }
133 
134  for (const auto& joint_goal : goal)
135  {
136  if (trajectory.joint_names.at(i) == joint_goal.joint_name)
137  {
138  if (fabs(last_point.positions.at(i) - joint_goal.position) > joint_position_tolerance)
139  {
140  std::cerr << "[ Fail ] goal position not reached."
141  << " Joint Name: " << trajectory.joint_names.at(i)
142  << "; Actual Position: " << last_point.positions.at(i)
143  << "; Expected Position: " << joint_goal.position << '\n';
144  return false;
145  }
146  }
147  }
148  }
149 
150  return true;
151 }
152 
153 bool testutils::isGoalReached(const moveit::core::RobotModelConstPtr& robot_model,
154  const trajectory_msgs::msg::JointTrajectory& trajectory,
155  const planning_interface::MotionPlanRequest& req, const double pos_tolerance,
156  const double orientation_tolerance)
157 {
158  std::string link_name;
159  Eigen::Isometry3d goal_pose_expect;
160  if (!testutils::getExpectedGoalPose(robot_model, req, link_name, goal_pose_expect))
161  {
162  return false;
163  }
164 
165  // compute the actual goal pose in model frame
166  trajectory_msgs::msg::JointTrajectoryPoint last_point = trajectory.points.back();
167  Eigen::Isometry3d goal_pose_actual;
168  std::map<std::string, double> joint_state;
169 
170  // initializing all joints of the model
171  for (const auto& joint_name : robot_model->getVariableNames())
172  {
173  joint_state[joint_name] = 0;
174  }
175 
176  for (std::size_t i = 0; i < trajectory.joint_names.size(); ++i)
177  {
178  joint_state[trajectory.joint_names.at(i)] = last_point.positions.at(i);
179  }
180 
181  if (!computeLinkFK(robot_model, link_name, joint_state, goal_pose_actual))
182  {
183  std::cerr << "[ Fail ] forward kinematics computation failed for link: " << link_name << '\n';
184  }
185 
186  auto actual_rotation{ goal_pose_actual.rotation() };
187  auto expected_rotation{ goal_pose_expect.rotation() };
188  auto rot_diff{ actual_rotation - expected_rotation };
189  if (rot_diff.norm() > orientation_tolerance)
190  {
191  std::cout << "\nOrientation difference = " << rot_diff.norm() << " (eps=" << orientation_tolerance << ')'
192  << "\n### Expected goal orientation: ### \n"
193  << expected_rotation << '\n'
194  << "### Actual goal orientation ### \n"
195  << actual_rotation << '\n';
196  return false;
197  }
198 
199  auto actual_position{ goal_pose_actual.translation() };
200  auto expected_position{ goal_pose_expect.translation() };
201  auto pos_diff{ actual_position - expected_position };
202  if (pos_diff.norm() > pos_tolerance)
203  {
204  std::cout << "\nPosition difference = " << pos_diff.norm() << " (eps=" << pos_tolerance << ')'
205  << "\n### Expected goal position: ### \n"
206  << expected_position << '\n'
207  << "### Actual goal position ### \n"
208  << actual_position << '\n';
209  return false;
210  }
211 
212  return true;
213 }
214 
215 bool testutils::isGoalReached(const moveit::core::RobotModelConstPtr& robot_model,
216  const trajectory_msgs::msg::JointTrajectory& trajectory,
217  const planning_interface::MotionPlanRequest& req, const double tolerance)
218 {
219  return isGoalReached(robot_model, trajectory, req, tolerance, tolerance);
220 }
221 
222 bool testutils::checkCartesianLinearity(const moveit::core::RobotModelConstPtr& robot_model,
223  const trajectory_msgs::msg::JointTrajectory& trajectory,
225  const double translation_norm_tolerance, const double rot_axis_norm_tolerance,
226  const double /*rot_angle_tolerance*/)
227 {
228  std::string link_name;
229  Eigen::Isometry3d goal_pose_expect;
230  if (!testutils::getExpectedGoalPose(robot_model, req, link_name, goal_pose_expect))
231  {
232  return false;
233  }
234 
235  // compute start pose
236  moveit::core::RobotState rstate(robot_model);
237  rstate.setToDefaultValues();
238  moveit::core::jointStateToRobotState(req.start_state.joint_state, rstate);
239  Eigen::Isometry3d start_pose = rstate.getFrameTransform(link_name);
240 
241  // start goal angle axis
242  Eigen::AngleAxisd start_goal_aa(start_pose.rotation().transpose() * goal_pose_expect.rotation());
243 
244  // check the linearity
245  for (trajectory_msgs::msg::JointTrajectoryPoint way_point : trajectory.points)
246  {
247  Eigen::Isometry3d way_point_pose;
248  std::map<std::string, double> way_point_joint_state;
249 
250  // initializing all joints of the model
251  for (const auto& joint_name : robot_model->getVariableNames())
252  {
253  way_point_joint_state[joint_name] = 0;
254  }
255 
256  for (std::size_t i = 0; i < trajectory.joint_names.size(); ++i)
257  {
258  way_point_joint_state[trajectory.joint_names.at(i)] = way_point.positions.at(i);
259  }
260 
261  if (!computeLinkFK(robot_model, link_name, way_point_joint_state, way_point_pose))
262  {
263  std::cerr << "Failed to compute forward kinematics for link in goal "
264  "constraints \n";
265  return false;
266  }
267 
268  // translational linearity
269  Eigen::Vector3d goal_start_translation = goal_pose_expect.translation() - start_pose.translation();
270  // https://de.wikipedia.org/wiki/Geradengleichung
271  // Determined form of a straight line in 3D space
272  if (fabs((goal_start_translation.cross(way_point_pose.translation()) -
273  goal_start_translation.cross(start_pose.translation()))
274  .norm()) > fabs(translation_norm_tolerance))
275  {
276  std::cout << "Translational linearity is violated. \n"
277  << "goal translation: " << goal_pose_expect.translation() << '\n'
278  << "start translation: " << start_pose.translation() << '\n'
279  << "actual translation " << way_point_pose.translation() << '\n';
280  return false;
281  }
282 
283  if (!checkSLERP(start_pose, goal_pose_expect, way_point_pose, rot_axis_norm_tolerance))
284  {
285  return false;
286  }
287  }
288 
289  return true;
290 }
291 
292 bool testutils::checkSLERP(const Eigen::Isometry3d& start_pose, const Eigen::Isometry3d& goal_pose,
293  const Eigen::Isometry3d& wp_pose, const double rot_axis_norm_tolerance,
294  const double rot_angle_tolerance)
295 {
296  // rotational linearity
297  // start way point angle axis
298  Eigen::AngleAxisd start_goal_aa(start_pose.rotation().transpose() * goal_pose.rotation());
299  Eigen::AngleAxisd start_wp_aa(start_pose.rotation().transpose() * wp_pose.rotation());
300 
301  // parallel rotation axis
302  // it is possible the axis opposite is
303  // if the angle is zero, axis is arbitrary
304  if (!(((start_goal_aa.axis() - start_wp_aa.axis()).norm() < fabs(rot_axis_norm_tolerance)) ||
305  ((start_goal_aa.axis() + start_wp_aa.axis()).norm() < fabs(rot_axis_norm_tolerance)) ||
306  (fabs(start_wp_aa.angle()) < fabs(rot_angle_tolerance))))
307  {
308  std::cout << "Rotational linearity is violated. \n"
309  << '\n'
310  << "start goal angle: " << start_goal_aa.angle() << "; axis: " << '\n'
311  << start_goal_aa.axis() << '\n'
312  << "start waypoint angle: " << start_wp_aa.angle() << "; axis: " << '\n'
313  << start_wp_aa.axis() << '\n';
314 
315  return false;
316  }
317 
318  return true;
319 }
320 
321 bool testutils::computeLinkFK(const moveit::core::RobotModelConstPtr& robot_model, const std::string& link_name,
322  const std::map<std::string, double>& joint_state, Eigen::Isometry3d& pose)
323 {
324  // create robot state
325  moveit::core::RobotState rstate(robot_model);
326  rstate.setToDefaultValues();
327 
328  // check the reference frame of the target pose
329  if (!rstate.knowsFrameTransform(link_name))
330  {
331  RCLCPP_ERROR_STREAM(LOGGER, "The target link " << link_name << " is not known by robot.");
332  return false;
333  }
334 
335  // set the joint positions
336  try
337  {
338  rstate.setVariablePositions(joint_state);
339  }
340  catch (const std::exception& e)
341  {
342  std::cerr << e.what() << '\n';
343  return false;
344  }
345 
346  // update the frame
347  rstate.update();
348  pose = rstate.getFrameTransform(link_name);
349 
350  return true;
351 }
352 
353 bool testutils::isVelocityBounded(const trajectory_msgs::msg::JointTrajectory& trajectory,
355 {
356  for (const auto& point : trajectory.points)
357  {
358  for (std::size_t i = 0; i < point.velocities.size(); ++i)
359  {
360  if (fabs(point.velocities.at(i)) > fabs(joint_limits.getLimit(trajectory.joint_names.at(i)).max_velocity))
361  {
362  std::cerr << "[ Fail ] Joint velocity limit violated in " << i << "th waypoint of joint: "
363  << " Joint Name: " << trajectory.joint_names.at(i) << "; Position: " << point.positions.at(i)
364  << "; Velocity: " << point.velocities.at(i) << "; Acceleration: " << point.accelerations.at(i)
365  << "; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
366  << "; Velocity Limit: " << joint_limits.getLimit(trajectory.joint_names.at(i)).max_velocity << '\n';
367 
368  return false;
369  }
370  }
371  }
372 
373  return true;
374 }
375 
376 bool testutils::isTrajectoryConsistent(const trajectory_msgs::msg::JointTrajectory& trajectory)
377 {
378  for (const auto& point : trajectory.points)
379  {
380  if (trajectory.joint_names.size() != point.positions.size() ||
381  trajectory.joint_names.size() != point.velocities.size() ||
382  trajectory.joint_names.size() != point.accelerations.size())
383  {
384  return false;
385  }
386  }
387 
388  // TODO check value is consistent (time, position, velocity, acceleration)
389 
390  return true;
391 }
392 
393 bool testutils::isAccelerationBounded(const trajectory_msgs::msg::JointTrajectory& trajectory,
395 {
396  for (const auto& point : trajectory.points)
397  {
398  for (std::size_t i = 0; i < point.velocities.size(); ++i)
399  {
400  // deceleration
401  if (point.velocities.at(i) * point.accelerations.at(i) <= 0)
402  {
403  if (fabs(point.accelerations.at(i)) > fabs(joint_limits.getLimit(trajectory.joint_names.at(i)).max_deceleration))
404  {
405  std::cerr << "[ Fail ] Deceleration limit violated of joint: " << trajectory.joint_names.at(i)
406  << ": Position: " << point.positions.at(i) << "; Velocity: " << point.velocities.at(i)
407  << "; Acceleration: " << point.accelerations.at(i)
408  << "; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
409  << ". Deceleration Limit: " << joint_limits.getLimit(trajectory.joint_names.at(i)).max_deceleration
410  << '\n';
411  return false;
412  }
413  }
414  // acceleration
415  else
416  {
417  if (fabs(point.accelerations.at(i)) > fabs(joint_limits.getLimit(trajectory.joint_names.at(i)).max_acceleration))
418  {
419  std::cerr << "[ Fail ] Acceleration limit violated of joint: " << trajectory.joint_names.at(i)
420  << ": Position: " << point.positions.at(i) << "; Velocity: " << point.velocities.at(i)
421  << "; Acceleration: " << point.accelerations.at(i)
422  << "; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
423  << ". Acceleration Limit: " << joint_limits.getLimit(trajectory.joint_names.at(i)).max_acceleration
424  << '\n';
425 
426  return false;
427  }
428  }
429  }
430  }
431 
432  return true;
433 }
434 
435 bool testutils::isPositionBounded(const trajectory_msgs::msg::JointTrajectory& trajectory,
437 {
438  for (const auto& point : trajectory.points)
439  {
440  for (std::size_t i = 0; i < point.positions.size(); ++i)
441  {
442  if (point.positions.at(i) > joint_limits.getLimit(trajectory.joint_names.at(i)).max_position ||
443  point.positions.at(i) < joint_limits.getLimit(trajectory.joint_names.at(i)).min_position)
444  {
445  std::cerr << "[ Fail ] Joint position limit violated in " << i << "th waypoint of joint: "
446  << " Joint Name: " << trajectory.joint_names.at(i) << "; Position: " << point.positions.at(i)
447  << "; Velocity: " << point.velocities.at(i) << "; Acceleration: " << point.accelerations.at(i)
448  << "; Time from start: " << rclcpp::Duration(point.time_from_start).seconds()
449  << "; Max Position: " << joint_limits.getLimit(trajectory.joint_names.at(i)).max_position
450  << "; Min Position: " << joint_limits.getLimit(trajectory.joint_names.at(i)).min_position << '\n';
451 
452  return false;
453  }
454  }
455  }
456 
457  return true;
458 }
459 
460 bool testutils::checkJointTrajectory(const trajectory_msgs::msg::JointTrajectory& trajectory,
462 {
463  if (!testutils::isTrajectoryConsistent(trajectory))
464  {
465  std::cout << "Joint trajectory is not consistent." << '\n';
466  return false;
467  }
468  if (!testutils::isPositionBounded(trajectory, joint_limits))
469  {
470  std::cout << "Joint poisiton violated the limits." << '\n';
471  return false;
472  }
473  if (!testutils::isVelocityBounded(trajectory, joint_limits))
474  {
475  std::cout << "Joint velocity violated the limits." << '\n';
476  return false;
477  }
479  {
480  std::cout << "Joint acceleration violated the limits." << '\n';
481  return false;
482  }
483 
484  return true;
485 }
486 
487 ::testing::AssertionResult testutils::hasStrictlyIncreasingTime(const robot_trajectory::RobotTrajectoryPtr& trajectory)
488 {
489  // Check for strictly positively increasing time steps
490  for (unsigned int i = 1; i < trajectory->getWayPointCount(); ++i)
491  {
492  if (trajectory->getWayPointDurationFromPrevious(i) <= 0.0)
493  {
494  return ::testing::AssertionFailure()
495  << "Waypoint " << (i) << " has " << trajectory->getWayPointDurationFromPrevious(i)
496  << " time between itself and its predecessor."
497  << " Total points in trajectory: " << trajectory->getWayPointCount() << '.';
498  }
499  }
500 
501  return ::testing::AssertionSuccess();
502 }
503 
504 void testutils::createDummyRequest(const moveit::core::RobotModelConstPtr& robot_model,
505  const std::string& planning_group, planning_interface::MotionPlanRequest& req)
506 {
507  // valid motion plan request with goal in joint space
508  req.group_name = planning_group;
509  req.max_velocity_scaling_factor = 1.0;
510  req.max_acceleration_scaling_factor = 1.0;
511  moveit::core::RobotState rstate(robot_model);
512  rstate.setToDefaultValues();
513  moveit::core::robotStateToRobotStateMsg(rstate, req.start_state, false);
514 }
515 
516 void testutils::createPTPRequest(const std::string& planning_group, const moveit::core::RobotState& start_state,
518 {
519  // valid motion plan request with goal in joint space
520  req.planner_id = "PTP";
521  req.group_name = planning_group;
522  req.max_velocity_scaling_factor = 0.5;
523  req.max_acceleration_scaling_factor = 0.5;
524  // start state
525  moveit::core::robotStateToRobotStateMsg(start_state, req.start_state, false);
526  // goal state
527  req.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
528  goal_state, goal_state.getRobotModel()->getJointModelGroup(planning_group)));
529 }
530 
531 bool testutils::toTCPPose(const moveit::core::RobotModelConstPtr& robot_model, const std::string& link_name,
532  const std::vector<double>& joint_values, geometry_msgs::msg::Pose& pose,
533  const std::string& joint_prefix)
534 {
535  {
536  std::map<std::string, double> joint_state;
537  auto joint_values_it = joint_values.begin();
538 
539  // initializing all joints of the model
540  for (const auto& joint_name : robot_model->getVariableNames())
541  {
542  joint_state[joint_name] = 0;
543  }
544 
545  for (std::size_t i = 0; i < joint_values.size(); ++i)
546  {
547  joint_state[testutils::getJointName(i + 1, joint_prefix)] = *joint_values_it;
548  ++joint_values_it;
549  }
550 
551  Eigen::Isometry3d eig_pose;
552  if (!testutils::computeLinkFK(robot_model, link_name, joint_state, eig_pose))
553  {
554  return false;
555  }
556  pose = tf2::toMsg(eig_pose);
557  return true;
558  }
559 }
560 
563  const double time_tolerance)
564 {
565  for (std::size_t i = 0; i < res.first_trajectory->getWayPointCount(); ++i)
566  {
567  for (const std::string& joint_name :
568  res.first_trajectory->getWayPoint(i).getJointModelGroup(req.group_name)->getActiveJointModelNames())
569  {
570  // check joint position
571  if (res.first_trajectory->getWayPoint(i).getVariablePosition(joint_name) !=
572  req.first_trajectory->getWayPoint(i).getVariablePosition(joint_name))
573  {
574  std::cout << i << "th position of the first trajectory is not same." << '\n';
575  return false;
576  }
577 
578  // check joint velocity
579  if (res.first_trajectory->getWayPoint(i).getVariableVelocity(joint_name) !=
580  req.first_trajectory->getWayPoint(i).getVariableVelocity(joint_name))
581  {
582  std::cout << i << "th velocity of the first trajectory is not same." << '\n';
583  return false;
584  }
585 
586  // check joint acceleration
587  if (res.first_trajectory->getWayPoint(i).getVariableAcceleration(joint_name) !=
588  req.first_trajectory->getWayPoint(i).getVariableAcceleration(joint_name))
589  {
590  std::cout << i << "th acceleration of the first trajectory is not same." << '\n';
591  return false;
592  }
593  }
594 
595  // check time from start
596  if (res.first_trajectory->getWayPointDurationFromStart(i) != req.first_trajectory->getWayPointDurationFromStart(i))
597  {
598  std::cout << i << "th time_from_start of the first trajectory is not same." << '\n';
599  return false;
600  }
601  }
602 
603  size_t size_second = res.second_trajectory->getWayPointCount();
604  size_t size_second_original = req.second_trajectory->getWayPointCount();
605  for (std::size_t i = 0; i < size_second; ++i)
606  {
607  for (const std::string& joint_name : res.second_trajectory->getWayPoint(size_second - i - 1)
608  .getJointModelGroup(req.group_name)
609  ->getActiveJointModelNames())
610  {
611  // check joint position
612  if (res.second_trajectory->getWayPoint(size_second - i - 1).getVariablePosition(joint_name) !=
613  req.second_trajectory->getWayPoint(size_second_original - i - 1).getVariablePosition(joint_name))
614  {
615  std::cout << i - 1 << "th position of the second trajectory is not same." << '\n';
616  return false;
617  }
618 
619  // check joint velocity
620  if (res.second_trajectory->getWayPoint(size_second - i - 1).getVariableVelocity(joint_name) !=
621  req.second_trajectory->getWayPoint(size_second_original - i - 1).getVariableVelocity(joint_name))
622  {
623  std::cout << i - 1 << "th position of the second trajectory is not same." << '\n';
624  return false;
625  }
626 
627  // check joint acceleration
628  if (res.second_trajectory->getWayPoint(size_second - i - 1).getVariableAcceleration(joint_name) !=
629  req.second_trajectory->getWayPoint(size_second_original - i - 1).getVariableAcceleration(joint_name))
630  {
631  std::cout << i - 1 << "th position of the second trajectory is not same." << '\n';
632  return false;
633  }
634  }
635 
636  // check time from start
637  if (i < size_second - 1)
638  {
639  if (fabs((res.second_trajectory->getWayPointDurationFromStart(size_second - i - 1) -
640  res.second_trajectory->getWayPointDurationFromStart(size_second - i - 2)) -
641  (req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) -
642  req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2))) > time_tolerance)
643  {
644  std::cout << size_second - i - 1 << "th time from start of the second trajectory is not same."
645  << res.second_trajectory->getWayPointDurationFromStart(size_second - i - 1) << ", "
646  << res.second_trajectory->getWayPointDurationFromStart(size_second - i - 2) << ", "
647  << req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) << ", "
648  << req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2) << '\n';
649  return false;
650  }
651  }
652  else
653  {
654  if (fabs((res.second_trajectory->getWayPointDurationFromStart(size_second - i - 1)) -
655  (req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) -
656  req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2))) > time_tolerance)
657  {
658  std::cout << size_second - i - 1 << "th time from start of the second trajectory is not same."
659  << res.second_trajectory->getWayPointDurationFromStart(size_second - i - 1) << ", "
660  << req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 1) -
661  req.second_trajectory->getWayPointDurationFromStart(size_second_original - i - 2)
662  << '\n';
663  return false;
664  }
665  }
666  }
667 
668  return true;
669 }
670 
672  double joint_velocity_tolerance, double joint_accleration_tolerance)
673 {
674  // convert to msgs
675  moveit_msgs::msg::RobotTrajectory first_traj, blend_traj, second_traj;
676  res.first_trajectory->getRobotTrajectoryMsg(first_traj);
677  res.blend_trajectory->getRobotTrajectoryMsg(blend_traj);
678  res.second_trajectory->getRobotTrajectoryMsg(second_traj);
679 
680  // check the continuity between first trajectory and blend trajectory
681  trajectory_msgs::msg::JointTrajectoryPoint first_end, blend_start;
682  first_end = first_traj.joint_trajectory.points.back();
683  blend_start = blend_traj.joint_trajectory.points.front();
684 
685  // check the dimensions
686  if (first_end.positions.size() != blend_start.positions.size() ||
687  first_end.velocities.size() != blend_start.velocities.size() ||
688  first_end.accelerations.size() != blend_start.accelerations.size())
689  {
690  std::cout << "Different sizes of the position/velocity/acceleration "
691  "between first trajectory and blend trajectory."
692  << '\n';
693  return false;
694  }
695 
696  // check the velocity and acceleration
697  for (std::size_t i = 0; i < first_end.positions.size(); ++i)
698  {
699  double blend_start_velo = (blend_start.positions.at(i) - first_end.positions.at(i)) /
700  rclcpp::Duration(blend_start.time_from_start).seconds();
701  if (fabs(blend_start_velo - blend_start.velocities.at(i)) > joint_velocity_tolerance)
702  {
703  std::cout << "Velocity computed from positions are different from the "
704  "value in trajectory."
705  << '\n'
706  << "position: " << blend_start.positions.at(i) << "; " << first_end.positions.at(i)
707  << "computed: " << blend_start_velo << "; "
708  << "in trajectory: " << blend_start.velocities.at(i) << '\n';
709  return false;
710  }
711 
712  double blend_start_acc =
713  (blend_start_velo - first_end.velocities.at(i)) / rclcpp::Duration(blend_start.time_from_start).seconds();
714  if (fabs(blend_start_acc - blend_start.accelerations.at(i)) > joint_velocity_tolerance)
715  {
716  std::cout << "Acceleration computed from positions/velocities are "
717  "different from the value in trajectory."
718  << '\n'
719  << "computed: " << blend_start_acc << "; "
720  << "in trajectory: " << blend_start.accelerations.at(i) << '\n';
721  return false;
722  }
723  }
724 
725  // check the continuity between blend trajectory and second trajectory
726  trajectory_msgs::msg::JointTrajectoryPoint blend_end, second_start;
727  blend_end = blend_traj.joint_trajectory.points.back();
728  second_start = second_traj.joint_trajectory.points.front();
729 
730  // check the dimensions
731  if (blend_end.positions.size() != second_start.positions.size() ||
732  blend_end.velocities.size() != second_start.velocities.size() ||
733  blend_end.accelerations.size() != second_start.accelerations.size())
734  {
735  std::cout << "Different sizes of the position/velocity/acceleration "
736  "between first trajectory and blend trajectory."
737  << '\n'
738  << blend_end.positions.size() << ", " << second_start.positions.size() << '\n'
739  << blend_end.velocities.size() << ", " << second_start.positions.size() << '\n'
740  << blend_end.accelerations.size() << ", " << second_start.accelerations.size() << '\n';
741  return false;
742  }
743 
744  // check the velocity and acceleration
745  for (std::size_t i = 0; i < blend_end.positions.size(); ++i)
746  {
747  double second_start_velo = (second_start.positions.at(i) - blend_end.positions.at(i)) /
748  rclcpp::Duration(second_start.time_from_start).seconds();
749  if (fabs(second_start_velo - second_start.velocities.at(i)) > joint_accleration_tolerance)
750  {
751  std::cout << "Velocity computed from positions are different from the "
752  "value in trajectory."
753  << '\n'
754  << "computed: " << second_start_velo << "; "
755  << "in trajectory: " << second_start.velocities.at(i) << '\n';
756  return false;
757  }
758 
759  double second_start_acc =
760  (second_start_velo - blend_end.velocities.at(i)) / rclcpp::Duration(second_start.time_from_start).seconds();
761  if (fabs(second_start_acc - second_start.accelerations.at(i)) > joint_accleration_tolerance)
762  {
763  std::cout << "Acceleration computed from positions/velocities are "
764  "different from the value in trajectory."
765  << '\n'
766  << "computed: " << second_start_acc << "; "
767  << "in trajectory: " << second_start.accelerations.at(i) << '\n';
768  return false;
769  }
770  }
771 
772  return true;
773 }
774 
778 {
779  // sampling time
780  double duration = res.blend_trajectory->getWayPointDurationFromPrevious(res.blend_trajectory->getWayPointCount() - 1);
781  if (duration == 0.0)
782  {
783  std::cout << "Cannot perform check of cartesian space continuity with "
784  "sampling time 0.0"
785  << '\n';
786  return false;
787  }
788 
789  // limits
790  double max_trans_velo = planner_limits.getCartesianLimits().max_trans_vel;
791  double max_trans_acc = planner_limits.getCartesianLimits().max_trans_acc;
792  double max_rot_velo = planner_limits.getCartesianLimits().max_rot_vel;
793  double max_rot_acc = max_trans_acc / max_trans_velo * max_rot_velo;
794 
795  // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
796  // +++ check the connection points between three trajectories +++
797  // ++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
798 
799  // connection points
800  Eigen::Isometry3d pose_first_end, pose_first_end_1, pose_blend_start, pose_blend_start_1, pose_blend_end,
801  pose_blend_end_1, pose_second_start, pose_second_start_1;
802  // one sample before last point of first trajectory
803  pose_first_end_1 = res.first_trajectory->getWayPointPtr(res.first_trajectory->getWayPointCount() - 2)
804  ->getFrameTransform(req.link_name);
805  // last point of first trajectory
806  pose_first_end = res.first_trajectory->getLastWayPointPtr()->getFrameTransform(req.link_name);
807  // first point of blend trajectory
808  pose_blend_start = res.blend_trajectory->getFirstWayPointPtr()->getFrameTransform(req.link_name);
809  // second point of blend trajectory
810  pose_blend_start_1 = res.blend_trajectory->getWayPointPtr(1)->getFrameTransform(req.link_name);
811  // one sample before last point of blend trajectory
812  pose_blend_end_1 = res.blend_trajectory->getWayPointPtr(res.blend_trajectory->getWayPointCount() - 2)
813  ->getFrameTransform(req.link_name);
814  // last point of blend trajectory
815  pose_blend_end = res.blend_trajectory->getLastWayPointPtr()->getFrameTransform(req.link_name);
816  // first point of second trajectory
817  pose_second_start = res.second_trajectory->getFirstWayPointPtr()->getFrameTransform(req.link_name);
818  // second point of second trajectory
819  pose_second_start_1 = res.second_trajectory->getWayPointPtr(1)->getFrameTransform(req.link_name);
820 
821  // std::cout << "### sample duration: " << duration << " ###" << '\n';
822  // std::cout << "### end pose of first trajectory ###" << '\n';
823  // std::cout << pose_first_end.matrix() << '\n';
824  // std::cout << "### start pose of blend trajectory ###" << '\n';
825  // std::cout << pose_blend_start.matrix() << '\n';
826  // std::cout << "### end pose of blend trajectory ###" << '\n';
827  // std::cout << pose_blend_end.matrix() << '\n';
828  // std::cout << "### start pose of second trajectory ###" << '\n';
829  // std::cout << pose_second_start.matrix() << '\n';
830 
831  // std::cout << "### v_1 ###" << '\n';
832  // std::cout << v_1 << '\n';
833  // std::cout << "### w_1 ###" << '\n';
834  // std::cout << w_1 << '\n';
835  // std::cout << "### v_2 ###" << '\n';
836  // std::cout << v_2 << '\n';
837  // std::cout << "### w_2 ###" << '\n';
838  // std::cout << w_2 << '\n';
839  // std::cout << "### v_3 ###" << '\n';
840  // std::cout << v_3 << '\n';
841  // std::cout << "### w_3 ###" << '\n';
842  // std::cout << w_3 << '\n';
843 
844  // check the connection points between first trajectory and blend trajectory
845  Eigen::Vector3d v_1, w_1, v_2, w_2, v_3, w_3;
846  computeCartVelocity(pose_first_end_1, pose_first_end, duration, v_1, w_1);
847  computeCartVelocity(pose_first_end, pose_blend_start, duration, v_2, w_2);
848  computeCartVelocity(pose_blend_start, pose_blend_start_1, duration, v_3, w_3);
849 
850  // translational velocity
851  if (v_2.norm() > max_trans_velo)
852  {
853  std::cout << "Translational velocity between first trajectory and blend "
854  "trajectory exceeds the limit."
855  << "Actual velocity (norm): " << v_2.norm() << "; "
856  << "Limits: " << max_trans_velo << '\n';
857  }
858  // rotational velocity
859  if (w_2.norm() > max_rot_velo)
860  {
861  std::cout << "Rotational velocity between first trajectory and blend "
862  "trajectory exceeds the limit."
863  << "Actual velocity (norm): " << w_2.norm() << "; "
864  << "Limits: " << max_rot_velo << '\n';
865  }
866  // translational acceleration
867  Eigen::Vector3d a_1 = (v_2 - v_1) / duration;
868  Eigen::Vector3d a_2 = (v_3 - v_2) / duration;
869  if (a_1.norm() > max_trans_acc || a_2.norm() > max_trans_acc)
870  {
871  std::cout << "Translational acceleration between first trajectory and "
872  "blend trajectory exceeds the limit."
873  << "Actual acceleration (norm): " << a_1.norm() << ", " << a_1.norm() << "; "
874  << "Limits: " << max_trans_acc << '\n';
875  }
876 
877  // rotational acceleration
878  a_1 = (w_2 - w_1) / duration;
879  a_2 = (w_3 - w_2) / duration;
880  if (a_1.norm() > max_rot_acc || a_2.norm() > max_rot_acc)
881  {
882  std::cout << "Rotational acceleration between first trajectory and blend "
883  "trajectory exceeds the limit."
884  << "Actual acceleration (norm): " << a_1.norm() << ", " << a_1.norm() << "; "
885  << "Limits: " << max_rot_acc << '\n';
886  }
887 
888  computeCartVelocity(pose_blend_end_1, pose_blend_end, duration, v_1, w_1);
889  computeCartVelocity(pose_blend_end, pose_second_start, duration, v_2, w_2);
890  computeCartVelocity(pose_second_start, pose_second_start_1, duration, v_3, w_3);
891 
892  if (v_2.norm() > max_trans_velo)
893  {
894  std::cout << "Translational velocity between blend trajectory and second "
895  "trajectory exceeds the limit."
896  << "Actual velocity (norm): " << v_2.norm() << "; "
897  << "Limits: " << max_trans_velo << '\n';
898  }
899  if (w_2.norm() > max_rot_velo)
900  {
901  std::cout << "Rotational velocity between blend trajectory and second "
902  "trajectory exceeds the limit."
903  << "Actual velocity (norm): " << w_2.norm() << "; "
904  << "Limits: " << max_rot_velo << '\n';
905  }
906  a_1 = (v_2 - v_1) / duration;
907  a_2 = (v_3 - v_2) / duration;
908  if (a_1.norm() > max_trans_acc || a_2.norm() > max_trans_acc)
909  {
910  std::cout << "Translational acceleration between blend trajectory and "
911  "second trajectory exceeds the limit."
912  << "Actual acceleration (norm): " << a_1.norm() << ", " << a_1.norm() << "; "
913  << "Limits: " << max_trans_acc << '\n';
914  }
915  // check rotational acceleration
916  a_1 = (w_2 - w_1) / duration;
917  a_2 = (w_3 - w_2) / duration;
918  if (a_1.norm() > max_rot_acc || a_2.norm() > max_rot_acc)
919  {
920  std::cout << "Rotational acceleration between blend trajectory and second "
921  "trajectory exceeds the limit."
922  << "Actual acceleration (norm): " << a_1.norm() << ", " << a_1.norm() << "; "
923  << "Limits: " << max_rot_acc << '\n';
924  }
925 
926  return true;
927 }
928 
929 bool testutils::checkThatPointsInRadius(const std::string& link_name, double r, Eigen::Isometry3d& circ_pose,
931 {
932  bool result = true;
933  for (size_t i = 1; i < res.blend_trajectory->getWayPointCount() - 1; ++i)
934  {
935  Eigen::Isometry3d curr_pos(res.blend_trajectory->getWayPointPtr(i)->getFrameTransform(link_name));
936  if ((curr_pos.translation() - circ_pose.translation()).norm() > r)
937  {
938  std::cout << "Point " << i << " does not lie within blending radius (dist: "
939  << ((curr_pos.translation() - circ_pose.translation()).norm() - r) << ")." << '\n';
940  result = false;
941  }
942  }
943  return result;
944 }
945 
946 void testutils::computeCartVelocity(const Eigen::Isometry3d& pose_1, const Eigen::Isometry3d& pose_2, double duration,
948 {
949  // translational velocity
950  v = (pose_2.translation() - pose_1.translation()) / duration;
951 
952  // angular velocity
953  // reference: A Mathematical Introduction to Robotics Manipulation 2.4.1
954  // Rotational velocity
955  Eigen::Matrix3d rm_1 = pose_1.linear();
956  Eigen::Matrix3d rm_2 = pose_2.linear();
957  Eigen::Matrix3d rm_dot = (rm_2 - rm_1) / duration;
958  Eigen::Matrix3d w_hat = rm_dot * rm_1.transpose();
959  w(0) = w_hat(2, 1);
960  w(1) = w_hat(0, 2);
961  w(2) = w_hat(1, 0);
962 }
963 
964 void testutils::getLinLinPosesWithoutOriChange(const std::string& frame_id,
965  sensor_msgs::msg::JointState& initialJointState,
966  geometry_msgs::msg::PoseStamped& p1, geometry_msgs::msg::PoseStamped& p2)
967 {
968  initialJointState =
969  testutils::generateJointState({ 0., 0.007881892504574495, -1.8157263253868452, 0., 1.8236082178909834, 0. });
970 
971  p1.header.frame_id = frame_id;
972  p1.pose.position.x = 0.25;
973  p1.pose.position.y = 0.3;
974  p1.pose.position.z = 0.65;
975  p1.pose.orientation.x = 0.;
976  p1.pose.orientation.y = 0.;
977  p1.pose.orientation.z = 0.;
978  p1.pose.orientation.w = 1.;
979 
980  p2 = p1;
981  p2.pose.position.x -= 0.15;
982 }
983 
984 void testutils::getOriChange(Eigen::Matrix3d& ori1, Eigen::Matrix3d& ori2)
985 {
986  ori1 = Eigen::AngleAxisd(0.2 * M_PI, Eigen::Vector3d::UnitZ());
987  ori2 = Eigen::AngleAxisd(0.4 * M_PI, Eigen::Vector3d::UnitZ());
988 }
989 
990 void testutils::createFakeCartTraj(const robot_trajectory::RobotTrajectoryPtr& traj, const std::string& link_name,
991  moveit_msgs::msg::RobotTrajectory& fake_traj)
992 {
993  fake_traj.joint_trajectory.joint_names.push_back("x");
994  fake_traj.joint_trajectory.joint_names.push_back("y");
995  fake_traj.joint_trajectory.joint_names.push_back("z");
996  // fake_traj.joint_trajectory.joint_names.push_back("a");
997  // fake_traj.joint_trajectory.joint_names.push_back("b");
998  // fake_traj.joint_trajectory.joint_names.push_back("c");
999 
1000  for (size_t i = 0; i < traj->getWayPointCount(); ++i)
1001  {
1002  trajectory_msgs::msg::JointTrajectoryPoint waypoint;
1003  waypoint.time_from_start = rclcpp::Duration::from_seconds(traj->getWayPointDurationFromStart(i));
1004  Eigen::Isometry3d waypoint_pose = traj->getWayPointPtr(i)->getFrameTransform(link_name);
1005  Eigen::Vector3d waypoint_position = waypoint_pose.translation();
1006  waypoint.positions.push_back(waypoint_position(0));
1007  waypoint.positions.push_back(waypoint_position(1));
1008  waypoint.positions.push_back(waypoint_position(2));
1009  waypoint.velocities.push_back(0);
1010  waypoint.velocities.push_back(0);
1011  waypoint.velocities.push_back(0);
1012  waypoint.accelerations.push_back(0);
1013  waypoint.accelerations.push_back(0);
1014  waypoint.accelerations.push_back(0);
1015  fake_traj.joint_trajectory.points.push_back(waypoint);
1016  }
1017 }
1018 
1019 bool testutils::getBlendTestData(const rclcpp::Node::SharedPtr& node, const size_t& dataset_num,
1020  const std::string& name_prefix, std::vector<testutils::BlendTestData>& datasets)
1021 {
1022  datasets.clear();
1023  testutils::BlendTestData dataset;
1024  auto get_parameter = [&](const std::string& name, std::vector<double>& parameter,
1025  const rclcpp::Node::SharedPtr& node) {
1026  if (node->has_parameter(name))
1027  {
1028  node->get_parameter<std::vector<double>>(name, parameter);
1029  return true;
1030  }
1031  else
1032  return false;
1033  };
1034 
1035  for (size_t i = 1; i < dataset_num + 1; ++i)
1036  {
1037  std::string data_set_name = "blend_set_" + std::to_string(i);
1038  if (get_parameter(name_prefix + data_set_name + "/start_position", dataset.start_position, node) &&
1039  get_parameter(name_prefix + data_set_name + "/mid_position", dataset.mid_position, node) &&
1040  get_parameter(name_prefix + data_set_name + "/end_position", dataset.end_position, node))
1041  {
1042  datasets.push_back(dataset);
1043  }
1044  else
1045  {
1046  return false;
1047  }
1048  }
1049  return true;
1050 }
1051 
1053  const planning_scene::PlanningSceneConstPtr& scene,
1054  const std::shared_ptr<pilz_industrial_motion_planner::TrajectoryGenerator>& tg, const std::string& group_name,
1055  const std::string& link_name, const testutils::BlendTestData& data, double sampling_time_1, double sampling_time_2,
1057  double& dis_2)
1058 {
1059  const moveit::core::RobotModelConstPtr robot_model = scene->getRobotModel();
1060 
1061  // generate first trajectory
1063  req_1.group_name = group_name;
1064  req_1.max_velocity_scaling_factor = 0.1;
1065  req_1.max_acceleration_scaling_factor = 0.1;
1066  // start state
1067  moveit::core::RobotState start_state(robot_model);
1068  start_state.setToDefaultValues();
1069  start_state.setJointGroupPositions(group_name, data.start_position);
1070  moveit::core::robotStateToRobotStateMsg(start_state, req_1.start_state, false);
1071  // goal constraint
1072  moveit::core::RobotState goal_state_1(robot_model);
1073  goal_state_1.setToDefaultValues();
1074  goal_state_1.setJointGroupPositions(group_name, data.mid_position);
1075  req_1.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
1076  goal_state_1, goal_state_1.getRobotModel()->getJointModelGroup(group_name)));
1077 
1078  // trajectory generation
1079  tg->generate(scene, req_1, res_1, sampling_time_1);
1080  if (res_1.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
1081  {
1082  std::cout << "Failed to generate first trajectory." << '\n';
1083  return false;
1084  }
1085 
1086  // generate second LIN trajectory
1088  req_2.group_name = group_name;
1089  req_2.max_velocity_scaling_factor = 0.1;
1090  req_2.max_acceleration_scaling_factor = 0.1;
1091  // start state
1092  moveit::core::robotStateToRobotStateMsg(goal_state_1, req_2.start_state, false);
1093  // goal state
1094  moveit::core::RobotState goal_state_2(robot_model);
1095  goal_state_2.setToDefaultValues();
1096  goal_state_2.setJointGroupPositions(group_name, data.end_position);
1097  req_2.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
1098  goal_state_2, goal_state_2.getRobotModel()->getJointModelGroup(group_name)));
1099  // trajectory generation
1100  tg->generate(scene, req_2, res_2, sampling_time_2);
1101  if (res_2.error_code.val != moveit_msgs::msg::MoveItErrorCodes::SUCCESS)
1102  {
1103  std::cout << "Failed to generate second trajectory." << '\n';
1104  return false;
1105  }
1106 
1107  // estimate a proper blend radius
1108  dis_1 =
1109  (start_state.getFrameTransform(link_name).translation() - goal_state_1.getFrameTransform(link_name).translation())
1110  .norm();
1111 
1112  dis_2 = (goal_state_1.getFrameTransform(link_name).translation() -
1113  goal_state_2.getFrameTransform(link_name).translation())
1114  .norm();
1115 
1116  return true;
1117 }
1118 
1122  double joint_velocity_tolerance, double joint_acceleration_tolerance,
1123  double /*cartesian_velocity_tolerance*/,
1124  double /*cartesian_angular_velocity_tolerance*/)
1125 {
1126  // ++++++++++++++++++++++
1127  // + Check trajectories +
1128  // ++++++++++++++++++++++
1129  moveit_msgs::msg::RobotTrajectory traj_msg;
1130  blend_res.first_trajectory->getRobotTrajectoryMsg(traj_msg);
1131  if (!testutils::checkJointTrajectory(traj_msg.joint_trajectory, limits.getJointLimitContainer()))
1132  {
1133  return false;
1134  }
1135 
1136  blend_res.blend_trajectory->getRobotTrajectoryMsg(traj_msg);
1137  if (!testutils::checkJointTrajectory(traj_msg.joint_trajectory, limits.getJointLimitContainer()))
1138  {
1139  return false;
1140  };
1141 
1142  blend_res.second_trajectory->getRobotTrajectoryMsg(traj_msg);
1143  if (!testutils::checkJointTrajectory(traj_msg.joint_trajectory, limits.getJointLimitContainer()))
1144  {
1145  return false;
1146  };
1147 
1148  Eigen::Isometry3d circ_pose =
1149  blend_req.first_trajectory->getLastWayPointPtr()->getFrameTransform(blend_req.link_name);
1150  if (!testutils::checkThatPointsInRadius(blend_req.link_name, blend_req.blend_radius, circ_pose, blend_res))
1151  {
1152  return false;
1153  }
1154 
1155  // check the first and second trajectories, if they are still the same before
1156  // and after the bendling phase
1157  if (!testutils::checkOriginalTrajectoryAfterBlending(blend_req, blend_res, 10e-5))
1158  {
1159  return false;
1160  }
1161 
1162  // check the continuity between the trajectories in joint space
1163  if (!testutils::checkBlendingJointSpaceContinuity(blend_res, joint_velocity_tolerance, joint_acceleration_tolerance))
1164  {
1165  return false;
1166  }
1167 
1168  // check the continuity between the trajectories in cart space
1169  if (!testutils::checkBlendingCartSpaceContinuity(blend_req, blend_res, limits))
1170  {
1171  return false;
1172  }
1173 
1174  // ++++++++++++++++++++++++
1175  // + Visualize the result +
1176  // ++++++++++++++++++++++++
1177  // ros::NodeHandle nh;
1178  // ros::Publisher pub =
1179  // nh.advertise<moveit_msgs::msg::DisplayTrajectory>("my_planned_path", 1);
1180  // ros::Duration duration(1.0);
1181  // duration.sleep();
1182 
1183  // // visualize the joint trajectory
1184  // moveit_msgs::msg::DisplayTrajectory displayTrajectory;
1185  // moveit_msgs::msg::RobotTrajectory res_first_traj_msg, res_blend_traj_msg,
1186  // res_second_traj_msg;
1187  // blend_res.first_trajectory->getRobotTrajectoryMsg(res_first_traj_msg);
1188  // blend_res.blend_trajectory->getRobotTrajectoryMsg(res_blend_traj_msg);
1189  // blend_res.second_trajectory->getRobotTrajectoryMsg(res_second_traj_msg);
1190  // displayTrajectory.trajectory.push_back(res_first_traj_msg);
1191  // displayTrajectory.trajectory.push_back(res_blend_traj_msg);
1192  // displayTrajectory.trajectory.push_back(res_second_traj_msg);
1193 
1194  // pub.publish(displayTrajectory);
1195 
1196  return true;
1197 }
1198 
1199 void testutils::generateRequestMsgFromBlendTestData(const moveit::core::RobotModelConstPtr& robot_model,
1200  const testutils::BlendTestData& data, const std::string& planner_id,
1201  const std::string& group_name, const std::string& link_name,
1202  moveit_msgs::msg::MotionSequenceRequest& req_list)
1203 {
1204  // motion plan request of first trajectory
1206  req_1.planner_id = planner_id;
1207  req_1.group_name = group_name;
1208  req_1.max_velocity_scaling_factor = 0.1;
1209  req_1.max_acceleration_scaling_factor = 0.1;
1210  // start state
1211  moveit::core::RobotState start_state(robot_model);
1212  start_state.setToDefaultValues();
1213  start_state.setJointGroupPositions(group_name, data.start_position);
1214  moveit::core::robotStateToRobotStateMsg(start_state, req_1.start_state, false);
1215  // goal constraint
1216  moveit::core::RobotState goal_state_1(robot_model);
1217  goal_state_1.setToDefaultValues();
1218  goal_state_1.setJointGroupPositions(group_name, data.mid_position);
1219  req_1.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
1220  goal_state_1, goal_state_1.getRobotModel()->getJointModelGroup(group_name)));
1221 
1222  // motion plan request of second trajectory
1224  req_2.planner_id = planner_id;
1225  req_2.group_name = group_name;
1226  req_2.max_velocity_scaling_factor = 0.1;
1227  req_2.max_acceleration_scaling_factor = 0.1;
1228  // start state
1229  // moveit::core::robotStateToRobotStateMsg(goal_state_1, req_2.start_state,
1230  // false);
1231  // goal state
1232  moveit::core::RobotState goal_state_2(robot_model);
1233  goal_state_2.setToDefaultValues();
1234  goal_state_2.setJointGroupPositions(group_name, data.end_position);
1235  req_2.goal_constraints.push_back(kinematic_constraints::constructGoalConstraints(
1236  goal_state_2, goal_state_2.getRobotModel()->getJointModelGroup(group_name)));
1237 
1238  // select a proper blending radius
1239  // estimate a proper blend radius
1240  double dis_1 =
1241  (start_state.getFrameTransform(link_name).translation() - goal_state_1.getFrameTransform(link_name).translation())
1242  .norm();
1243 
1244  double dis_2 = (goal_state_1.getFrameTransform(link_name).translation() -
1245  goal_state_2.getFrameTransform(link_name).translation())
1246  .norm();
1247 
1248  double blend_radius = 0.5 * std::min(dis_1, dis_2);
1249 
1250  moveit_msgs::msg::MotionSequenceItem blend_req_1, blend_req_2;
1251  blend_req_1.req = req_1;
1252  blend_req_1.blend_radius = blend_radius;
1253  blend_req_2.req = req_2;
1254  blend_req_2.blend_radius = 0.0;
1255 
1256  req_list.items.push_back(blend_req_1);
1257  req_list.items.push_back(blend_req_2);
1258 }
1259 
1260 void testutils::checkRobotModel(const moveit::core::RobotModelConstPtr& robot_model, const std::string& group_name,
1261  const std::string& link_name)
1262 {
1263  ASSERT_TRUE(robot_model != nullptr) << "failed to load robot model";
1264  ASSERT_FALSE(robot_model->isEmpty()) << "robot model is empty";
1265  ASSERT_TRUE(robot_model->hasJointModelGroup(group_name)) << group_name << " is not known to robot";
1266  ASSERT_TRUE(robot_model->hasLinkModel(link_name)) << link_name << " is not known to robot";
1267  ASSERT_TRUE(moveit::core::RobotState(robot_model).knowsFrameTransform(link_name))
1268  << "Transform of " << link_name << " is unknown";
1269 }
1270 
1271 ::testing::AssertionResult testutils::hasTrapezoidVelocity(std::vector<double> accelerations, const double acc_tol)
1272 {
1273  // Check that acceleration is monotonously decreasing
1274  if (!isMonotonouslyDecreasing(accelerations, acc_tol))
1275  {
1276  return ::testing::AssertionFailure() << "Cannot be a trapezoid since "
1277  "acceleration is not monotonously "
1278  "decreasing!";
1279  }
1280 
1281  // Check accelerations
1282  double first_acc = accelerations.front();
1283  auto it_last_acc = std::find_if(accelerations.begin(), accelerations.end(),
1284  [first_acc, acc_tol](double el) { return (std::abs(el - first_acc) > acc_tol); }) -
1285  1;
1286 
1287  auto it_last_intermediate =
1288  std::find_if(it_last_acc + 1, accelerations.end(), [acc_tol](double el) { return (el < acc_tol); }) - 1;
1289 
1290  // Check that there are 1 or 2 intermediate points
1291  auto n_intermediate_1 = std::distance(it_last_acc, it_last_intermediate);
1292 
1293  if (n_intermediate_1 != 1 && n_intermediate_1 != 2)
1294  {
1295  return ::testing::AssertionFailure() << "Expected 1 or 2 intermediate points between acceleration and "
1296  "constant "
1297  "velocity phase but found: "
1298  << n_intermediate_1;
1299  }
1300 
1301  // Const phase (vel == 0)
1302  auto it_first_const = it_last_intermediate + 1;
1303  auto it_last_const =
1304  std::find_if(it_first_const, accelerations.end(), [acc_tol](double el) { return (std::abs(el) > acc_tol); }) - 1;
1305  // This test makes sense only if the generated traj has enough points such
1306  // that the trapezoid is not degenerated.
1307  if (std::distance(it_first_const, it_last_const) < 3)
1308  {
1309  return ::testing::AssertionFailure() << "Expected the have at least 3 points during the phase of "
1310  "constant "
1311  "velocity.";
1312  }
1313 
1314  // Deceleration
1315  double deceleration = accelerations.back();
1316  auto it_first_dec =
1317  std::find_if(it_last_const + 1, accelerations.end(),
1318  [deceleration, acc_tol](double el) { return (std::abs(el - deceleration) > acc_tol); }) +
1319  1;
1320 
1321  // Points between const and deceleration (again 1 or 2)
1322  auto n_intermediate_2 = std::distance(it_last_const, it_first_dec);
1323  if (n_intermediate_2 != 1 && n_intermediate_2 != 2)
1324  {
1325  return ::testing::AssertionFailure() << "Expected 1 or 2 intermediate points between constant velocity "
1326  "and "
1327  "deceleration phase but found: "
1328  << n_intermediate_2;
1329  }
1330 
1331  std::stringstream debug_stream;
1332  for (auto it = accelerations.begin(); it != it_last_acc + 1; ++it)
1333  {
1334  debug_stream << *it << "(Acc)" << '\n';
1335  }
1336 
1337  for (auto it = it_last_acc + 1; it != it_last_intermediate + 1; ++it)
1338  {
1339  debug_stream << *it << "(Inter1)" << '\n';
1340  }
1341 
1342  for (auto it = it_first_const; it != it_last_const + 1; ++it)
1343  {
1344  debug_stream << *it << "(Const)" << '\n';
1345  }
1346 
1347  for (auto it = it_last_const + 1; it != it_first_dec; ++it)
1348  {
1349  debug_stream << *it << "(Inter2)" << '\n';
1350  }
1351 
1352  for (auto it = it_first_dec; it != accelerations.end(); ++it)
1353  {
1354  debug_stream << *it << "(Dec)" << '\n';
1355  }
1356 
1357  RCLCPP_DEBUG_STREAM(LOGGER, debug_stream.str());
1358 
1359  return ::testing::AssertionSuccess();
1360 }
1361 
1362 ::testing::AssertionResult
1363 testutils::checkCartesianTranslationalPath(const robot_trajectory::RobotTrajectoryConstPtr& trajectory,
1364  const std::string& link_name, const double acc_tol)
1365 {
1366  // We require the following such that the test makes sense, else the traj
1367  // would have a degenerated velocity profile
1368  EXPECT_GT(trajectory->getWayPointCount(), 9u);
1369 
1370  std::vector<double> accelerations;
1371 
1372  // Iterate over waypoints collect accelerations
1373  for (size_t i = 2; i < trajectory->getWayPointCount(); ++i)
1374  {
1375  auto waypoint_pose_0 = trajectory->getWayPoint(i - 2).getFrameTransform(link_name);
1376  auto waypoint_pose_1 = trajectory->getWayPoint(i - 1).getFrameTransform(link_name);
1377  auto waypoint_pose_2 = trajectory->getWayPoint(i).getFrameTransform(link_name);
1378 
1379  auto t1 = trajectory->getWayPointDurationFromPrevious(i - 1);
1380  auto t2 = trajectory->getWayPointDurationFromPrevious(i);
1381 
1382  auto vel1 = (waypoint_pose_1.translation() - waypoint_pose_0.translation()).norm() / t1;
1383  auto vel2 = (waypoint_pose_2.translation() - waypoint_pose_1.translation()).norm() / t2;
1384  auto acc_transl = (vel2 - vel1) / (t1 + t2);
1385  accelerations.push_back(acc_transl);
1386  }
1387 
1388  return hasTrapezoidVelocity(accelerations, acc_tol);
1389 }
1390 
1391 ::testing::AssertionResult
1392 testutils::checkCartesianRotationalPath(const robot_trajectory::RobotTrajectoryConstPtr& trajectory,
1393  const std::string& link_name, const double rot_axis_tol, const double acc_tol)
1394 {
1395  // skip computations if rotation angle is zero
1396  if (trajectory->getFirstWayPoint().getFrameTransform(link_name).rotation().isApprox(
1397  trajectory->getLastWayPoint().getFrameTransform(link_name).rotation(), rot_axis_tol))
1398  {
1399  return ::testing::AssertionSuccess();
1400  }
1401 
1402  // We require the following such that the test makes sense, else the traj
1403  // would have a degenerated velocity profile
1404  EXPECT_GT(trajectory->getWayPointCount(), 9u);
1405 
1406  std::vector<double> accelerations;
1407  std::vector<Eigen::AngleAxisd> rotation_axes;
1408 
1409  // Iterate over waypoints collect accelerations and rotation axes
1410  for (size_t i = 2; i < trajectory->getWayPointCount(); ++i)
1411  {
1412  auto waypoint_pose_0 = trajectory->getWayPoint(i - 2).getFrameTransform(link_name);
1413  auto waypoint_pose_1 = trajectory->getWayPoint(i - 1).getFrameTransform(link_name);
1414  auto waypoint_pose_2 = trajectory->getWayPoint(i).getFrameTransform(link_name);
1415 
1416  auto t1 = trajectory->getWayPointDurationFromPrevious(i - 1);
1417  auto t2 = trajectory->getWayPointDurationFromPrevious(i);
1418 
1419  Eigen::Quaterniond orientation0(waypoint_pose_0.rotation());
1420  Eigen::Quaterniond orientation1(waypoint_pose_1.rotation());
1421  Eigen::Quaterniond orientation2(waypoint_pose_2.rotation());
1422 
1423  Eigen::AngleAxisd axis1(orientation0 * orientation1.inverse());
1424  Eigen::AngleAxisd axis2(orientation1 * orientation2.inverse());
1425  if (i == 2)
1426  {
1427  rotation_axes.push_back(axis1);
1428  }
1429  rotation_axes.push_back(axis2);
1430 
1431  double angular_vel1 = axis1.angle() / t1;
1432  double angular_vel2 = axis2.angle() / t2;
1433  double angular_acc = (angular_vel2 - angular_vel1) / (t1 + t2);
1434  accelerations.push_back(angular_acc);
1435  }
1436 
1437  // Check that rotation axis is fixed
1438  if (std::adjacent_find(rotation_axes.begin(), rotation_axes.end(),
1439  [rot_axis_tol](const Eigen::AngleAxisd& axis1, const Eigen::AngleAxisd& axis2) {
1440  return ((axis1.axis() - axis2.axis()).norm() > rot_axis_tol);
1441  }) != rotation_axes.end())
1442  {
1443  return ::testing::AssertionFailure() << "Rotational path of trajectory "
1444  "does not have a fixed rotation "
1445  "axis";
1446  }
1447 
1448  return hasTrapezoidVelocity(accelerations, acc_tol);
1449 }
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
Definition: robot_state.h:583
const RobotModelConstPtr & getRobotModel() const
Get the robot model this state is constructed for.
Definition: robot_state.h:104
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool knowsFrameTransform(const std::string &frame_id) const
Check if a transformation matrix from the model frame (root of model) to frame frame_id is known.
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
bool addLimit(const std::string &joint_name, JointLimit joint_limit)
Add a limit.
This class combines CartesianLimit and JointLimits into on single class.
const cartesian_limits::Params & getCartesianLimits() const
Return the cartesian limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
moveit_msgs::msg::Constraints constructGoalConstraints(const moveit::core::RobotState &state, const moveit::core::JointModelGroup *jmg, double tolerance_below, double tolerance_above)
Generates a constraint message intended to be used as a goal constraint for a joint group....
Definition: utils.cpp:152
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
bool jointStateToRobotState(const sensor_msgs::msg::JointState &joint_state, RobotState &state)
Convert a joint state to a MoveIt robot state.
bool computeLinkFK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at give robot state
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
double distance(const urdf::Pose &transform)
Definition: pr2_arm_ik.h:55
name
Definition: setup.py:7
bool checkBlendingCartSpaceContinuity(const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, const pilz_industrial_motion_planner::LimitsContainer &planner_limits)
Definition: test_utils.cpp:775
bool isGoalReached(const trajectory_msgs::msg::JointTrajectory &trajectory, const std::vector< moveit_msgs::msg::JointConstraint > &goal, const double joint_position_tolerance, const double joint_velocity_tolerance=1.0e-6)
check if the goal given in joint space is reached Only the last point in the trajectory is verified.
Definition: test_utils.cpp:118
bool computeLinkFK(const moveit::core::RobotModelConstPtr &robot_model, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
computeLinkFK
Definition: test_utils.cpp:321
sensor_msgs::msg::JointState generateJointState(const std::vector< double > &pos, const std::vector< double > &vel, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX)
Definition: test_utils.h:100
::testing::AssertionResult checkCartesianTranslationalPath(const robot_trajectory::RobotTrajectoryConstPtr &trajectory, const std::string &link_name, const double acc_tol=DEFAULT_ACCELERATION_EQUALITY_TOLERANCE)
Check that the translational path of a given trajectory has a trapezoid velocity profile.
bool isVelocityBounded(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
is Velocity Bounded
Definition: test_utils.cpp:353
void createDummyRequest(const moveit::core::RobotModelConstPtr &robot_model, const std::string &planning_group, planning_interface::MotionPlanRequest &req)
create a dummy motion plan request with zero start state No goal constraint is given.
Definition: test_utils.cpp:504
bool getExpectedGoalPose(const moveit::core::RobotModelConstPtr &robot_model, const planning_interface::MotionPlanRequest &req, std::string &link_name, Eigen::Isometry3d &goal_pose_expect)
Determines the goal position from the given request. TRUE if successful, FALSE otherwise.
Definition: test_utils.cpp:71
bool isAccelerationBounded(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
is Acceleration Bounded
Definition: test_utils.cpp:393
bool checkThatPointsInRadius(const std::string &link_name, double r, Eigen::Isometry3d &circ_pose, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res)
Checks if all points of the blending trajectory lie within the blending radius.
Definition: test_utils.cpp:929
void generateRequestMsgFromBlendTestData(const moveit::core::RobotModelConstPtr &robot_model, const BlendTestData &data, const std::string &planner_id, const std::string &group_name, const std::string &link_name, moveit_msgs::msg::MotionSequenceRequest &req_list)
bool isMonotonouslyDecreasing(const std::vector< double > &vec, double tol)
Definition: test_utils.h:477
bool isTrajectoryConsistent(const trajectory_msgs::msg::JointTrajectory &trajectory)
check if the sizes of the joint position/veloicty/acceleration are correct
Definition: test_utils.cpp:376
void createFakeCartTraj(const robot_trajectory::RobotTrajectoryPtr &traj, const std::string &link_name, moveit_msgs::msg::RobotTrajectory &fake_traj)
Definition: test_utils.cpp:990
bool checkBlendResult(const pilz_industrial_motion_planner::TrajectoryBlendRequest &blend_req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &blend_res, const pilz_industrial_motion_planner::LimitsContainer &limits, double joint_velocity_tolerance, double joint_acceleration_tolerance, double cartesian_velocity_tolerance, double cartesian_angular_velocity_tolerance)
check the blending result of lin-lin
bool getBlendTestData(const rclcpp::Node::SharedPtr &node, const size_t &dataset_num, const std::string &name_prefix, std::vector< BlendTestData > &datasets)
fetch test datasets from node parameters
pilz_industrial_motion_planner::JointLimitsContainer createFakeLimits(const std::vector< std::string > &joint_names)
Create limits for tests to avoid the need to get the limits from the node parameter.
Definition: test_utils.cpp:48
bool checkSLERP(const Eigen::Isometry3d &start_pose, const Eigen::Isometry3d &goal_pose, const Eigen::Isometry3d &wp_pose, const double rot_axis_norm_tolerance, const double rot_angle_tolerance=10e-5)
check SLERP. The orientation should rotate around the same axis linearly.
Definition: test_utils.cpp:292
::testing::AssertionResult hasStrictlyIncreasingTime(const robot_trajectory::RobotTrajectoryPtr &trajectory)
Checks that every waypoint in the trajectory has a non-zero duration between itself and its predecess...
Definition: test_utils.cpp:487
bool checkJointTrajectory(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
check joint trajectory of consistency, position, velocity and acceleration limits
Definition: test_utils.cpp:460
std::string getJointName(size_t joint_number, const std::string &joint_prefix)
Definition: test_utils.h:80
void computeCartVelocity(const Eigen::Isometry3d &pose_1, const Eigen::Isometry3d &pose_2, double duration, Eigen::Vector3d &v, Eigen::Vector3d &w)
compute Cartesian velocity
Definition: test_utils.cpp:946
bool generateTrajFromBlendTestData(const planning_scene::PlanningSceneConstPtr &scene, const std::shared_ptr< pilz_industrial_motion_planner::TrajectoryGenerator > &tg, const std::string &group_name, const std::string &link_name, const BlendTestData &data, double sampling_time_1, double sampling_time_2, planning_interface::MotionPlanResponse &res_lin_1, planning_interface::MotionPlanResponse &res_lin_2, double &dis_lin_1, double &dis_lin_2)
generate two LIN trajectories from test data set
void getOriChange(Eigen::Matrix3d &ori1, Eigen::Matrix3d &ori2)
Definition: test_utils.cpp:984
bool toTCPPose(const moveit::core::RobotModelConstPtr &robot_model, const std::string &link_name, const std::vector< double > &joint_values, geometry_msgs::msg::Pose &pose, const std::string &joint_prefix=testutils::JOINT_NAME_PREFIX)
compute the tcp pose from joint values
Definition: test_utils.cpp:531
void getLinLinPosesWithoutOriChange(const std::string &frame_id, sensor_msgs::msg::JointState &initialJointState, geometry_msgs::msg::PoseStamped &p1, geometry_msgs::msg::PoseStamped &p2)
Returns an initial joint state and two poses which can be used to perform a Lin-Lin movement.
Definition: test_utils.cpp:964
bool checkCartesianLinearity(const moveit::core::RobotModelConstPtr &robot_model, const trajectory_msgs::msg::JointTrajectory &trajectory, const planning_interface::MotionPlanRequest &req, const double translation_norm_tolerance, const double rot_axis_norm_tolerance, const double rot_angle_tolerance=10e-5)
Check that given trajectory is straight line.
Definition: test_utils.cpp:222
bool isPositionBounded(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
is Position Bounded
Definition: test_utils.cpp:435
::testing::AssertionResult hasTrapezoidVelocity(std::vector< double > accelerations, const double acc_tol)
Check that a given vector of accelerations represents a trapezoid velocity profile.
bool checkOriginalTrajectoryAfterBlending(const pilz_industrial_motion_planner::TrajectoryBlendRequest &req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, const double time_tolerance)
checkOriginalTrajectoryAfterBlending
Definition: test_utils.cpp:561
bool checkBlendingJointSpaceContinuity(const pilz_industrial_motion_planner::TrajectoryBlendResponse &res, double joint_velocity_tolerance, double joint_accleration_tolerance)
check the blending result, if the joint space continuity is fulfilled
Definition: test_utils.cpp:671
void createPTPRequest(const std::string &planning_group, const moveit::core::RobotState &start_state, const moveit::core::RobotState &goal_state, planning_interface::MotionPlanRequest &req)
Definition: test_utils.cpp:516
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
::testing::AssertionResult checkCartesianRotationalPath(const robot_trajectory::RobotTrajectoryConstPtr &trajectory, const std::string &link_name, const double rot_axis_tol=DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE, const double acc_tol=DEFAULT_ACCELERATION_EQUALITY_TOLERANCE)
Check that the rotational path of a given trajectory is a quaternion slerp.
Extends joint_limits_interface::JointLimits with a deceleration parameter.
double max_deceleration
maximum deceleration MUST(!) be negative
Response to a planning query.
moveit::core::MoveItErrorCode error_code
Test data for blending, which contains three joint position vectors of three robot state.
Definition: test_utils.h:395
std::vector< double > end_position
Definition: test_utils.h:398
std::vector< double > start_position
Definition: test_utils.h:396
std::vector< double > mid_position
Definition: test_utils.h:397
void normalizeQuaternion(geometry_msgs::msg::Quaternion &quat)