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>
66static const std::string UNDEFINED =
"<undefined>";
72 typedef pluginlib::ClassLoader<kinematics::KinematicsBase> KinematicsLoader;
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_;
88 int num_ik_multiple_tests_;
89 int num_nearest_ik_tests_;
90 bool publish_trajectory_;
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);
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";
111 kinematics_loader_ = std::make_unique<KinematicsLoader>(
"moveit_core",
"kinematics::KinematicsBase");
112 ASSERT_TRUE(
bool(kinematics_loader_)) <<
"Failed to instantiate ClassLoader";
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);
136 ASSERT_TRUE(robot_model_->hasJointModelGroup(group_name_));
137 ASSERT_TRUE(robot_model_->hasLinkModel(root_link_));
138 ASSERT_TRUE(robot_model_->hasLinkModel(tip_link_));
142 std::shared_ptr<rclcpp::Node>
node_;
146 return kinematics_loader_->createUniqueInstance(name);
157 shared.kinematics_loader_.reset();
197 <<
"Solver failed to initialize";
209 testing::AssertionResult
isNear(
const char* expr1,
const char* expr2,
const char* ,
210 const geometry_msgs::msg::Point& val1,
const geometry_msgs::msg::Point& val2,
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();
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 <<
']';
225 testing::AssertionResult
isNear(
const char* expr1,
const char* expr2,
const char* ,
226 const geometry_msgs::msg::Quaternion& val1,
227 const geometry_msgs::msg::Quaternion& val2,
double abs_error)
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();
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 <<
']';
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)
246 if (val1.size() != val2.size())
248 return testing::AssertionFailure() <<
"Different vector sizes"
249 <<
"\nExpected: " << expr1 <<
" (" << val1.size() <<
')'
250 <<
"\nActual: " << expr2 <<
" (" << val2.size() <<
')';
253 for (
size_t i = 0; i < val1.size(); ++i)
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_);
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_);
267 return testing::AssertionSuccess();
270 void searchIKCallback(
const std::vector<double>& joint_state, moveit_msgs::msg::MoveItErrorCodes& error_code)
272 std::vector<std::string> link_names = {
tip_link_ };
273 std::vector<geometry_msgs::msg::Pose> poses;
276 error_code.val = error_code.PLANNING_FAILED;
280 EXPECT_GT(poses[0].position.z, 0.0f);
281 if (poses[0].position.z > 0.0)
283 error_code.val = error_code.SUCCESS;
287 error_code.val = error_code.PLANNING_FAILED;
296 random_numbers::RandomNumberGenerator
rng_{ 42 };
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_);
320 std::vector<double> joints(kinematics_solver_->getJointNames().size(), 0.0);
321 const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
325 for (
unsigned int i = 0; i < num_fk_tests_; ++i)
329 std::vector<geometry_msgs::msg::Pose> fk_poses;
330 EXPECT_TRUE(kinematics_solver_->getPositionFK(tip_frames, joints, fk_poses));
333 std::vector<geometry_msgs::msg::Pose> model_poses;
334 model_poses.reserve(tip_frames.size());
335 for (
const auto& tip : tip_frames)
344 std::vector<double> seed, goal, solution;
345 const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
352 moveit_msgs::msg::DisplayTrajectory msg;
353 msg.model_id = robot_model_->getName();
355 msg.trajectory.resize(1);
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)
370 std::vector<geometry_msgs::msg::Pose> poses;
371 ASSERT_TRUE(kinematics_solver_->getPositionFK(tip_frames, goal, poses));
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)
383 std::vector<geometry_msgs::msg::Pose> reached_poses;
384 kinematics_solver_->getPositionFK(tip_frames, solution, reached_poses);
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))
393 RCLCPP_WARN_STREAM(
getLogger(),
"jump in [" << i <<
"]: " << diff.transpose());
401 if (publish_trajectory_)
403 auto pub = node_->create_publisher<moveit_msgs::msg::DisplayTrajectory>(
"display_random_walk", 1);
406 rclcpp::spin_some(node_);
410static bool parsePose(
const std::vector<double>& pose_values, Eigen::Isometry3d& goal)
412 std::vector<double> vec;
413 Eigen::Quaterniond q;
414 if (pose_values.size() == 6)
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());
420 else if (pose_values.size() == 7)
422 q = Eigen::Quaterniond(pose_values[3], pose_values[4], pose_values[5], pose_values[6]);
430 goal.translation() = Eigen::Vector3d(pose_values[0], pose_values[1], pose_values[2]);
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);
441 std::vector<double> sol;
442 const std::vector<std::string>& tip_frames = kinematics_solver_->getTipFrames();
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);
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);
457 auto validate_ik = [&](
const geometry_msgs::msg::Pose& goal, std::vector<double>& truth) {
459 moveit_msgs::msg::MoveItErrorCodes error_code;
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);
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);
469 std::vector<geometry_msgs::msg::Pose> reached_poses;
470 kinematics_solver_->getPositionFK(tip_frames, sol, reached_poses);
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';
484 std::vector<double> ground_truth, pose_values;
485 constexpr char pose_type_relative[] =
"relative";
486 constexpr char pose_type_absolute[] =
"absolute";
498 for (
size_t i = 0; i < expected_test_poses; ++i)
500 const std::string pose_name =
"pose_" + std::to_string(i);
501 const std::string pose_param = TEST_POSES_PARAM +
"." + pose_name;
503 ground_truth.clear();
505 node_->get_parameter_or(pose_param +
".joints", ground_truth, ground_truth);
506 if (!ground_truth.empty())
508 ASSERT_EQ(ground_truth.size(), joints_.size())
509 <<
"Test pose '" << pose_name <<
"' has invalid 'joints' vector size";
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";
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)
525 else if (pose_type == pose_type_absolute)
531 FAIL() <<
"Found invalid 'type' in " << pose_name <<
": should be one of '" << pose_type_relative <<
"' or '"
532 << pose_type_absolute <<
'\'';
538 validate_ik(tf2::toMsg(goal), ground_truth);
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();
552 unsigned int success = 0;
553 for (
unsigned int i = 0; i < num_ik_tests_; ++i)
555 seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
556 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
559 std::vector<geometry_msgs::msg::Pose> poses;
560 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
562 kinematics_solver_->searchPositionIK(poses[0], seed, timeout_, solution, error_code);
563 if (error_code.val == error_code.SUCCESS)
572 std::vector<geometry_msgs::msg::Pose> reached_poses;
573 kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
577 if (num_ik_cb_tests_ > 0)
579 RCLCPP_INFO_STREAM(
getLogger(),
"Success Rate: " <<
static_cast<double>(success) / num_ik_tests_);
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();
593 unsigned int success = 0;
594 for (
unsigned int i = 0; i < num_ik_cb_tests_; ++i)
596 seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
597 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
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)
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); },
613 if (error_code.val == error_code.SUCCESS)
622 std::vector<geometry_msgs::msg::Pose> reached_poses;
623 kinematics_solver_->getPositionFK(fk_names, solution, reached_poses);
627 if (num_ik_cb_tests_ > 0)
629 RCLCPP_INFO_STREAM(
getLogger(),
"Success Rate: " <<
static_cast<double>(success) / num_ik_cb_tests_);
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();
643 for (
unsigned int i = 0; i < num_ik_tests_; ++i)
645 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
648 std::vector<geometry_msgs::msg::Pose> poses;
650 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
651 kinematics_solver_->getPositionIK(poses[0], fk_values, solution, error_code);
653 EXPECT_EQ(error_code.val, error_code.SUCCESS);
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';
663 std::vector<double> seed, fk_values;
664 std::vector<std::vector<double>> solutions;
668 const std::vector<std::string>& fk_names = kinematics_solver_->getTipFrames();
672 unsigned int success = 0;
673 for (
unsigned int i = 0; i < num_ik_multiple_tests_; ++i)
675 seed.resize(kinematics_solver_->getJointNames().size(), 0.0);
676 fk_values.resize(kinematics_solver_->getJointNames().size(), 0.0);
679 std::vector<geometry_msgs::msg::Pose> poses;
680 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
683 kinematics_solver_->getPositionIK(poses, fk_values, solutions, result, options);
687 success += solutions.empty() ? 0 : 1;
694 std::vector<geometry_msgs::msg::Pose> reached_poses;
695 for (
const auto& s : solutions)
697 kinematics_solver_->getPositionFK(fk_names, s, reached_poses);
702 if (num_ik_cb_tests_ > 0)
704 RCLCPP_INFO_STREAM(
getLogger(),
"Success Rate: " <<
static_cast<double>(success) / num_ik_multiple_tests_);
712 std::vector<std::vector<double>> solutions;
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();
722 for (
unsigned int i = 0; i < num_nearest_ik_tests_; ++i)
726 std::vector<geometry_msgs::msg::Pose> poses;
727 ASSERT_TRUE(kinematics_solver_->getPositionFK(fk_names, fk_values, poses));
734 kinematics_solver_->getPositionIK(poses[0], seed, solution, error_code);
737 if (error_code.val != error_code.SUCCESS)
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();
746 kinematics_solver_->getPositionIK(poses, seed, solutions, result, options);
750 <<
"Multiple solution call failed, while single solution call succeeded";
754 double smallest_error_multiple_ik = std::numeric_limits<double>::max();
755 for (
const auto& s : solutions)
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;
762 EXPECT_NEAR(smallest_error_multiple_ik, error_get_ik, tolerance_);
768 testing::InitGoogleTest(&argc, argv);
769 rclcpp::init(argc, argv);
770 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)
auto createUniqueInstance(const std::string &name) const
static const SharedData & instance()
std::shared_ptr< rclcpp::Node > node_
Representation of a robot's state. This includes position, velocity, acceleration and effort.
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...
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...
Maintain a sequence of waypoints and the time durations between these waypoints.
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
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.
A set of options for the kinematics solver.
KinematicError kinematic_error
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)