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 #include <moveit/utils/logger.hpp>
58 
59 rclcpp::Logger getLogger()
60 {
61  return moveit::getLogger("moveit.kinematics.test_kinematics_plugin");
62 }
63 const std::string ROBOT_DESCRIPTION_PARAM = "robot_description";
64 const double DEFAULT_SEARCH_DISCRETIZATION = 0.01f;
65 const double EXPECTED_SUCCESS_RATE = 0.8;
66 static const std::string UNDEFINED = "<undefined>";
67 
68 // As loading of parameters is quite slow, we share them across all tests
70 {
71  friend class KinematicsTest;
72  typedef pluginlib::ClassLoader<kinematics::KinematicsBase> KinematicsLoader;
73 
74  moveit::core::RobotModelPtr robot_model_;
75  std::unique_ptr<KinematicsLoader> kinematics_loader_;
76  std::string root_link_;
77  std::string tip_link_;
78  std::string group_name_;
79  std::string ik_plugin_name_;
80  std::vector<std::string> joints_;
81  std::vector<double> seed_;
82  std::vector<double> consistency_limits_;
83  double timeout_;
84  double tolerance_;
85  int num_fk_tests_;
86  int num_ik_cb_tests_;
87  int num_ik_tests_;
91 
92  SharedData(const SharedData&) = delete; // this is a singleton
93  SharedData()
94  {
95  initialize();
96  }
97 
98  void initialize()
99  {
100  rclcpp::NodeOptions node_options;
101  node_options.automatically_declare_parameters_from_overrides(true);
102  node_ = rclcpp::Node::make_shared("moveit_kinematics_test", node_options);
103 
104  RCLCPP_INFO_STREAM(getLogger(), "Loading robot model from " << node_->get_name() << '.' << ROBOT_DESCRIPTION_PARAM);
105  // load robot model
107  robot_model_ = std::make_shared<moveit::core::RobotModel>(rdf_loader.getURDF(), rdf_loader.getSRDF());
108  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
109 
110  // init ClassLoader
111  kinematics_loader_ = std::make_unique<KinematicsLoader>("moveit_core", "kinematics::KinematicsBase");
112  ASSERT_TRUE(bool(kinematics_loader_)) << "Failed to instantiate ClassLoader";
113 
114  // load parameters
115  ASSERT_TRUE(node_->get_parameter("group", group_name_));
116  ASSERT_TRUE(node_->get_parameter("tip_link", tip_link_));
117  ASSERT_TRUE(node_->get_parameter("root_link", root_link_));
118  ASSERT_TRUE(node_->get_parameter("joint_names", joints_));
119  node_->get_parameter_or("seed", seed_, { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 });
120  ASSERT_TRUE(seed_.empty() || seed_.size() == joints_.size()) << "If set, 'seed' size must match 'joint_names' size";
121  node_->get_parameter_or("consistency_limits", consistency_limits_, consistency_limits_);
122  ASSERT_TRUE(consistency_limits_.empty() || consistency_limits_.size() == joints_.size())
123  << "If set, 'consistency_limits' size must match 'joint_names' size";
124  ASSERT_TRUE(node_->get_parameter("ik_timeout", timeout_));
125  ASSERT_TRUE(timeout_ > 0.0) << "'ik_timeout' must be more than 0.0 seconds";
126  ASSERT_TRUE(node_->get_parameter("tolerance", tolerance_));
127  ASSERT_TRUE(tolerance_ > 0.0) << "'tolerance' must be greater than 0.0";
128  ASSERT_TRUE(node_->get_parameter("num_fk_tests", num_fk_tests_));
129  ASSERT_TRUE(node_->get_parameter("num_ik_cb_tests", num_ik_cb_tests_));
130  ASSERT_TRUE(node_->get_parameter("num_ik_tests", num_ik_tests_));
131  ASSERT_TRUE(node_->get_parameter("num_ik_multiple_tests", num_ik_multiple_tests_));
132  ASSERT_TRUE(node_->get_parameter("num_nearest_ik_tests", num_nearest_ik_tests_));
133  ASSERT_TRUE(node_->get_parameter("ik_plugin_name", ik_plugin_name_));
134  node_->get_parameter_or("publish_trajectory", publish_trajectory_, false);
135 
136  ASSERT_TRUE(robot_model_->hasJointModelGroup(group_name_));
137  ASSERT_TRUE(robot_model_->hasLinkModel(root_link_));
138  ASSERT_TRUE(robot_model_->hasLinkModel(tip_link_));
139  }
140 
141 public:
142  std::shared_ptr<rclcpp::Node> node_;
143 
144  auto createUniqueInstance(const std::string& name) const
145  {
146  return kinematics_loader_->createUniqueInstance(name);
147  }
148 
149  static const SharedData& instance()
150  {
151  static SharedData instance;
152  return instance;
153  }
154  static void release()
155  {
156  SharedData& shared = const_cast<SharedData&>(instance());
157  shared.kinematics_loader_.reset();
158  }
159 };
160 
161 class KinematicsTest : public ::testing::Test
162 {
163 protected:
164  void operator=(const SharedData& data)
165  {
166  node_ = data.node_;
167  robot_model_ = data.robot_model_;
168  jmg_ = robot_model_->getJointModelGroup(data.group_name_);
169  root_link_ = data.root_link_;
170  tip_link_ = data.tip_link_;
171  group_name_ = data.group_name_;
172  ik_plugin_name_ = data.ik_plugin_name_;
173  joints_ = data.joints_;
174  seed_ = data.seed_;
175  consistency_limits_ = data.consistency_limits_;
176  timeout_ = data.timeout_;
177  tolerance_ = data.tolerance_;
178  num_fk_tests_ = data.num_fk_tests_;
179  num_ik_cb_tests_ = data.num_ik_cb_tests_;
180  num_ik_tests_ = data.num_ik_tests_;
181  num_ik_multiple_tests_ = data.num_ik_multiple_tests_;
182  num_nearest_ik_tests_ = data.num_nearest_ik_tests_;
183  publish_trajectory_ = data.publish_trajectory_;
184  }
185 
186  void SetUp() override
187  {
188  *this = SharedData::instance();
189 
190  RCLCPP_INFO_STREAM(getLogger(), "Loading " << ik_plugin_name_);
192  ASSERT_TRUE(bool(kinematics_solver_)) << "Failed to load plugin: " << ik_plugin_name_;
193 
194  // initializing plugin
195  ASSERT_TRUE(kinematics_solver_->initialize(node_, *robot_model_, group_name_, root_link_, { tip_link_ },
197  << "Solver failed to initialize";
198  jmg_ = robot_model_->getJointModelGroup(kinematics_solver_->getGroupName());
199  ASSERT_TRUE(jmg_);
200  // Validate chain information
201  ASSERT_EQ(root_link_, kinematics_solver_->getBaseFrame());
202  ASSERT_FALSE(kinematics_solver_->getTipFrames().empty());
203  ASSERT_EQ(tip_link_, kinematics_solver_->getTipFrame());
204 
205  ASSERT_EQ(joints_, kinematics_solver_->getJointNames());
206  }
207 
208 public:
209  testing::AssertionResult isNear(const char* expr1, const char* expr2, const char* /*abs_error_expr*/,
210  const geometry_msgs::msg::Point& val1, const geometry_msgs::msg::Point& val2,
211  double abs_error)
212  {
213  // clang-format off
214  if (std::fabs(val1.x - val2.x) <= abs_error &&
215  std::fabs(val1.y - val2.y) <= abs_error &&
216  std::fabs(val1.z - val2.z) <= abs_error)
217  return testing::AssertionSuccess();
218 
219  return testing::AssertionFailure()
220  << std::setprecision(std::numeric_limits<double>::digits10 + 2)
221  << "Expected: " << expr1 << " [" << val1.x << ", " << val1.y << ", " << val1.z << "]\n"
222  << "Actual: " << expr2 << " [" << val2.x << ", " << val2.y << ", " << val2.z << ']';
223  // clang-format on
224  }
225  testing::AssertionResult isNear(const char* expr1, const char* expr2, const char* /*abs_error_expr*/,
226  const geometry_msgs::msg::Quaternion& val1,
227  const geometry_msgs::msg::Quaternion& val2, double abs_error)
228  {
229  if ((std::fabs(val1.x - val2.x) <= abs_error && std::fabs(val1.y - val2.y) <= abs_error &&
230  std::fabs(val1.z - val2.z) <= abs_error && std::fabs(val1.w - val2.w) <= abs_error) ||
231  (std::fabs(val1.x + val2.x) <= abs_error && std::fabs(val1.y + val2.y) <= abs_error &&
232  std::fabs(val1.z + val2.z) <= abs_error && std::fabs(val1.w + val2.w) <= abs_error))
233  return testing::AssertionSuccess();
234 
235  // clang-format off
236  return testing::AssertionFailure()
237  << std::setprecision(std::numeric_limits<double>::digits10 + 2)
238  << "Expected: " << expr1 << " [" << val1.w << ", " << val1.x << ", " << val1.y << ", " << val1.z << "]\n"
239  << "Actual: " << expr2 << " [" << val2.w << ", " << val2.x << ", " << val2.y << ", " << val2.z << ']';
240  // clang-format on
241  }
242  testing::AssertionResult expectNearHelper(const char* expr1, const char* expr2, const char* abs_error_expr,
243  const std::vector<geometry_msgs::msg::Pose>& val1,
244  const std::vector<geometry_msgs::msg::Pose>& val2, double abs_error)
245  {
246  if (val1.size() != val2.size())
247  {
248  return testing::AssertionFailure() << "Different vector sizes"
249  << "\nExpected: " << expr1 << " (" << val1.size() << ')'
250  << "\nActual: " << expr2 << " (" << val2.size() << ')';
251  }
252 
253  for (size_t i = 0; i < val1.size(); ++i)
254  {
255  ::std::stringstream ss;
256  ss << '[' << i << "].position";
257  GTEST_ASSERT_(isNear((expr1 + ss.str()).c_str(), (expr2 + ss.str()).c_str(), abs_error_expr, val1[i].position,
258  val2[i].position, abs_error),
259  GTEST_NONFATAL_FAILURE_);
260 
261  ss.str("");
262  ss << '[' << i << "].orientation";
263  GTEST_ASSERT_(isNear((expr1 + ss.str()).c_str(), (expr2 + ss.str()).c_str(), abs_error_expr, val1[i].orientation,
264  val2[i].orientation, abs_error),
265  GTEST_NONFATAL_FAILURE_);
266  }
267  return testing::AssertionSuccess();
268  }
269 
270  void searchIKCallback(const std::vector<double>& joint_state, moveit_msgs::msg::MoveItErrorCodes& error_code)
271  {
272  std::vector<std::string> link_names = { tip_link_ };
273  std::vector<geometry_msgs::msg::Pose> poses;
274  if (!kinematics_solver_->getPositionFK(link_names, joint_state, poses))
275  {
276  error_code.val = error_code.PLANNING_FAILED;
277  return;
278  }
279 
280  EXPECT_GT(poses[0].position.z, 0.0f);
281  if (poses[0].position.z > 0.0)
282  {
283  error_code.val = error_code.SUCCESS;
284  }
285  else
286  {
287  error_code.val = error_code.PLANNING_FAILED;
288  }
289  }
290 
291 public:
292  rclcpp::Node::SharedPtr node_;
293  moveit::core::RobotModelPtr robot_model_;
295  kinematics::KinematicsBasePtr kinematics_solver_;
296  random_numbers::RandomNumberGenerator rng_{ 42 };
297  std::string root_link_;
298  std::string tip_link_;
299  std::string group_name_;
300  std::string ik_plugin_name_;
301  std::vector<std::string> joints_;
302  std::vector<double> seed_;
303  std::vector<double> consistency_limits_;
304  double timeout_;
305  double tolerance_;
306  unsigned int num_fk_tests_;
307  unsigned int num_ik_cb_tests_;
308  unsigned int num_ik_tests_;
310  unsigned int num_nearest_ik_tests_;
312 };
313 
314 #define EXPECT_NEAR_POSES(lhs, rhs, near) \
315  SCOPED_TRACE("EXPECT_NEAR_POSES(" #lhs ", " #rhs ")"); \
316  GTEST_ASSERT_(expectNearHelper(#lhs, #rhs, #near, lhs, rhs, near), GTEST_NONFATAL_FAILURE_);
317 
319 {
320  std::vector<double> joints(kinematics_solver_->getJointNames().size(), 0.0);
321  const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
322  moveit::core::RobotState robot_state(robot_model_);
323  robot_state.setToDefaultValues();
324 
325  for (unsigned int i = 0; i < num_fk_tests_; ++i)
326  {
327  robot_state.setToRandomPositions(jmg_, this->rng_);
328  robot_state.copyJointGroupPositions(jmg_, joints);
329  std::vector<geometry_msgs::msg::Pose> fk_poses;
330  EXPECT_TRUE(kinematics_solver_->getPositionFK(tip_frames, joints, fk_poses));
331 
332  robot_state.updateLinkTransforms();
333  std::vector<geometry_msgs::msg::Pose> model_poses;
334  model_poses.reserve(tip_frames.size());
335  for (const auto& tip : tip_frames)
336  model_poses.emplace_back(tf2::toMsg(robot_state.getGlobalLinkTransform(tip)));
337  EXPECT_NEAR_POSES(model_poses, fk_poses, tolerance_);
338  }
339 }
340 
341 // perform random walk in joint-space, reaching poses via IK
342 TEST_F(KinematicsTest, randomWalkIK)
343 {
344  std::vector<double> seed, goal, solution;
345  const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
346  moveit::core::RobotState robot_state(robot_model_);
347  robot_state.setToDefaultValues();
348 
349  if (!seed_.empty())
350  robot_state.setJointGroupPositions(jmg_, seed_);
351 
352  moveit_msgs::msg::DisplayTrajectory msg;
353  msg.model_id = robot_model_->getName();
354  moveit::core::robotStateToRobotStateMsg(robot_state, msg.trajectory_start);
355  msg.trajectory.resize(1);
356  robot_trajectory::RobotTrajectory traj(robot_model_, jmg_);
357 
358  unsigned int failures = 0;
359  static constexpr double NEAR_JOINT = 0.1;
360  const std::vector<double> consistency_limits(jmg_->getVariableCount(), 1.05 * NEAR_JOINT);
361  for (unsigned int i = 0; i < num_ik_tests_; ++i)
362  {
363  // remember previous pose
364  robot_state.copyJointGroupPositions(jmg_, seed);
365  // sample a new pose nearby
366  robot_state.setToRandomPositionsNearBy(jmg_, robot_state, NEAR_JOINT);
367  // get joints of new pose
368  robot_state.copyJointGroupPositions(jmg_, goal);
369  // compute target tip_frames
370  std::vector<geometry_msgs::msg::Pose> poses;
371  ASSERT_TRUE(kinematics_solver_->getPositionFK(tip_frames, goal, poses));
372 
373  // compute IK
374  moveit_msgs::msg::MoveItErrorCodes error_code;
375  kinematics_solver_->searchPositionIK(poses[0], seed, 0.1, consistency_limits, solution, error_code);
376  if (error_code.val != error_code.SUCCESS)
377  {
378  ++failures;
379  continue;
380  }
381 
382  // on success: validate reached poses
383  std::vector<geometry_msgs::msg::Pose> reached_poses;
384  kinematics_solver_->getPositionFK(tip_frames, solution, reached_poses);
385  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
386 
387  // validate closeness of solution pose to goal
388  auto diff = Eigen::Map<Eigen::ArrayXd>(solution.data(), solution.size()) -
389  Eigen::Map<Eigen::ArrayXd>(goal.data(), goal.size());
390  if (!diff.isZero(1.05 * NEAR_JOINT))
391  {
392  ++failures;
393  RCLCPP_WARN_STREAM(getLogger(), "jump in [" << i << "]: " << diff.transpose());
394  }
395 
396  // update robot state to found pose
397  robot_state.setJointGroupPositions(jmg_, solution);
398  traj.addSuffixWayPoint(robot_state, 0.1);
399  }
400  EXPECT_LE(failures, (1.0 - EXPECTED_SUCCESS_RATE) * num_ik_tests_);
401  if (publish_trajectory_)
402  {
403  auto pub = node_->create_publisher<moveit_msgs::msg::DisplayTrajectory>("display_random_walk", 1);
404  traj.getRobotTrajectoryMsg(msg.trajectory[0]);
405  pub->publish(msg);
406  rclcpp::spin_some(node_);
407  }
408 }
409 
410 static bool parsePose(const std::vector<double>& pose_values, Eigen::Isometry3d& goal)
411 {
412  std::vector<double> vec;
413  Eigen::Quaterniond q;
414  if (pose_values.size() == 6)
415  {
416  q = Eigen::AngleAxisd(pose_values[3], Eigen::Vector3d::UnitX()) *
417  Eigen::AngleAxisd(pose_values[4], Eigen::Vector3d::UnitY()) *
418  Eigen::AngleAxisd(pose_values[5], Eigen::Vector3d::UnitZ());
419  }
420  else if (pose_values.size() == 7)
421  {
422  q = Eigen::Quaterniond(pose_values[3], pose_values[4], pose_values[5], pose_values[6]);
423  }
424  else
425  {
426  return false;
427  }
428 
429  goal = q;
430  goal.translation() = Eigen::Vector3d(pose_values[0], pose_values[1], pose_values[2]);
431 
432  return true;
433 }
434 
436 {
437  static const std::string TEST_POSES_PARAM = "unit_test_poses";
438  size_t expected_test_poses = 0;
439  node_->get_parameter_or(TEST_POSES_PARAM + ".size", expected_test_poses, expected_test_poses);
440 
441  std::vector<double> sol;
442  const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
443  moveit::core::RobotState robot_state(robot_model_);
444  robot_state.setToDefaultValues();
445  robot_state.setJointGroupPositions(jmg_, seed_);
446 
447  // compute initial end-effector pose
448  std::vector<geometry_msgs::msg::Pose> poses;
449  ASSERT_TRUE(kinematics_solver_->getPositionFK(tip_frames, seed_, poses));
450  Eigen::Isometry3d initial, goal;
451  tf2::fromMsg(poses[0], initial);
452 
453  RCLCPP_DEBUG(getLogger(), "Initial: %f %f %f %f %f %f %f\n", poses[0].position.x, poses[0].position.y,
454  poses[0].position.z, poses[0].orientation.x, poses[0].orientation.y, poses[0].orientation.z,
455  poses[0].orientation.w);
456 
457  auto validate_ik = [&](const geometry_msgs::msg::Pose& goal, std::vector<double>& truth) {
458  // compute IK
459  moveit_msgs::msg::MoveItErrorCodes error_code;
460 
461  RCLCPP_DEBUG(getLogger(), "Goal %f %f %f %f %f %f %f\n", goal.position.x, goal.position.y, goal.position.z,
462  goal.orientation.x, goal.orientation.y, goal.orientation.z, goal.orientation.w);
463 
464  kinematics_solver_->searchPositionIK(goal, seed_, timeout_,
465  const_cast<const std::vector<double>&>(consistency_limits_), sol, error_code);
466  ASSERT_EQ(error_code.val, error_code.SUCCESS);
467 
468  // validate reached poses
469  std::vector<geometry_msgs::msg::Pose> reached_poses;
470  kinematics_solver_->getPositionFK(tip_frames, sol, reached_poses);
471  EXPECT_NEAR_POSES({ goal }, reached_poses, tolerance_);
472 
473  // validate ground truth
474  if (!truth.empty())
475  {
476  ASSERT_EQ(truth.size(), sol.size()) << "Invalid size of ground truth joints vector";
477  Eigen::Map<Eigen::ArrayXd> solution(sol.data(), sol.size());
478  Eigen::Map<Eigen::ArrayXd> ground_truth(truth.data(), truth.size());
479  EXPECT_TRUE(solution.isApprox(ground_truth, 10 * tolerance_)) << solution.transpose() << '\n'
480  << ground_truth.transpose() << '\n';
481  }
482  };
483 
484  std::vector<double> ground_truth, pose_values;
485  constexpr char pose_type_relative[] = "relative";
486  constexpr char pose_type_absolute[] = "absolute";
487 
488  // process tests definitions on parameter server of the form
489  // pose_1:
490  // pose: [0.3, 0.2, 0.1, 0, 0, 0] // xyzrpy (position + euler angles)
491  // joints: [0, 0, 0, 0, 0, 0] // ground truth solution
492  // type: relative // pose applied relative to current pose
493  // pose_2:
494  // pose: [0.1, 0.2, 0.3, 0, 0, 0, 0] // xyzwxyz (position + quaternion)
495  // joints: [1, 2, 3, 4, 5, 6] // pose applied absolute in planning frame
496  // type: absolute
497 
498  for (size_t i = 0; i < expected_test_poses; ++i) // NOLINT(modernize-loop-convert)
499  {
500  const std::string pose_name = "pose_" + std::to_string(i);
501  const std::string pose_param = TEST_POSES_PARAM + "." + pose_name; // NOLINT
502  goal = initial; // reset goal to initial
503  ground_truth.clear();
504 
505  node_->get_parameter_or(pose_param + ".joints", ground_truth, ground_truth);
506  if (!ground_truth.empty())
507  {
508  ASSERT_EQ(ground_truth.size(), joints_.size())
509  << "Test pose '" << pose_name << "' has invalid 'joints' vector size";
510  }
511 
512  pose_values.clear();
513  node_->get_parameter_or(pose_param + ".pose", pose_values, pose_values);
514  ASSERT_TRUE(pose_values.size() == 6 || pose_values.size() == 7)
515  << "Test pose '" << pose_name << "' has invalid 'pose' vector size";
516 
517  Eigen::Isometry3d pose;
518  ASSERT_TRUE(parsePose(pose_values, pose)) << "Failed to parse 'pose' vector in: " << pose_name;
519  std::string pose_type = "pose_type_relative";
520  node_->get_parameter_or(pose_param + ".type", pose_type, pose_type);
521  if (pose_type == pose_type_relative)
522  {
523  goal = goal * pose;
524  }
525  else if (pose_type == pose_type_absolute)
526  {
527  goal = pose;
528  }
529  else
530  {
531  FAIL() << "Found invalid 'type' in " << pose_name << ": should be one of '" << pose_type_relative << "' or '"
532  << pose_type_absolute << '\'';
533  }
534 
535  std::string desc;
536  {
537  SCOPED_TRACE(desc);
538  validate_ik(tf2::toMsg(goal), ground_truth);
539  }
540  }
541 }
542 
544 {
545  std::vector<double> seed, fk_values, solution;
546  moveit_msgs::msg::MoveItErrorCodes error_code;
547  solution.resize(kinematics_solver_->getJointNames().size(), 0.0);
548  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
549  moveit::core::RobotState robot_state(robot_model_);
550  robot_state.setToDefaultValues();
551 
552  unsigned int success = 0;
553  for (unsigned int i = 0; i < num_ik_tests_; ++i)
554  {
555  seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
556  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
557  robot_state.setToRandomPositions(jmg_, this->rng_);
558  robot_state.copyJointGroupPositions(jmg_, fk_values);
559  std::vector<geometry_msgs::msg::Pose> poses;
560  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
561 
562  kinematics_solver_->searchPositionIK(poses[0], seed, timeout_, solution, error_code);
563  if (error_code.val == error_code.SUCCESS)
564  {
565  success++;
566  }
567  else
568  {
569  continue;
570  }
571 
572  std::vector<geometry_msgs::msg::Pose> reached_poses;
573  kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
574  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
575  }
576 
577  if (num_ik_cb_tests_ > 0)
578  {
579  RCLCPP_INFO_STREAM(getLogger(), "Success Rate: " << static_cast<double>(success) / num_ik_tests_);
580  }
581  EXPECT_GE(success, EXPECTED_SUCCESS_RATE * num_ik_tests_);
582 }
583 
584 TEST_F(KinematicsTest, searchIKWithCallback)
585 {
586  std::vector<double> seed, fk_values, solution;
587  moveit_msgs::msg::MoveItErrorCodes error_code;
588  solution.resize(kinematics_solver_->getJointNames().size(), 0.0);
589  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
590  moveit::core::RobotState robot_state(robot_model_);
591  robot_state.setToDefaultValues();
592 
593  unsigned int success = 0;
594  for (unsigned int i = 0; i < num_ik_cb_tests_; ++i)
595  {
596  seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
597  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
598  robot_state.setToRandomPositions(jmg_, this->rng_);
599  robot_state.copyJointGroupPositions(jmg_, fk_values);
600  std::vector<geometry_msgs::msg::Pose> poses;
601  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
602  if (poses[0].position.z <= 0.0f)
603  {
604  --i; // draw a new random state
605  continue;
606  }
607 
608  kinematics_solver_->searchPositionIK(
609  poses[0], fk_values, timeout_, solution,
610  [this](const geometry_msgs::msg::Pose&, const std::vector<double>& joints,
611  moveit_msgs::msg::MoveItErrorCodes& error_code) { searchIKCallback(joints, error_code); },
612  error_code);
613  if (error_code.val == error_code.SUCCESS)
614  {
615  success++;
616  }
617  else
618  {
619  continue;
620  }
621 
622  std::vector<geometry_msgs::msg::Pose> reached_poses;
623  kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
624  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
625  }
626 
627  if (num_ik_cb_tests_ > 0)
628  {
629  RCLCPP_INFO_STREAM(getLogger(), "Success Rate: " << static_cast<double>(success) / num_ik_cb_tests_);
630  }
631  EXPECT_GE(success, EXPECTED_SUCCESS_RATE * num_ik_cb_tests_);
632 }
633 
635 {
636  std::vector<double> fk_values, solution;
637  moveit_msgs::msg::MoveItErrorCodes error_code;
638  solution.resize(kinematics_solver_->getJointNames().size(), 0.0);
639  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
640  moveit::core::RobotState robot_state(robot_model_);
641  robot_state.setToDefaultValues();
642 
643  for (unsigned int i = 0; i < num_ik_tests_; ++i)
644  {
645  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
646  robot_state.setToRandomPositions(jmg_, this->rng_);
647  robot_state.copyJointGroupPositions(jmg_, fk_values);
648  std::vector<geometry_msgs::msg::Pose> poses;
649 
650  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
651  kinematics_solver_->getPositionIK(poses[0], fk_values, solution, error_code);
652  // starting from the correct solution, should yield the same pose
653  EXPECT_EQ(error_code.val, error_code.SUCCESS);
654 
655  Eigen::Map<Eigen::ArrayXd> sol(solution.data(), solution.size());
656  Eigen::Map<Eigen::ArrayXd> truth(fk_values.data(), fk_values.size());
657  EXPECT_TRUE(sol.isApprox(truth, tolerance_)) << sol.transpose() << '\n' << truth.transpose() << '\n';
658  }
659 }
660 
661 TEST_F(KinematicsTest, getIKMultipleSolutions)
662 {
663  std::vector<double> seed, fk_values;
664  std::vector<std::vector<double>> solutions;
667 
668  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
669  moveit::core::RobotState robot_state(robot_model_);
670  robot_state.setToDefaultValues();
671 
672  unsigned int success = 0;
673  for (unsigned int i = 0; i < num_ik_multiple_tests_; ++i)
674  {
675  seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
676  fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
677  robot_state.setToRandomPositions(jmg_, this->rng_);
678  robot_state.copyJointGroupPositions(jmg_, fk_values);
679  std::vector<geometry_msgs::msg::Pose> poses;
680  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
681 
682  solutions.clear();
683  kinematics_solver_->getPositionIK(poses, fk_values, solutions, result, options);
684 
686  {
687  success += solutions.empty() ? 0 : 1;
688  }
689  else
690  {
691  continue;
692  }
693 
694  std::vector<geometry_msgs::msg::Pose> reached_poses;
695  for (const auto& s : solutions)
696  {
697  kinematics_solver_->getPositionFK(fk_names, s, reached_poses);
698  EXPECT_NEAR_POSES(poses, reached_poses, tolerance_);
699  }
700  }
701 
702  if (num_ik_cb_tests_ > 0)
703  {
704  RCLCPP_INFO_STREAM(getLogger(), "Success Rate: " << static_cast<double>(success) / num_ik_multiple_tests_);
705  }
706  EXPECT_GE(success, EXPECTED_SUCCESS_RATE * num_ik_multiple_tests_);
707 }
708 
709 // validate that getPositionIK() retrieves closest solution to seed
710 TEST_F(KinematicsTest, getNearestIKSolution)
711 {
712  std::vector<std::vector<double>> solutions;
715 
716  std::vector<double> seed, fk_values, solution;
717  moveit_msgs::msg::MoveItErrorCodes error_code;
718  const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
719  moveit::core::RobotState robot_state(robot_model_);
720  robot_state.setToDefaultValues();
721 
722  for (unsigned int i = 0; i < num_nearest_ik_tests_; ++i)
723  {
724  robot_state.setToRandomPositions(jmg_, this->rng_);
725  robot_state.copyJointGroupPositions(jmg_, fk_values);
726  std::vector<geometry_msgs::msg::Pose> poses;
727  ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
728 
729  // sample seed vector
730  robot_state.setToRandomPositions(jmg_, this->rng_);
731  robot_state.copyJointGroupPositions(jmg_, seed);
732 
733  // getPositionIK for single solution
734  kinematics_solver_->getPositionIK(poses[0], seed, solution, error_code);
735 
736  // check if getPositionIK call for single solution returns solution
737  if (error_code.val != error_code.SUCCESS)
738  continue;
739 
740  const Eigen::Map<const Eigen::VectorXd> seed_eigen(seed.data(), seed.size());
741  double error_get_ik =
742  (Eigen::Map<const Eigen::VectorXd>(solution.data(), solution.size()) - seed_eigen).array().abs().sum();
743 
744  // getPositionIK for multiple solutions
745  solutions.clear();
746  kinematics_solver_->getPositionIK(poses, seed, solutions, result, options);
747 
748  // check if getPositionIK call for multiple solutions returns solution
750  << "Multiple solution call failed, while single solution call succeeded";
752  continue;
753 
754  double smallest_error_multiple_ik = std::numeric_limits<double>::max();
755  for (const auto& s : solutions)
756  {
757  double error_multiple_ik =
758  (Eigen::Map<const Eigen::VectorXd>(s.data(), s.size()) - seed_eigen).array().abs().sum();
759  if (error_multiple_ik <= smallest_error_multiple_ik)
760  smallest_error_multiple_ik = error_multiple_ik;
761  }
762  EXPECT_NEAR(smallest_error_multiple_ik, error_get_ik, tolerance_);
763  }
764 }
765 
766 int main(int argc, char** argv)
767 {
768  testing::InitGoogleTest(&argc, argv);
769  rclcpp::init(argc, argv);
770  int result = RUN_ALL_TESTS();
771  SharedData::release(); // avoid class_loader::LibraryUnloadException
772  return result;
773 }
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:1246
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
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:669
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.
rclcpp::Logger getLogger(const std::string &name)
Creates a namespaced logger.
Definition: logger.cpp:79
name
Definition: setup.py:7
A set of options for the kinematics solver.
int main(int argc, char **argv)
rclcpp::Logger getLogger()
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)