38 #include <gtest/gtest.h>
41 #include <pluginlib/class_loader.hpp>
42 #include <rclcpp/rclcpp.hpp>
43 #include <tf2_eigen/tf2_eigen.hpp>
53 #include <moveit_msgs/msg/display_trajectory.hpp>
58 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"test_kinematics_plugin");
62 static const std::string UNDEFINED =
"<undefined>";
68 typedef pluginlib::ClassLoader<kinematics::KinematicsBase> KinematicsLoader;
71 std::unique_ptr<KinematicsLoader> kinematics_loader_;
76 std::vector<std::string>
joints_;
77 std::vector<double>
seed_;
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);
104 ASSERT_TRUE(
bool(
robot_model_)) <<
"Failed to load robot model";
107 kinematics_loader_ = std::make_unique<KinematicsLoader>(
"moveit_core",
"kinematics::KinematicsBase");
108 ASSERT_TRUE(
bool(kinematics_loader_)) <<
"Failed to instantiate ClassLoader";
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";
119 <<
"If set, 'consistency_limits' size must match 'joint_names' size";
121 ASSERT_TRUE(
timeout_ > 0.0) <<
"'ik_timeout' must be more than 0.0 seconds";
123 ASSERT_TRUE(
tolerance_ > 0.0) <<
"'tolerance' must be greater than 0.0";
138 std::shared_ptr<rclcpp::Node>
node_;
142 return kinematics_loader_->createUniqueInstance(
name);
153 shared.kinematics_loader_.reset();
193 <<
"Solver failed to initialize";
205 testing::AssertionResult
isNear(
const char* expr1,
const char* expr2,
const char* ,
206 const geometry_msgs::msg::Point& val1,
const geometry_msgs::msg::Point& val2,
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();
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 <<
"]";
221 testing::AssertionResult
isNear(
const char* expr1,
const char* expr2,
const char* ,
222 const geometry_msgs::msg::Quaternion& val1,
223 const geometry_msgs::msg::Quaternion& val2,
double abs_error)
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();
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 <<
"]";
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)
242 if (val1.size() != val2.size())
243 return testing::AssertionFailure() <<
"Different vector sizes"
244 <<
"\nExpected: " << expr1 <<
" (" << val1.size() <<
")"
245 <<
"\nActual: " << expr2 <<
" (" << val2.size() <<
")";
247 for (
size_t i = 0; i < val1.size(); ++i)
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_);
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_);
261 return testing::AssertionSuccess();
264 void searchIKCallback(
const std::vector<double>& joint_state, moveit_msgs::msg::MoveItErrorCodes& error_code)
266 std::vector<std::string> link_names = {
tip_link_ };
267 std::vector<geometry_msgs::msg::Pose> poses;
270 error_code.val = error_code.PLANNING_FAILED;
274 EXPECT_GT(poses[0].position.z, 0.0f);
275 if (poses[0].position.z > 0.0)
276 error_code.val = error_code.SUCCESS;
278 error_code.val = error_code.PLANNING_FAILED;
286 random_numbers::RandomNumberGenerator
rng_{ 42 };
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_);
310 std::vector<double> joints(kinematics_solver_->getJointNames().size(), 0.0);
311 const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
315 for (
unsigned int i = 0; i < num_fk_tests_; ++i)
319 std::vector<geometry_msgs::msg::Pose> fk_poses;
320 EXPECT_TRUE(kinematics_solver_->getPositionFK(tip_frames, joints, fk_poses));
323 std::vector<geometry_msgs::msg::Pose> model_poses;
324 model_poses.reserve(tip_frames.size());
325 for (
const auto& tip : tip_frames)
334 std::vector<double> seed, goal, solution;
335 const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
342 moveit_msgs::msg::DisplayTrajectory msg;
343 msg.model_id = robot_model_->getName();
345 msg.trajectory.resize(1);
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)
360 std::vector<geometry_msgs::msg::Pose> poses;
361 ASSERT_TRUE(kinematics_solver_->getPositionFK(tip_frames, goal, poses));
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)
373 std::vector<geometry_msgs::msg::Pose> reached_poses;
374 kinematics_solver_->getPositionFK(tip_frames, solution, reached_poses);
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))
383 RCLCPP_WARN_STREAM(LOGGER,
"jump in [" << i <<
"]: " << diff.transpose());
391 if (publish_trajectory_)
393 auto pub = node_->create_publisher<moveit_msgs::msg::DisplayTrajectory>(
"display_random_walk", 1);
396 rclcpp::spin_some(node_);
400 static bool parsePose(
const std::vector<double>& pose_values, Eigen::Isometry3d& goal)
402 std::vector<double> vec;
403 Eigen::Quaterniond q;
404 if (pose_values.size() == 6)
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());
410 else if (pose_values.size() == 7)
412 q = Eigen::Quaterniond(pose_values[3], pose_values[4], pose_values[5], pose_values[6]);
420 goal.translation() =
Eigen::Vector3d(pose_values[0], pose_values[1], pose_values[2]);
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);
431 std::vector<double> sol;
432 const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
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);
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);
446 auto validate_ik = [&](
const geometry_msgs::msg::Pose& goal, std::vector<double>& truth) {
448 moveit_msgs::msg::MoveItErrorCodes error_code;
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);
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);
458 std::vector<geometry_msgs::msg::Pose> reached_poses;
459 kinematics_solver_->getPositionFK(tip_frames, sol, reached_poses);
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';
473 std::vector<double> ground_truth, pose_values;
474 constexpr
char pose_type_relative[] =
"relative";
475 constexpr
char pose_type_absolute[] =
"absolute";
487 for (
size_t i = 0; i < expected_test_poses; ++i)
489 const std::string pose_name =
"pose_" + std::to_string(i);
490 const std::string pose_param = TEST_POSES_PARAM +
"." + pose_name;
492 ground_truth.clear();
494 node_->get_parameter_or(pose_param +
".joints", ground_truth, ground_truth);
495 if (!ground_truth.empty())
497 ASSERT_EQ(ground_truth.size(), joints_.size())
498 <<
"Test pose '" << pose_name <<
"' has invalid 'joints' vector size";
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";
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)
512 else if (pose_type == pose_type_absolute)
515 FAIL() <<
"Found invalid 'type' in " << pose_name <<
": should be one of '" << pose_type_relative <<
"' or '"
516 << pose_type_absolute <<
"'";
521 validate_ik(tf2::toMsg(goal), ground_truth);
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();
535 unsigned int success = 0;
536 for (
unsigned int i = 0; i < num_ik_tests_; ++i)
538 seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
539 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
542 std::vector<geometry_msgs::msg::Pose> poses;
543 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
545 kinematics_solver_->searchPositionIK(poses[0], seed, timeout_, solution, error_code);
546 if (error_code.val == error_code.SUCCESS)
551 std::vector<geometry_msgs::msg::Pose> reached_poses;
552 kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
556 if (num_ik_cb_tests_ > 0)
558 RCLCPP_INFO_STREAM(LOGGER,
"Success Rate: " << (
double)success / num_ik_tests_);
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();
572 unsigned int success = 0;
573 for (
unsigned int i = 0; i < num_ik_cb_tests_; ++i)
575 seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
576 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
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)
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); },
592 if (error_code.val == error_code.SUCCESS)
597 std::vector<geometry_msgs::msg::Pose> reached_poses;
598 kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
602 if (num_ik_cb_tests_ > 0)
604 RCLCPP_INFO_STREAM(LOGGER,
"Success Rate: " << (
double)success / num_ik_cb_tests_);
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();
618 for (
unsigned int i = 0; i < num_ik_tests_; ++i)
620 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
623 std::vector<geometry_msgs::msg::Pose> poses;
625 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
626 kinematics_solver_->getPositionIK(poses[0], fk_values, solution, error_code);
628 EXPECT_EQ(error_code.val, error_code.SUCCESS);
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';
638 std::vector<double> seed, fk_values;
639 std::vector<std::vector<double>> solutions;
643 const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
647 unsigned int success = 0;
648 for (
unsigned int i = 0; i < num_ik_multiple_tests_; ++i)
650 seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
651 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
654 std::vector<geometry_msgs::msg::Pose> poses;
655 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
658 kinematics_solver_->getPositionIK(poses, fk_values, solutions, result,
options);
661 success += solutions.empty() ? 0 : 1;
665 std::vector<geometry_msgs::msg::Pose> reached_poses;
666 for (
const auto& s : solutions)
668 kinematics_solver_->getPositionFK(fk_names, s, reached_poses);
673 if (num_ik_cb_tests_ > 0)
675 RCLCPP_INFO_STREAM(LOGGER,
"Success Rate: " << (
double)success / num_ik_multiple_tests_);
683 std::vector<std::vector<double>> solutions;
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();
693 for (
unsigned int i = 0; i < num_nearest_ik_tests_; ++i)
697 std::vector<geometry_msgs::msg::Pose> poses;
698 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
705 kinematics_solver_->getPositionIK(poses[0], seed, solution, error_code);
708 if (error_code.val != error_code.SUCCESS)
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();
717 kinematics_solver_->getPositionIK(poses, seed, solutions, result,
options);
721 <<
"Multiple solution call failed, while single solution call succeeded";
725 double smallest_error_multiple_ik = std::numeric_limits<double>::max();
726 for (
const auto& s : solutions)
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;
733 EXPECT_NEAR(smallest_error_multiple_ik, error_get_ik, tolerance_);
737 int main(
int argc,
char** argv)
739 testing::InitGoogleTest(&argc, argv);
740 rclcpp::init(argc, argv);
741 int result = RUN_ALL_TESTS();
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_
std::string ik_plugin_name_
unsigned int num_ik_tests_
kinematics::KinematicsBasePtr kinematics_solver_
void operator=(const SharedData &data)
moveit::core::JointModelGroup * jmg_
unsigned int num_nearest_ik_tests_
unsigned int num_fk_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)
unsigned int num_ik_cb_tests_
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
std::shared_ptr< rclcpp::Node > node_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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...
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...
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...
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
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.
A set of options for the kinematics solver.
KinematicError kinematic_error
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)