moveit2
The MoveIt Motion Planning Framework for ROS 2.
test_kinematics_plugin.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2015, Southwest Research Institute
5  * 2018, Bielefeld University
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of Willow Garage nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *********************************************************************/
35 
36 /* Author: Jorge Nicho, Robert Haschke */
37 
38 #include <gtest/gtest.h>
39 #include <memory>
40 #include <functional>
41 #include <pluginlib/class_loader.hpp>
42 #include <rclcpp/rclcpp.hpp>
43 #include <tf2_eigen/tf2_eigen.hpp>
44 
45 // MoveIt
51 
53 #include <moveit_msgs/msg/display_trajectory.hpp>
55 
57 
58 static const rclcpp::Logger LOGGER = rclcpp::get_logger("test_kinematics_plugin");
59 const std::string ROBOT_DESCRIPTION_PARAM = "robot_description";
60 const double DEFAULT_SEARCH_DISCRETIZATION = 0.01f;
61 const double EXPECTED_SUCCESS_RATE = 0.8;
62 static const std::string UNDEFINED = "<undefined>";
63 
64 // As loading of parameters is quite slow, we share them across all tests
66 {
67  friend class KinematicsTest;
68  typedef pluginlib::ClassLoader<kinematics::KinematicsBase> KinematicsLoader;
69 
70  moveit::core::RobotModelPtr robot_model_;
71  std::unique_ptr<KinematicsLoader> kinematics_loader_;
72  std::string root_link_;
73  std::string tip_link_;
74  std::string group_name_;
75  std::string ik_plugin_name_;
76  std::vector<std::string> joints_;
77  std::vector<double> seed_;
78  std::vector<double> consistency_limits_;
79  double timeout_;
80  double tolerance_;
81  int num_fk_tests_;
82  int num_ik_cb_tests_;
83  int num_ik_tests_;
87 
88  SharedData(SharedData const&) = delete; // this is a singleton
89  SharedData()
90  {
91  initialize();
92  }
93 
94  void initialize()
95  {
96  rclcpp::NodeOptions node_options;
97  node_options.automatically_declare_parameters_from_overrides(true);
98  node_ = rclcpp::Node::make_shared("moveit_kinematics_test", node_options);
99 
100  RCLCPP_INFO_STREAM(LOGGER, "Loading robot model from " << node_->get_name() << "." << ROBOT_DESCRIPTION_PARAM);
101  // load robot model
103  robot_model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader.getURDF(), rdf_loader.getSRDF());
104  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
105 
106  // init ClassLoader
107  kinematics_loader_ = std::make_unique<KinematicsLoader>("moveit_core", "kinematics::KinematicsBase");
108  ASSERT_TRUE(bool(kinematics_loader_)) << "Failed to instantiate ClassLoader";
109 
110  // load parameters
111  ASSERT_TRUE(node_->get_parameter("group", group_name_));
112  ASSERT_TRUE(node_->get_parameter("tip_link", tip_link_));
113  ASSERT_TRUE(node_->get_parameter("root_link", root_link_));
114  ASSERT_TRUE(node_->get_parameter("joint_names", joints_));
115  node_->get_parameter_or("seed", seed_, { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
116  ASSERT_TRUE(seed_.empty() || seed_.size() == joints_.size()) << "If set, 'seed' size must match 'joint_names' size";
117  node_->get_parameter_or("consistency_limits", consistency_limits_, consistency_limits_);
118  ASSERT_TRUE(consistency_limits_.empty() || consistency_limits_.size() == joints_.size())
119  << "If set, 'consistency_limits' size must match 'joint_names' size";
120  ASSERT_TRUE(node_->get_parameter("ik_timeout", timeout_));
121  ASSERT_TRUE(timeout_ > 0.0) << "'ik_timeout' must be more than 0.0 seconds";
122  ASSERT_TRUE(node_->get_parameter("tolerance", tolerance_));
123  ASSERT_TRUE(tolerance_ > 0.0) << "'tolerance' must be greater than 0.0";
124  ASSERT_TRUE(node_->get_parameter("num_fk_tests", num_fk_tests_));
125  ASSERT_TRUE(node_->get_parameter("num_ik_cb_tests", num_ik_cb_tests_));
126  ASSERT_TRUE(node_->get_parameter("num_ik_tests", num_ik_tests_));
127  ASSERT_TRUE(node_->get_parameter("num_ik_multiple_tests", num_ik_multiple_tests_));
128  ASSERT_TRUE(node_->get_parameter("num_nearest_ik_tests", num_nearest_ik_tests_));
129  ASSERT_TRUE(node_->get_parameter("ik_plugin_name", ik_plugin_name_));
130  node_->get_parameter_or("publish_trajectory", publish_trajectory_, false);
131 
132  ASSERT_TRUE(robot_model_->hasJointModelGroup(group_name_));
133  ASSERT_TRUE(robot_model_->hasLinkModel(root_link_));
134  ASSERT_TRUE(robot_model_->hasLinkModel(tip_link_));
135  }
136 
137 public:
138  std::shared_ptr<rclcpp::Node> node_;
139 
140  auto createUniqueInstance(const std::string& name) const
141  {
142  return kinematics_loader_->createUniqueInstance(name);
143  }
144 
145  static const SharedData& instance()
146  {
147  static SharedData instance;
148  return instance;
149  }
150  static void release()
151  {
152  SharedData& shared = const_cast<SharedData&>(instance());
153  shared.kinematics_loader_.reset();
154  }
155 };
156 
157 class KinematicsTest : public ::testing::Test
158 {
159 protected:
160  void operator=(const SharedData& data)
161  {
162  node_ = data.node_;
163  robot_model_ = data.robot_model_;
164  jmg_ = robot_model_->getJointModelGroup(data.group_name_);
165  root_link_ = data.root_link_;
166  tip_link_ = data.tip_link_;
167  group_name_ = data.group_name_;
168  ik_plugin_name_ = data.ik_plugin_name_;
169  joints_ = data.joints_;
170  seed_ = data.seed_;
171  consistency_limits_ = data.consistency_limits_;
172  timeout_ = data.timeout_;
173  tolerance_ = data.tolerance_;
174  num_fk_tests_ = data.num_fk_tests_;
175  num_ik_cb_tests_ = data.num_ik_cb_tests_;
176  num_ik_tests_ = data.num_ik_tests_;
177  num_ik_multiple_tests_ = data.num_ik_multiple_tests_;
178  num_nearest_ik_tests_ = data.num_nearest_ik_tests_;
179  publish_trajectory_ = data.publish_trajectory_;
180  }
181 
182  void SetUp() override
183  {
184  *this = SharedData::instance();
185 
186  RCLCPP_INFO_STREAM(LOGGER, "Loading " << ik_plugin_name_);
188  ASSERT_TRUE(bool(kinematics_solver_)) << "Failed to load plugin: " << ik_plugin_name_;
189 
190  // initializing plugin
191  ASSERT_TRUE(kinematics_solver_->initialize(node_, *robot_model_, group_name_, root_link_, { tip_link_ },
193  << "Solver failed to initialize";
194  jmg_ = robot_model_->getJointModelGroup(kinematics_solver_->getGroupName());
195  ASSERT_TRUE(jmg_);
196  // Validate chain information
197  ASSERT_EQ(root_link_, kinematics_solver_->getBaseFrame());
198  ASSERT_FALSE(kinematics_solver_->getTipFrames().empty());
199  ASSERT_EQ(tip_link_, kinematics_solver_->getTipFrame());
200 
201  ASSERT_EQ(joints_, kinematics_solver_->getJointNames());
202  }
203 
204 public:
205  testing::AssertionResult isNear(const char* expr1, const char* expr2, const char* /*abs_error_expr*/,
206  const geometry_msgs::msg::Point& val1, const geometry_msgs::msg::Point& val2,
207  double abs_error)
208  {
209  // clang-format off
210  if (std::fabs(val1.x - val2.x) <= abs_error &&
211  std::fabs(val1.y - val2.y) <= abs_error &&
212  std::fabs(val1.z - val2.z) <= abs_error)
213  return testing::AssertionSuccess();
214 
215  return testing::AssertionFailure()
216  << std::setprecision(std::numeric_limits<double>::digits10 + 2)
217  << "Expected: " << expr1 << " [" << val1.x << ", " << val1.y << ", " << val1.z << "]\n"
218  << "Actual: " << expr2 << " [" << val2.x << ", " << val2.y << ", " << val2.z << "]";
219  // clang-format on
220  }
221  testing::AssertionResult isNear(const char* expr1, const char* expr2, const char* /*abs_error_expr*/,
222  const geometry_msgs::msg::Quaternion& val1,
223  const geometry_msgs::msg::Quaternion& val2, double abs_error)
224  {
225  if ((std::fabs(val1.x - val2.x) <= abs_error && std::fabs(val1.y - val2.y) <= abs_error &&
226  std::fabs(val1.z - val2.z) <= abs_error && std::fabs(val1.w - val2.w) <= abs_error) ||
227  (std::fabs(val1.x + val2.x) <= abs_error && std::fabs(val1.y + val2.y) <= abs_error &&
228  std::fabs(val1.z + val2.z) <= abs_error && std::fabs(val1.w + val2.w) <= abs_error))
229  return testing::AssertionSuccess();
230 
231  // clang-format off
232  return testing::AssertionFailure()
233  << std::setprecision(std::numeric_limits<double>::digits10 + 2)
234  << "Expected: " << expr1 << " [" << val1.w << ", " << val1.x << ", " << val1.y << ", " << val1.z << "]\n"
235  << "Actual: " << expr2 << " [" << val2.w << ", " << val2.x << ", " << val2.y << ", " << val2.z << "]";
236  // clang-format on
237  }
238  testing::AssertionResult expectNearHelper(const char* expr1, const char* expr2, const char* abs_error_expr,
239  const std::vector<geometry_msgs::msg::Pose>& val1,
240  const std::vector<geometry_msgs::msg::Pose>& val2, double abs_error)
241  {
242  if (val1.size() != val2.size())
243  return testing::AssertionFailure() << "Different vector sizes"
244  << "\nExpected: " << expr1 << " (" << val1.size() << ")"
245  << "\nActual: " << expr2 << " (" << val2.size() << ")";
246 
247  for (size_t i = 0; i < val1.size(); ++i)
248  {
249  ::std::stringstream ss;
250  ss << "[" << i << "].position";
251  GTEST_ASSERT_(isNear((expr1 + ss.str()).c_str(), (expr2 + ss.str()).c_str(), abs_error_expr, val1[i].position,
252  val2[i].position, abs_error),
253  GTEST_NONFATAL_FAILURE_);
254 
255  ss.str("");
256  ss << "[" << i << "].orientation";
257  GTEST_ASSERT_(isNear((expr1 + ss.str()).c_str(), (expr2 + ss.str()).c_str(), abs_error_expr, val1[i].orientation,
258  val2[i].orientation, abs_error),
259  GTEST_NONFATAL_FAILURE_);
260  }
261  return testing::AssertionSuccess();
262  }
263 
264  void searchIKCallback(const std::vector<double>& joint_state, moveit_msgs::msg::MoveItErrorCodes& error_code)
265  {
266  std::vector<std::string> link_names = { tip_link_ };
267  std::vector<geometry_msgs::msg::Pose> poses;
268  if (!kinematics_solver_->getPositionFK(link_names, joint_state, poses))
269  {
270  error_code.val = error_code.PLANNING_FAILED;
271  return;
272  }
273 
274  EXPECT_GT(poses[0].position.z, 0.0f);
275  if (poses[0].position.z > 0.0)
276  error_code.val = error_code.SUCCESS;
277  else
278  error_code.val = error_code.PLANNING_FAILED;
279  }
280 
281 public:
282  rclcpp::Node::SharedPtr node_;
283  moveit::core::RobotModelPtr robot_model_;
285  kinematics::KinematicsBasePtr kinematics_solver_;
286  random_numbers::RandomNumberGenerator rng_{ 42 };
287  std::string root_link_;
288  std::string tip_link_;
289  std::string group_name_;
290  std::string ik_plugin_name_;
291  std::vector<std::string> joints_;
292  std::vector<double> seed_;
293  std::vector<double> consistency_limits_;
294  double timeout_;
295  double tolerance_;
296  unsigned int num_fk_tests_;
297  unsigned int num_ik_cb_tests_;
298  unsigned int num_ik_tests_;
300  unsigned int num_nearest_ik_tests_;
302 };
303 
304 #define EXPECT_NEAR_POSES(lhs, rhs, near) \
305  SCOPED_TRACE("EXPECT_NEAR_POSES(" #lhs ", " #rhs ")"); \
306  GTEST_ASSERT_(expectNearHelper(#lhs, #rhs, #near, lhs, rhs, near), GTEST_NONFATAL_FAILURE_);
307 
309 {
310  std::vector<double> joints(kinematics_solver_->getJointNames().size(), 0.0);
311  const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
312  moveit::core::RobotState robot_state(robot_model_);
313  robot_state.setToDefaultValues();
314 
315  for (unsigned int i = 0; i < num_fk_tests_; ++i)
316  {
317  robot_state.setToRandomPositions(jmg_, this->rng_);
318  robot_state.copyJointGroupPositions(jmg_, joints);
319  std::vector<geometry_msgs::msg::Pose> fk_poses;
320  EXPECT_TRUE(kinematics_solver_->getPositionFK(tip_frames, joints, fk_poses));
321 
322  robot_state.updateLinkTransforms();
323  std::vector<geometry_msgs::msg::Pose> model_poses;
324  model_poses.reserve(tip_frames.size());
325  for (const auto& tip : tip_frames)
326  model_poses.emplace_back(tf2::toMsg(robot_state.getGlobalLinkTransform(tip)));
327  EXPECT_NEAR_POSES(model_poses, fk_poses, tolerance_);
328  }
329 }
330 
331 // perform random walk in joint-space, reaching poses via IK
332 TEST_F(KinematicsTest, randomWalkIK)
333 {
334  std::vector<double> seed, goal, solution;
335  const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
336  moveit::core::RobotState robot_state(robot_model_);
337  robot_state.setToDefaultValues();
338 
339  if (!seed_.empty())
340  robot_state.setJointGroupPositions(jmg_, seed_);
341 
342  moveit_msgs::msg::DisplayTrajectory msg;
343  msg.model_id = robot_model_->getName();
344  moveit::core::robotStateToRobotStateMsg(robot_state, msg.trajectory_start);
345  msg.trajectory.resize(1);
346  robot_trajectory::RobotTrajectory traj(robot_model_, jmg_);
347 
348  unsigned int failures = 0;
349  static constexpr double NEAR_JOINT = 0.1;
350  const std::vector<double> consistency_limits(jmg_->getVariableCount(), 1.05 * NEAR_JOINT);
351  for (unsigned int i = 0; i < num_ik_tests_; ++i)
352  {
353  // remember previous pose
354  robot_state.copyJointGroupPositions(jmg_, seed);
355  // sample a new pose nearby
356  robot_state.setToRandomPositionsNearBy(jmg_, robot_state, NEAR_JOINT);
357  // get joints of new pose
358  robot_state.copyJointGroupPositions(jmg_, goal);
359  // compute target tip_frames
360  std::vector<geometry_msgs::msg::Pose> poses;
361  ASSERT_TRUE(kinematics_solver_->getPositionFK(tip_frames, goal, poses));
362 
363  // compute IK
364  moveit_msgs::msg::MoveItErrorCodes error_code;
365  kinematics_solver_->searchPositionIK(poses[0], seed, 0.1, consistency_limits, solution, error_code);
366  if (error_code.val != error_code.SUCCESS)
367  {
368  ++failures;
369  continue;
370  }
371 
372  // on success: validate reached poses
373  std::vector<geometry_msgs::msg::Pose> reached_poses;
374  kinematics_solver_->getPositionFK(tip_frames, solution, reached_poses);
375  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
376 
377  // validate closeness of solution pose to goal
378  auto diff = Eigen::Map<Eigen::ArrayXd>(solution.data(), solution.size()) -
379  Eigen::Map<Eigen::ArrayXd>(goal.data(), goal.size());
380  if (!diff.isZero(1.05 * NEAR_JOINT))
381  {
382  ++failures;
383  RCLCPP_WARN_STREAM(LOGGER, "jump in [" << i << "]: " << diff.transpose());
384  }
385 
386  // update robot state to found pose
387  robot_state.setJointGroupPositions(jmg_, solution);
388  traj.addSuffixWayPoint(robot_state, 0.1);
389  }
390  EXPECT_LE(failures, (1.0 - EXPECTED_SUCCESS_RATE) * num_ik_tests_);
391  if (publish_trajectory_)
392  {
393  auto pub = node_->create_publisher<moveit_msgs::msg::DisplayTrajectory>("display_random_walk", 1);
394  traj.getRobotTrajectoryMsg(msg.trajectory[0]);
395  pub->publish(msg);
396  rclcpp::spin_some(node_);
397  }
398 }
399 
400 static bool parsePose(const std::vector<double>& pose_values, Eigen::Isometry3d& goal)
401 {
402  std::vector<double> vec;
403  Eigen::Quaterniond q;
404  if (pose_values.size() == 6)
405  {
406  q = Eigen::AngleAxisd(pose_values[3], Eigen::Vector3d::UnitX()) *
407  Eigen::AngleAxisd(pose_values[4], Eigen::Vector3d::UnitY()) *
408  Eigen::AngleAxisd(pose_values[5], Eigen::Vector3d::UnitZ());
409  }
410  else if (pose_values.size() == 7)
411  {
412  q = Eigen::Quaterniond(pose_values[3], pose_values[4], pose_values[5], pose_values[6]);
413  }
414  else
415  {
416  return false;
417  }
418 
419  goal = q;
420  goal.translation() = Eigen::Vector3d(pose_values[0], pose_values[1], pose_values[2]);
421 
422  return true;
423 }
424 
426 {
427  static const std::string TEST_POSES_PARAM = "unit_test_poses";
428  size_t expected_test_poses = 0;
429  node_->get_parameter_or(TEST_POSES_PARAM + ".size", expected_test_poses, expected_test_poses);
430 
431  std::vector<double> sol;
432  const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
433  moveit::core::RobotState robot_state(robot_model_);
434  robot_state.setToDefaultValues();
435  robot_state.setJointGroupPositions(jmg_, seed_);
436 
437  // compute initial end-effector pose
438  std::vector<geometry_msgs::msg::Pose> poses;
439  ASSERT_TRUE(kinematics_solver_->getPositionFK(tip_frames, seed_, poses));
440  Eigen::Isometry3d initial, goal;
441  tf2::fromMsg(poses[0], initial);
442 
443  RCLCPP_DEBUG(LOGGER, "Initial: %f %f %f %f %f %f %f\n", poses[0].position.x, poses[0].position.y, poses[0].position.z,
444  poses[0].orientation.x, poses[0].orientation.y, poses[0].orientation.z, poses[0].orientation.w);
445 
446  auto validate_ik = [&](const geometry_msgs::msg::Pose& goal, std::vector<double>& truth) {
447  // compute IK
448  moveit_msgs::msg::MoveItErrorCodes error_code;
449 
450  RCLCPP_DEBUG(LOGGER, "Goal %f %f %f %f %f %f %f\n", goal.position.x, goal.position.y, goal.position.z,
451  goal.orientation.x, goal.orientation.y, goal.orientation.z, goal.orientation.w);
452 
453  kinematics_solver_->searchPositionIK(goal, seed_, timeout_,
454  const_cast<const std::vector<double>&>(consistency_limits_), sol, error_code);
455  ASSERT_EQ(error_code.val, error_code.SUCCESS);
456 
457  // validate reached poses
458  std::vector<geometry_msgs::msg::Pose> reached_poses;
459  kinematics_solver_->getPositionFK(tip_frames, sol, reached_poses);
460  EXPECT_NEAR_POSES({ goal }, reached_poses, tolerance_);
461 
462  // validate ground truth
463  if (!truth.empty())
464  {
465  ASSERT_EQ(truth.size(), sol.size()) << "Invalid size of ground truth joints vector";
466  Eigen::Map<Eigen::ArrayXd> solution(sol.data(), sol.size());
467  Eigen::Map<Eigen::ArrayXd> ground_truth(truth.data(), truth.size());
468  EXPECT_TRUE(solution.isApprox(ground_truth, 10 * tolerance_)) << solution.transpose() << '\n'
469  << ground_truth.transpose() << '\n';
470  }
471  };
472 
473  std::vector<double> ground_truth, pose_values;
474  constexpr char pose_type_relative[] = "relative";
475  constexpr char pose_type_absolute[] = "absolute";
476 
477  // process tests definitions on parameter server of the form
478  // pose_1:
479  // pose: [0.3, 0.2, 0.1, 0, 0, 0] // xyzrpy (position + euler angles)
480  // joints: [0, 0, 0, 0, 0, 0] // ground truth solution
481  // type: relative // pose applied relative to current pose
482  // pose_2:
483  // pose: [0.1, 0.2, 0.3, 0, 0, 0, 0] // xyzwxyz (position + quaternion)
484  // joints: [1, 2, 3, 4, 5, 6] // pose applied absolute in planning frame
485  // type: absolute
486 
487  for (size_t i = 0; i < expected_test_poses; ++i) // NOLINT(modernize-loop-convert)
488  {
489  const std::string pose_name = "pose_" + std::to_string(i);
490  const std::string pose_param = TEST_POSES_PARAM + "." + pose_name; // NOLINT
491  goal = initial; // reset goal to initial
492  ground_truth.clear();
493 
494  node_->get_parameter_or(pose_param + ".joints", ground_truth, ground_truth);
495  if (!ground_truth.empty())
496  {
497  ASSERT_EQ(ground_truth.size(), joints_.size())
498  << "Test pose '" << pose_name << "' has invalid 'joints' vector size";
499  }
500 
501  pose_values.clear();
502  node_->get_parameter_or(pose_param + ".pose", pose_values, pose_values);
503  ASSERT_TRUE(pose_values.size() == 6 || pose_values.size() == 7)
504  << "Test pose '" << pose_name << "' has invalid 'pose' vector size";
505 
506  Eigen::Isometry3d pose;
507  ASSERT_TRUE(parsePose(pose_values, pose)) << "Failed to parse 'pose' vector in: " << pose_name;
508  std::string pose_type = "pose_type_relative";
509  node_->get_parameter_or(pose_param + ".type", pose_type, pose_type);
510  if (pose_type == pose_type_relative)
511  goal = goal * pose;
512  else if (pose_type == pose_type_absolute)
513  goal = pose;
514  else
515  FAIL() << "Found invalid 'type' in " << pose_name << ": should be one of '" << pose_type_relative << "' or '"
516  << pose_type_absolute << "'";
517 
518  std::string desc;
519  {
520  SCOPED_TRACE(desc);
521  validate_ik(tf2::toMsg(goal), ground_truth);
522  }
523  }
524 }
525 
527 {
528  std::vector<double> seed, fk_values, solution;
529  moveit_msgs::msg::MoveItErrorCodes error_code;
530  solution.resize(kinematics_solver_->getJointNames().size(), 0.0);
531  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
532  moveit::core::RobotState robot_state(robot_model_);
533  robot_state.setToDefaultValues();
534 
535  unsigned int success = 0;
536  for (unsigned int i = 0; i < num_ik_tests_; ++i)
537  {
538  seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
539  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
540  robot_state.setToRandomPositions(jmg_, this->rng_);
541  robot_state.copyJointGroupPositions(jmg_, fk_values);
542  std::vector<geometry_msgs::msg::Pose> poses;
543  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
544 
545  kinematics_solver_->searchPositionIK(poses[0], seed, timeout_, solution, error_code);
546  if (error_code.val == error_code.SUCCESS)
547  success++;
548  else
549  continue;
550 
551  std::vector<geometry_msgs::msg::Pose> reached_poses;
552  kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
553  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
554  }
555 
556  if (num_ik_cb_tests_ > 0)
557  {
558  RCLCPP_INFO_STREAM(LOGGER, "Success Rate: " << (double)success / num_ik_tests_);
559  }
560  EXPECT_GE(success, EXPECTED_SUCCESS_RATE * num_ik_tests_);
561 }
562 
563 TEST_F(KinematicsTest, searchIKWithCallback)
564 {
565  std::vector<double> seed, fk_values, solution;
566  moveit_msgs::msg::MoveItErrorCodes error_code;
567  solution.resize(kinematics_solver_->getJointNames().size(), 0.0);
568  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
569  moveit::core::RobotState robot_state(robot_model_);
570  robot_state.setToDefaultValues();
571 
572  unsigned int success = 0;
573  for (unsigned int i = 0; i < num_ik_cb_tests_; ++i)
574  {
575  seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
576  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
577  robot_state.setToRandomPositions(jmg_, this->rng_);
578  robot_state.copyJointGroupPositions(jmg_, fk_values);
579  std::vector<geometry_msgs::msg::Pose> poses;
580  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
581  if (poses[0].position.z <= 0.0f)
582  {
583  --i; // draw a new random state
584  continue;
585  }
586 
587  kinematics_solver_->searchPositionIK(
588  poses[0], fk_values, timeout_, solution,
589  [this](const geometry_msgs::msg::Pose&, const std::vector<double>& joints,
590  moveit_msgs::msg::MoveItErrorCodes& error_code) { searchIKCallback(joints, error_code); },
591  error_code);
592  if (error_code.val == error_code.SUCCESS)
593  success++;
594  else
595  continue;
596 
597  std::vector<geometry_msgs::msg::Pose> reached_poses;
598  kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
599  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
600  }
601 
602  if (num_ik_cb_tests_ > 0)
603  {
604  RCLCPP_INFO_STREAM(LOGGER, "Success Rate: " << (double)success / num_ik_cb_tests_);
605  }
606  EXPECT_GE(success, EXPECTED_SUCCESS_RATE * num_ik_cb_tests_);
607 }
608 
610 {
611  std::vector<double> fk_values, solution;
612  moveit_msgs::msg::MoveItErrorCodes error_code;
613  solution.resize(kinematics_solver_->getJointNames().size(), 0.0);
614  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
615  moveit::core::RobotState robot_state(robot_model_);
616  robot_state.setToDefaultValues();
617 
618  for (unsigned int i = 0; i < num_ik_tests_; ++i)
619  {
620  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
621  robot_state.setToRandomPositions(jmg_, this->rng_);
622  robot_state.copyJointGroupPositions(jmg_, fk_values);
623  std::vector<geometry_msgs::msg::Pose> poses;
624 
625  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
626  kinematics_solver_->getPositionIK(poses[0], fk_values, solution, error_code);
627  // starting from the correct solution, should yield the same pose
628  EXPECT_EQ(error_code.val, error_code.SUCCESS);
629 
630  Eigen::Map<Eigen::ArrayXd> sol(solution.data(), solution.size());
631  Eigen::Map<Eigen::ArrayXd> truth(fk_values.data(), fk_values.size());
632  EXPECT_TRUE(sol.isApprox(truth, tolerance_)) << sol.transpose() << '\n' << truth.transpose() << '\n';
633  }
634 }
635 
636 TEST_F(KinematicsTest, getIKMultipleSolutions)
637 {
638  std::vector<double> seed, fk_values;
639  std::vector<std::vector<double>> solutions;
642 
643  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
644  moveit::core::RobotState robot_state(robot_model_);
645  robot_state.setToDefaultValues();
646 
647  unsigned int success = 0;
648  for (unsigned int i = 0; i < num_ik_multiple_tests_; ++i)
649  {
650  seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
651  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
652  robot_state.setToRandomPositions(jmg_, this->rng_);
653  robot_state.copyJointGroupPositions(jmg_, fk_values);
654  std::vector<geometry_msgs::msg::Pose> poses;
655  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
656 
657  solutions.clear();
658  kinematics_solver_->getPositionIK(poses, fk_values, solutions, result, options);
659 
661  success += solutions.empty() ? 0 : 1;
662  else
663  continue;
664 
665  std::vector<geometry_msgs::msg::Pose> reached_poses;
666  for (const auto& s : solutions)
667  {
668  kinematics_solver_->getPositionFK(fk_names, s, reached_poses);
669  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
670  }
671  }
672 
673  if (num_ik_cb_tests_ > 0)
674  {
675  RCLCPP_INFO_STREAM(LOGGER, "Success Rate: " << (double)success / num_ik_multiple_tests_);
676  }
677  EXPECT_GE(success, EXPECTED_SUCCESS_RATE * num_ik_multiple_tests_);
678 }
679 
680 // validate that getPositionIK() retrieves closest solution to seed
681 TEST_F(KinematicsTest, getNearestIKSolution)
682 {
683  std::vector<std::vector<double>> solutions;
686 
687  std::vector<double> seed, fk_values, solution;
688  moveit_msgs::msg::MoveItErrorCodes error_code;
689  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
690  moveit::core::RobotState robot_state(robot_model_);
691  robot_state.setToDefaultValues();
692 
693  for (unsigned int i = 0; i < num_nearest_ik_tests_; ++i)
694  {
695  robot_state.setToRandomPositions(jmg_, this->rng_);
696  robot_state.copyJointGroupPositions(jmg_, fk_values);
697  std::vector<geometry_msgs::msg::Pose> poses;
698  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
699 
700  // sample seed vector
701  robot_state.setToRandomPositions(jmg_, this->rng_);
702  robot_state.copyJointGroupPositions(jmg_, seed);
703 
704  // getPositionIK for single solution
705  kinematics_solver_->getPositionIK(poses[0], seed, solution, error_code);
706 
707  // check if getPositionIK call for single solution returns solution
708  if (error_code.val != error_code.SUCCESS)
709  continue;
710 
711  const Eigen::Map<const Eigen::VectorXd> seed_eigen(seed.data(), seed.size());
712  double error_get_ik =
713  (Eigen::Map<const Eigen::VectorXd>(solution.data(), solution.size()) - seed_eigen).array().abs().sum();
714 
715  // getPositionIK for multiple solutions
716  solutions.clear();
717  kinematics_solver_->getPositionIK(poses, seed, solutions, result, options);
718 
719  // check if getPositionIK call for multiple solutions returns solution
721  << "Multiple solution call failed, while single solution call succeeded";
723  continue;
724 
725  double smallest_error_multiple_ik = std::numeric_limits<double>::max();
726  for (const auto& s : solutions)
727  {
728  double error_multiple_ik =
729  (Eigen::Map<const Eigen::VectorXd>(s.data(), s.size()) - seed_eigen).array().abs().sum();
730  if (error_multiple_ik <= smallest_error_multiple_ik)
731  smallest_error_multiple_ik = error_multiple_ik;
732  }
733  EXPECT_NEAR(smallest_error_multiple_ik, error_get_ik, tolerance_);
734  }
735 }
736 
737 int main(int argc, char** argv)
738 {
739  testing::InitGoogleTest(&argc, argv);
740  rclcpp::init(argc, argv);
741  int result = RUN_ALL_TESTS();
742  SharedData::release(); // avoid class_loader::LibraryUnloadException
743  return result;
744 }
testing::AssertionResult isNear(const char *expr1, const char *expr2, const char *, const geometry_msgs::msg::Point &val1, const geometry_msgs::msg::Point &val2, double abs_error)
std::vector< double > consistency_limits_
void searchIKCallback(const std::vector< double > &joint_state, moveit_msgs::msg::MoveItErrorCodes &error_code)
moveit::core::RobotModelPtr robot_model_
random_numbers::RandomNumberGenerator rng_
unsigned int num_ik_multiple_tests_
std::vector< double > seed_
kinematics::KinematicsBasePtr kinematics_solver_
void operator=(const SharedData &data)
moveit::core::JointModelGroup * jmg_
unsigned int num_nearest_ik_tests_
testing::AssertionResult expectNearHelper(const char *expr1, const char *expr2, const char *abs_error_expr, const std::vector< geometry_msgs::msg::Pose > &val1, const std::vector< geometry_msgs::msg::Pose > &val2, double abs_error)
std::vector< std::string > joints_
rclcpp::Node::SharedPtr node_
testing::AssertionResult isNear(const char *expr1, const char *expr2, const char *, const geometry_msgs::msg::Quaternion &val1, const geometry_msgs::msg::Quaternion &val2, double abs_error)
static const SharedData & instance()
auto createUniqueInstance(const std::string &name) const
static void release()
std::shared_ptr< rclcpp::Node > node_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.h:90
const Eigen::Isometry3d & getGlobalLinkTransform(const std::string &link_name)
Get the link transform w.r.t. the root link (model frame) of the RobotModel. This is typically the ro...
Definition: robot_state.h:1339
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:605
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
Definition: robot_state.h:691
void setToRandomPositionsNearBy(const JointModelGroup *group, const RobotState &seed, double distance)
Set all joints in group to random values near the value in seed. distance is the maximum amount each ...
void updateLinkTransforms()
Update the reference frame transforms for links. This call is needed before using the transforms of l...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
Maintain a sequence of waypoints and the time durations between these waypoints.
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.h:89
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.
name
Definition: setup.py:7
A set of options for the kinematics solver.
int main(int argc, char **argv)
const double EXPECTED_SUCCESS_RATE
const double DEFAULT_SEARCH_DISCRETIZATION
#define EXPECT_NEAR_POSES(lhs, rhs, near)
const std::string ROBOT_DESCRIPTION_PARAM
TEST_F(KinematicsTest, getFK)