moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_trajectory_functions.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2018 Pilz GmbH & Co. KG
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Pilz GmbH & Co. KG nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 #include <gtest/gtest.h>
36 
37 #include <map>
38 #include <math.h>
39 #include <string>
40 #include <vector>
41 
42 #include <Eigen/Geometry>
43 #include <kdl/frames.hpp>
44 #include <kdl/path_roundedcomposite.hpp>
45 #include <kdl/rotational_interpolation_sa.hpp>
46 #include <kdl/trajectory.hpp>
47 #include <kdl/trajectory_segment.hpp>
48 #include <kdl/velocityprofile_trap.hpp>
53 #include <tf2_eigen/tf2_eigen.hpp>
54 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
55 
60 #include "test_utils.hpp"
61 
62 #define _USE_MATH_DEFINES
63 
64 static constexpr double EPSILON{ 1.0e-6 };
65 static constexpr double IK_SEED_OFFSET{ 0.1 };
66 static constexpr double L0{ 0.2604 }; // Height of foot
67 static constexpr double L1{ 0.3500 }; // Height of first connector
68 static constexpr double L2{ 0.3070 }; // Height of second connector
69 static constexpr double L3{ 0.0840 }; // Distance last joint to flange
70 
71 // parameters from parameter server
72 const std::string PARAM_PLANNING_GROUP_NAME("planning_group");
73 const std::string GROUP_TIP_LINK_NAME("group_tip_link");
74 const std::string ROBOT_TCP_LINK_NAME("tcp_link");
75 const std::string IK_FAST_LINK_NAME("ik_fast_link");
76 const std::string RANDOM_TEST_NUMBER("random_test_number");
77 
81 class TrajectoryFunctionsTestBase : public testing::Test
82 {
83 protected:
88  void SetUp() override
89  {
90  rclcpp::NodeOptions node_options;
91  node_options.automatically_declare_parameters_from_overrides(true);
92  node_ = rclcpp::Node::make_shared("unittest_trajectory_functions", node_options);
93 
94  // load robot model
95  rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
96  robot_model_ = rm_loader_->getModel();
97  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
98  robot_state_ = std::make_shared<moveit::core::RobotState>(robot_model_);
99  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
100 
101  // get parameters
102  ASSERT_TRUE(node_->has_parameter("planning_group"));
103  node_->get_parameter<std::string>("planning_group", planning_group_);
104  ASSERT_TRUE(node_->has_parameter("group_tip_link"));
105  node_->get_parameter<std::string>("group_tip_link", group_tip_link_);
106  ASSERT_TRUE(node_->has_parameter("tcp_link"));
107  node_->get_parameter<std::string>("tcp_link", tcp_link_);
108  ASSERT_TRUE(node_->has_parameter("ik_fast_link"));
109  node_->get_parameter<std::string>("ik_fast_link", ik_fast_link_);
110  ASSERT_TRUE(node_->has_parameter("random_test_number"));
111  node_->get_parameter<int>("random_test_number", random_test_number_);
112 
113  // check robot model
115 
116  // initialize the zero state configurationg and test joint state
117  joint_names_ = robot_model_->getJointModelGroup(planning_group_)->getActiveJointModelNames();
118  for (const auto& joint_name : joint_names_)
119  {
120  zero_state_[joint_name] = 0.0;
121  }
122  }
123 
124  void TearDown() override
125  {
126  robot_model_.reset();
127  }
128 
136  bool tfNear(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, double epsilon);
137 
145  bool jointsNear(const std::vector<double>& joints1, const std::vector<double>& joints2, double epsilon);
146 
153  std::vector<double> getJoints(const moveit::core::JointModelGroup* jmg, const moveit::core::RobotState& state);
154 
164  const std::string& object_name, const Eigen::Isometry3d& object_pose,
165  const moveit::core::FixedTransformsMap& subframes);
166 
167 protected:
168  // ros stuff
169  rclcpp::Node::SharedPtr node_;
170  moveit::core::RobotModelConstPtr robot_model_;
171  moveit::core::RobotStatePtr robot_state_;
172  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
173  planning_scene::PlanningSceneConstPtr planning_scene_;
174 
175  // test parameters from parameter server
178  std::vector<std::string> joint_names_;
179  std::map<std::string, double> zero_state_;
180 
181  // random seed
182  uint32_t random_seed_{ 100 };
183  random_numbers::RandomNumberGenerator rng_{ random_seed_ };
184 };
185 
186 bool TrajectoryFunctionsTestBase::tfNear(const Eigen::Isometry3d& pose1, const Eigen::Isometry3d& pose2, double epsilon)
187 {
188  for (std::size_t i = 0; i < 3; ++i)
189  {
190  for (std::size_t j = 0; j < 4; ++j)
191  {
192  if (fabs(pose1(i, j) - pose2(i, j)) > fabs(epsilon))
193  return false;
194  }
195  }
196  return true;
197 }
198 
199 bool TrajectoryFunctionsTestBase::jointsNear(const std::vector<double>& joints1, const std::vector<double>& joints2,
200  double epsilon)
201 {
202  if (joints1.size() != joints2.size())
203  {
204  return false;
205  }
206  for (std::size_t i = 0; i < joints1.size(); ++i)
207  {
208  if (fabs(joints1.at(i) - joints2.at(i)) > fabs(epsilon))
209  {
210  return false;
211  }
212  }
213  return true;
214 }
215 
217  const moveit::core::RobotState& state)
218 {
219  std::vector<double> joints;
220  for (const auto& name : jmg->getActiveJointModelNames())
221  {
222  joints.push_back(state.getVariablePosition(name));
223  }
224  return joints;
225 }
226 
228  const std::string& object_name, const Eigen::Isometry3d& object_pose,
229  const moveit::core::FixedTransformsMap& subframes)
230 {
231  state.attachBody(std::make_unique<moveit::core::AttachedBody>(
232  link, object_name, object_pose, std::vector<shapes::ShapeConstPtr>{}, EigenSTL::vector_Isometry3d{},
233  std::set<std::string>{}, trajectory_msgs::msg::JointTrajectory{}, subframes));
234 }
235 
240 {
241 };
242 
243 // TODO(henningkayser): re-enable gripper tests
244 // /**
245 // * @brief Parametrized class for tests, that only run with a gripper
246 // */
247 // class TrajectoryFunctionsTestOnlyGripper : public TrajectoryFunctionsTestBase
248 // {
249 // };
250 
257 {
258  Eigen::Isometry3d tip_pose;
259  std::map<std::string, double> test_state = zero_state_;
260  EXPECT_TRUE(pilz_industrial_motion_planner::computeLinkFK(*robot_state_, group_tip_link_, test_state, tip_pose));
261  EXPECT_NEAR(tip_pose(0, 3), 0, EPSILON);
262  EXPECT_NEAR(tip_pose(1, 3), 0, EPSILON);
263  EXPECT_NEAR(tip_pose(2, 3), L0 + L1 + L2 + L3, EPSILON);
264 
265  test_state[joint_names_.at(1)] = M_PI_2;
266  EXPECT_TRUE(pilz_industrial_motion_planner::computeLinkFK(*robot_state_, group_tip_link_, test_state, tip_pose));
267  EXPECT_NEAR(tip_pose(0, 3), L1 + L2 + L3, EPSILON);
268  EXPECT_NEAR(tip_pose(1, 3), 0, EPSILON);
269  EXPECT_NEAR(tip_pose(2, 3), L0, EPSILON);
270 
271  test_state[joint_names_.at(1)] = -M_PI_2;
272  test_state[joint_names_.at(2)] = M_PI_2;
273  EXPECT_TRUE(pilz_industrial_motion_planner::computeLinkFK(*robot_state_, group_tip_link_, test_state, tip_pose));
274  EXPECT_NEAR(tip_pose(0, 3), -L1, EPSILON);
275  EXPECT_NEAR(tip_pose(1, 3), 0, EPSILON);
276  EXPECT_NEAR(tip_pose(2, 3), L0 - L2 - L3, EPSILON);
277 
278  // wrong link name
279  std::string link_name = "wrong_link_name";
280  EXPECT_FALSE(pilz_industrial_motion_planner::computeLinkFK(*robot_state_, link_name, test_state, tip_pose));
281 }
282 
287 {
288  // Load solver
289  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
290  const kinematics::KinematicsBaseConstPtr& solver = jmg->getSolverInstance();
291 
292  if (!solver)
293  {
294  throw("No IK solver configured for group '" + planning_group_ + "'");
295  }
296  // robot state
297  moveit::core::RobotState rstate(robot_model_);
298 
299  while (random_test_number_ > 0)
300  {
301  // sample random robot state
302  rstate.setToRandomPositions(jmg, rng_);
303  rstate.update();
304  geometry_msgs::msg::Pose pose_expect = tf2::toMsg(rstate.getFrameTransform(ik_fast_link_));
305 
306  // prepare inverse kinematics
307  std::vector<geometry_msgs::msg::Pose> ik_poses;
308  ik_poses.push_back(pose_expect);
309  std::vector<double> ik_seed, ik_expect, ik_actual;
310  for (const auto& joint_name : jmg->getActiveJointModelNames())
311  {
312  ik_expect.push_back(rstate.getVariablePosition(joint_name));
313  if (rstate.getVariablePosition(joint_name) > 0)
314  {
315  ik_seed.push_back(rstate.getVariablePosition(joint_name) - IK_SEED_OFFSET);
316  }
317  else
318  {
319  ik_seed.push_back(rstate.getVariablePosition(joint_name) + IK_SEED_OFFSET);
320  }
321  }
322 
323  std::vector<std::vector<double>> ik_solutions;
325  moveit_msgs::msg::MoveItErrorCodes err_code;
327 
328  // compute all ik solutions
329  EXPECT_TRUE(solver->getPositionIK(ik_poses, ik_seed, ik_solutions, ik_result, options));
330 
331  // compute one ik solution
332  EXPECT_TRUE(solver->getPositionIK(pose_expect, ik_seed, ik_actual, err_code));
333 
334  ASSERT_EQ(ik_expect.size(), ik_actual.size());
335 
336  for (std::size_t i = 0; i < ik_expect.size(); ++i)
337  {
338  EXPECT_NEAR(ik_actual.at(i), ik_expect.at(i), 4 * IK_SEED_OFFSET);
339  }
340 
341  --random_test_number_;
342  }
343 }
344 
350 {
351  // robot state
352  moveit::core::RobotState rstate(robot_model_);
353  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
354 
355  while (random_test_number_ > 0)
356  {
357  // sample random robot state
358  rstate.setToRandomPositions(jmg, rng_);
359 
360  Eigen::Isometry3d pose_expect = rstate.getFrameTransform(tcp_link_);
361 
362  // copy the random state and set ik seed
363  std::map<std::string, double> ik_seed, ik_expect;
364  for (const auto& joint_name : joint_names_)
365  {
366  ik_expect[joint_name] = rstate.getVariablePosition(joint_name);
367  if (rstate.getVariablePosition(joint_name) > 0)
368  {
369  ik_seed[joint_name] = rstate.getVariablePosition(joint_name) - IK_SEED_OFFSET;
370  }
371  else
372  {
373  ik_seed[joint_name] = rstate.getVariablePosition(joint_name) + IK_SEED_OFFSET;
374  }
375  }
376 
377  rstate.setVariablePositions(ik_seed);
378  rstate.update();
379 
380  // compute the ik
381  std::map<std::string, double> ik_actual;
382 
383  EXPECT_TRUE(rstate.setFromIK(robot_model_->getJointModelGroup(planning_group_), pose_expect, tcp_link_));
384 
385  for (const auto& joint_name : joint_names_)
386  {
387  ik_actual[joint_name] = rstate.getVariablePosition(joint_name);
388  }
389 
390  // compare ik solution and expected value
391  for (const auto& joint_pair : ik_actual)
392  {
393  EXPECT_NEAR(joint_pair.second, ik_expect.at(joint_pair.first), 4 * IK_SEED_OFFSET);
394  }
395 
396  // compute the pose from ik_solution
397  rstate.setVariablePositions(ik_actual);
398  rstate.update();
399  Eigen::Isometry3d pose_actual = rstate.getFrameTransform(tcp_link_);
400 
401  EXPECT_TRUE(tfNear(pose_expect, pose_actual, EPSILON));
402 
403  --random_test_number_;
404  }
405 }
406 
407 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentityCollisionObject)
408 {
409  // Set up a default robot
410  moveit::core::RobotState state(robot_model_);
411  state.setToDefaultValues();
412  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
413 
414  std::vector<double> default_joints = getJoints(jmg, state);
415  const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
416  Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
417 
418  // Attach an object with ignored subframes, and no transform
419  Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity();
420  moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } });
421  attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
422 
423  // The RobotState should be able to use an object pose to set the joints
424  Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
425  bool success = state.setFromIK(jmg, object_pose_in_base, "object");
426  EXPECT_TRUE(success);
427 
428  // Given the target pose is the default pose of the object, the joints should be unchanged
429  std::vector<double> ik_joints = getJoints(jmg, state);
430  EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
431 }
432 
433 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedCollisionObject)
434 {
435  // Set up a default robot
436  moveit::core::RobotState state(robot_model_);
437  state.setToDefaultValues();
438  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
439 
440  std::vector<double> default_joints = getJoints(jmg, state);
441  const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
442  Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
443 
444  // Attach an object with ignored subframes, and a non-trivial transform
445  Eigen::Isometry3d object_pose_in_tip;
446  object_pose_in_tip = Eigen::Translation3d(1, 2, 3);
447  object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX());
448  moveit::core::FixedTransformsMap subframes({ { "ignored", Eigen::Isometry3d::Identity() } });
449  attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
450 
451  // The RobotState should be able to use an object pose to set the joints
452  Eigen::Isometry3d object_pose_in_base = tip_pose_in_base * object_pose_in_tip;
453  bool success = state.setFromIK(jmg, object_pose_in_base, "object");
454  EXPECT_TRUE(success);
455 
456  // Given the target pose is the default pose of the object, the joints should be unchanged
457  std::vector<double> ik_joints = getJoints(jmg, state);
458  EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
459 }
460 
461 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithIdentitySubframe)
462 {
463  // Set up a default robot
464  moveit::core::RobotState state(robot_model_);
465  state.setToDefaultValues();
466  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
467 
468  std::vector<double> default_joints = getJoints(jmg, state);
469  const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
470  Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
471 
472  // Attach an object and subframe with no transforms
473  Eigen::Isometry3d object_pose_in_tip = Eigen::Isometry3d::Identity();
474  Eigen::Isometry3d subframe_pose_in_object = Eigen::Isometry3d::Identity();
475  moveit::core::FixedTransformsMap subframes({ { "subframe", subframe_pose_in_object } });
476  attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
477 
478  // The RobotState should be able to use a subframe pose to set the joints
479  Eigen::Isometry3d subframe_pose_in_base = tip_pose_in_base * object_pose_in_tip * subframe_pose_in_object;
480  bool success = state.setFromIK(jmg, subframe_pose_in_base, "object/subframe");
481  EXPECT_TRUE(success);
482 
483  // Given the target pose is the default pose of the subframe, the joints should be unchanged
484  std::vector<double> ik_joints = getJoints(jmg, state);
485  EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
486 }
487 
488 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIKRobotStateWithTransformedSubframe)
489 {
490  // Set up a default robot
491  moveit::core::RobotState state(robot_model_);
492  state.setToDefaultValues();
493  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
494 
495  std::vector<double> default_joints = getJoints(jmg, state);
496  const moveit::core::LinkModel* tip_link = robot_model_->getLinkModel(tcp_link_);
497  Eigen::Isometry3d tip_pose_in_base = state.getFrameTransform(tcp_link_);
498 
499  // Attach an object and subframe with non-trivial transforms
500  Eigen::Isometry3d object_pose_in_tip;
501  object_pose_in_tip = Eigen::Translation3d(1, 2, 3);
502  object_pose_in_tip *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitX());
503 
504  Eigen::Isometry3d subframe_pose_in_object;
505  subframe_pose_in_object = Eigen::Translation3d(4, 5, 6);
506  subframe_pose_in_object *= Eigen::AngleAxis(M_PI_2, Eigen::Vector3d::UnitY());
507 
508  moveit::core::FixedTransformsMap subframes({ { "subframe", subframe_pose_in_object } });
509  attachToLink(state, tip_link, "object", object_pose_in_tip, subframes);
510 
511  // The RobotState should be able to use a subframe pose to set the joints
512  Eigen::Isometry3d subframe_pose_in_base = tip_pose_in_base * object_pose_in_tip * subframe_pose_in_object;
513  bool success = state.setFromIK(jmg, subframe_pose_in_base, "object/subframe");
514  EXPECT_TRUE(success);
515 
516  // Given the target pose is the default pose of the subframe, the joints should be unchanged
517  std::vector<double> ik_joints = getJoints(jmg, state);
518  EXPECT_TRUE(jointsNear(ik_joints, default_joints, 4 * IK_SEED_OFFSET));
519 }
520 
526 {
527  // robot state
528  moveit::core::RobotState rstate(robot_model_);
529 
530  const std::string frame_id = robot_model_->getModelFrame();
531  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
532 
533  while (random_test_number_ > 0)
534  {
535  // sample random robot state
536  rstate.setToRandomPositions(jmg, rng_);
537 
538  Eigen::Isometry3d pose_expect = rstate.getFrameTransform(tcp_link_);
539 
540  // copy the random state and set ik seed
541  std::map<std::string, double> ik_seed, ik_expect;
542  for (const auto& joint_name : robot_model_->getJointModelGroup(planning_group_)->getActiveJointModelNames())
543  {
544  ik_expect[joint_name] = rstate.getVariablePosition(joint_name);
545  if (rstate.getVariablePosition(joint_name) > 0)
546  {
547  ik_seed[joint_name] = rstate.getVariablePosition(joint_name) - IK_SEED_OFFSET;
548  }
549  else
550  {
551  ik_seed[joint_name] = rstate.getVariablePosition(joint_name) + IK_SEED_OFFSET;
552  }
553  }
554 
555  // compute the ik
556  std::map<std::string, double> ik_actual;
557  EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect,
558  frame_id, ik_seed, ik_actual, false));
559 
560  // compare ik solution and expected value
561  for (const auto& joint_pair : ik_actual)
562  {
563  EXPECT_NEAR(joint_pair.second, ik_expect.at(joint_pair.first), 4 * IK_SEED_OFFSET);
564  }
565 
566  --random_test_number_;
567  }
568 }
569 
573 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKInvalidGroupName)
574 {
575  const std::string frame_id = robot_model_->getModelFrame();
576  Eigen::Isometry3d pose_expect;
577 
578  std::map<std::string, double> ik_seed;
579 
580  // compute the ik
581  std::map<std::string, double> ik_actual;
582  EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, "InvalidGroupName", tcp_link_,
583  pose_expect, frame_id, ik_seed, ik_actual, false));
584 }
585 
589 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKInvalidLinkName)
590 {
591  const std::string frame_id = robot_model_->getModelFrame();
592  Eigen::Isometry3d pose_expect;
593 
594  std::map<std::string, double> ik_seed;
595 
596  // compute the ik
597  std::map<std::string, double> ik_actual;
598  EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, "WrongLink", pose_expect,
599  frame_id, ik_seed, ik_actual, false));
600 }
601 
607 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKInvalidFrameId)
608 {
609  Eigen::Isometry3d pose_expect;
610 
611  std::map<std::string, double> ik_seed;
612 
613  // compute the ik
614  std::map<std::string, double> ik_actual;
615  EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect,
616  "InvalidFrameId", ik_seed, ik_actual, false));
617 }
618 
619 // /**
620 // * @brief Test if activated self collision for a pose that would be in self
621 // * collision without the check results in a
622 // * valid ik solution.
623 // */
624 // TEST_F(TrajectoryFunctionsTestOnlyGripper, testComputePoseIKSelfCollisionForValidPosition)
625 // {
626 // const std::string frame_id = robot_model_->getModelFrame();
627 // const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
628 //
629 // // create seed
630 // std::vector<double> ik_seed_states = { -0.553, 0.956, 1.758, 0.146, -1.059, 1.247 };
631 // auto joint_names = jmg->getActiveJointModelNames();
632 //
633 // std::map<std::string, double> ik_seed;
634 // for (unsigned int i = 0; i < ik_seed_states.size(); ++i)
635 // {
636 // ik_seed[joint_names[i]] = ik_seed_states[i];
637 // }
638 //
639 // // create expected pose
640 // geometry_msgs::msg::Pose pose;
641 // pose.position.x = -0.454;
642 // pose.position.y = -0.15;
643 // pose.position.z = 0.431;
644 // pose.orientation.y = 0.991562;
645 // pose.orientation.w = -0.1296328;
646 // Eigen::Isometry3d pose_expect;
647 // normalizeQuaternion(pose.orientation);
648 // tf2::fromMsg(pose, pose_expect);
649 //
650 // // compute the ik without self collision check and expect the resulting pose
651 // // to be in self collision.
652 // std::map<std::string, double> ik_actual1;
653 // EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect,
654 // frame_id, ik_seed, ik_actual1, false));
655 //
656 // moveit::core::RobotState rstate(robot_model_);
657 // planning_scene::PlanningScene rscene(robot_model_);
658 //
659 // std::vector<double> ik_state;
660 // std::transform(ik_actual1.begin(), ik_actual1.end(), std::back_inserter(ik_state),
661 // [](const auto& pair) { return pair.second; });
662 //
663 // rstate.setJointGroupPositions(jmg, ik_state);
664 // rstate.update();
665 //
666 // collision_detection::CollisionRequest collision_req;
667 // collision_req.group_name = jmg->getName();
668 // collision_detection::CollisionResult collision_res;
669 //
670 // rscene.checkSelfCollision(collision_req, collision_res, rstate);
671 //
672 // EXPECT_TRUE(collision_res.collision);
673 //
674 // // compute the ik with collision detection activated and expect the resulting
675 // // pose to be without self collision.
676 // std::map<std::string, double> ik_actual2;
677 // EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(robot_model_, planning_group_, tcp_link_, pose_expect,
678 // frame_id, ik_seed, ik_actual2, true));
679 //
680 // std::vector<double> ik_state2;
681 // std::transform(ik_actual2.begin(), ik_actual2.end(), std::back_inserter(ik_state2),
682 // [](const auto& pair) { return pair.second; });
683 // rstate.setJointGroupPositions(jmg, ik_state2);
684 // rstate.update();
685 //
686 // collision_detection::CollisionResult collision_res2;
687 // rscene.checkSelfCollision(collision_req, collision_res2, rstate);
688 //
689 // EXPECT_FALSE(collision_res2.collision);
690 // }
691 
696 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testComputePoseIKSelfCollisionForInvalidPose)
697 {
698  // robot state
699  moveit::core::RobotState rstate(robot_model_);
700 
701  const std::string frame_id = robot_model_->getModelFrame();
702  const moveit::core::JointModelGroup* jmg = robot_model_->getJointModelGroup(planning_group_);
703 
704  // create seed
705  std::map<std::string, double> ik_seed;
706  for (const auto& joint_name : jmg->getActiveJointModelNames())
707  {
708  ik_seed[joint_name] = 0;
709  }
710 
711  // create goal
712  std::vector<double> ik_goal = { 0, 2.3, -2.3, 0, 0, 0 };
713 
714  rstate.setJointGroupPositions(jmg, ik_goal);
715 
716  Eigen::Isometry3d pose_expect = rstate.getFrameTransform(tcp_link_);
717 
718  // compute the ik with disabled collision check
719  std::map<std::string, double> ik_actual;
720  EXPECT_TRUE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect,
721  frame_id, ik_seed, ik_actual, false));
722 
723  // compute the ik with enabled collision check
724  EXPECT_FALSE(pilz_industrial_motion_planner::computePoseIK(planning_scene_, planning_group_, tcp_link_, pose_expect,
725  frame_id, ik_seed, ik_actual, true));
726 }
727 
738 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testVerifySampleJointLimitsWithSmallDuration)
739 {
740  const std::map<std::string, double> position_last, velocity_last, position_current;
741  double duration_last{ 0.0 };
743 
744  double duration_current = 10e-7;
745 
746  EXPECT_FALSE(pilz_industrial_motion_planner::verifySampleJointLimits(position_last, velocity_last, position_current,
747  duration_last, duration_current, joint_limits));
748 }
749 
760 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testVerifySampleJointLimitsVelocityViolation)
761 {
762  const std::string test_joint_name{ "joint" };
763 
764  std::map<std::string, double> position_last{ { test_joint_name, 2.0 } };
765  std::map<std::string, double> position_current{ { test_joint_name, 10.0 } };
766  std::map<std::string, double> velocity_last;
767  double duration_current{ 1.0 };
768  double duration_last{ 0.0 };
770 
772  // Calculate the max allowed velocity in such a way that it is always smaller
773  // than the current velocity.
774  test_joint_limits.max_velocity =
775  ((position_current.at(test_joint_name) - position_last.at(test_joint_name)) / duration_current) - 1.0;
776  test_joint_limits.has_velocity_limits = true;
777  joint_limits.addLimit(test_joint_name, test_joint_limits);
778 
779  EXPECT_FALSE(pilz_industrial_motion_planner::verifySampleJointLimits(position_last, velocity_last, position_current,
780  duration_last, duration_current, joint_limits));
781 }
782 
793 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testVerifySampleJointLimitsAccelerationViolation)
794 {
795  const std::string test_joint_name{ "joint" };
796 
797  double duration_current = 1.0;
798  double duration_last = 1.0;
799 
800  std::map<std::string, double> position_last{ { test_joint_name, 2.0 } };
801  std::map<std::string, double> position_current{ { test_joint_name, 20.0 } };
802  double velocity_current =
803  ((position_current.at(test_joint_name) - position_last.at(test_joint_name)) / duration_current);
804  std::map<std::string, double> velocity_last{ { test_joint_name, 9.0 } };
806 
808  // Calculate the max allowed velocity in such a way that it is always bigger
809  // than the current velocity.
810  test_joint_limits.max_velocity = velocity_current + 1.0;
811  test_joint_limits.has_velocity_limits = true;
812 
813  double acceleration_current =
814  (velocity_current - velocity_last.at(test_joint_name)) / (duration_last + duration_current) * 2;
815  // Calculate the max allowed acceleration in such a way that it is always
816  // smaller than the current acceleration.
817  test_joint_limits.max_acceleration = acceleration_current - 1.0;
818  test_joint_limits.has_acceleration_limits = true;
819 
820  joint_limits.addLimit(test_joint_name, test_joint_limits);
821 
822  EXPECT_FALSE(pilz_industrial_motion_planner::verifySampleJointLimits(position_last, velocity_last, position_current,
823  duration_last, duration_current, joint_limits));
824 }
825 
836 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testVerifySampleJointLimitsDecelerationViolation)
837 {
838  const std::string test_joint_name{ "joint" };
839 
840  double duration_current = 1.0;
841  double duration_last = 1.0;
842 
843  std::map<std::string, double> position_last{ { test_joint_name, 20.0 } };
844  std::map<std::string, double> position_current{ { test_joint_name, 2.0 } };
845  double velocity_current =
846  ((position_current.at(test_joint_name) - position_last.at(test_joint_name)) / duration_current);
847  std::map<std::string, double> velocity_last{ { test_joint_name, 19.0 } };
849 
851  // Calculate the max allowed velocity in such a way that it is always bigger
852  // than the current velocity.
853  test_joint_limits.max_velocity = fabs(velocity_current) + 1.0;
854  test_joint_limits.has_velocity_limits = true;
855 
856  double acceleration_current =
857  (velocity_current - velocity_last.at(test_joint_name)) / (duration_last + duration_current) * 2;
858  // Calculate the max allowed deceleration in such a way that it is always
859  // bigger than the current acceleration.
860  test_joint_limits.max_deceleration = acceleration_current + 1.0;
861  test_joint_limits.has_deceleration_limits = true;
862 
863  joint_limits.addLimit(test_joint_name, test_joint_limits);
864 
865  EXPECT_FALSE(pilz_industrial_motion_planner::verifySampleJointLimits(position_last, velocity_last, position_current,
866  duration_last, duration_current, joint_limits));
867 }
868 
883 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testGenerateJointTrajectoryWithInvalidCartesianTrajectory)
884 {
885  // Create random test trajectory
886  // Note: 'path' is deleted by KDL::Trajectory_Segment
887  KDL::Path_RoundedComposite* path =
888  new KDL::Path_RoundedComposite(0.2, 0.01, new KDL::RotationalInterpolation_SingleAxis());
889  path->Add(KDL::Frame(KDL::Rotation::RPY(0, 0, 0), KDL::Vector(-1, 0, 0)));
890  path->Finish();
891  // Note: 'velprof' is deleted by KDL::Trajectory_Segment
892  KDL::VelocityProfile* vel_prof = new KDL::VelocityProfile_Trap(0.5, 0.1);
893  vel_prof->SetProfile(0, path->PathLength());
894  KDL::Trajectory_Segment kdl_trajectory(path, vel_prof);
895 
897  std::string group_name{ "invalid_group_name" };
898  std::map<std::string, double> initial_joint_position;
899  double sampling_time{ 0.1 };
900  trajectory_msgs::msg::JointTrajectory joint_trajectory;
901  moveit_msgs::msg::MoveItErrorCodes error_code;
902  bool check_self_collision{ false };
903 
905  planning_scene_, joint_limits, kdl_trajectory, group_name, tcp_link_, initial_joint_position, sampling_time,
906  joint_trajectory, error_code, check_self_collision));
907 
908  std::map<std::string, double> initial_joint_velocity;
909 
911  cart_traj.group_name = group_name;
912  cart_traj.link_name = tcp_link_;
914  cart_traj.points.push_back(cart_traj_point);
915 
917  planning_scene_, joint_limits, cart_traj, group_name, tcp_link_, initial_joint_position, initial_joint_velocity,
918  joint_trajectory, error_code, check_self_collision));
919 }
920 
932 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testDetermineAndCheckSamplingTimeInvalidVectorSize)
933 {
934  robot_trajectory::RobotTrajectoryPtr first_trajectory =
935  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
936  robot_trajectory::RobotTrajectoryPtr second_trajectory =
937  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
938  double epsilon{ 0.0 };
939  double sampling_time{ 0.0 };
940 
941  moveit::core::RobotState rstate(robot_model_);
942  first_trajectory->insertWayPoint(0, rstate, 0.1);
943  second_trajectory->insertWayPoint(0, rstate, 0.1);
944 
945  EXPECT_FALSE(pilz_industrial_motion_planner::determineAndCheckSamplingTime(first_trajectory, second_trajectory,
946  epsilon, sampling_time));
947 }
948 
960 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testDetermineAndCheckSamplingTimeCorrectSamplingTime)
961 {
962  robot_trajectory::RobotTrajectoryPtr first_trajectory =
963  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
964  robot_trajectory::RobotTrajectoryPtr second_trajectory =
965  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
966  double epsilon{ 0.0001 };
967  double sampling_time{ 0.0 };
968  double expected_sampling_time{ 0.1 };
969 
970  moveit::core::RobotState rstate(robot_model_);
971  first_trajectory->insertWayPoint(0, rstate, expected_sampling_time);
972  first_trajectory->insertWayPoint(1, rstate, expected_sampling_time);
973 
974  second_trajectory->insertWayPoint(0, rstate, expected_sampling_time);
975  second_trajectory->insertWayPoint(1, rstate, expected_sampling_time);
976  second_trajectory->insertWayPoint(2, rstate, expected_sampling_time);
977 
978  EXPECT_TRUE(pilz_industrial_motion_planner::determineAndCheckSamplingTime(first_trajectory, second_trajectory,
979  epsilon, sampling_time));
980  EXPECT_EQ(expected_sampling_time, sampling_time);
981 }
982 
994 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testDetermineAndCheckSamplingTimeViolateSamplingTime)
995 {
996  robot_trajectory::RobotTrajectoryPtr first_trajectory =
997  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
998  robot_trajectory::RobotTrajectoryPtr second_trajectory =
999  std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
1000  double epsilon{ 0.0001 };
1001  double sampling_time{ 0.0 };
1002  double expected_sampling_time{ 0.1 };
1003 
1004  moveit::core::RobotState rstate(robot_model_);
1005  first_trajectory->insertWayPoint(0, rstate, expected_sampling_time);
1006  first_trajectory->insertWayPoint(1, rstate, expected_sampling_time);
1007  first_trajectory->insertWayPoint(2, rstate, expected_sampling_time);
1008  // Violate sampling time
1009  first_trajectory->insertWayPoint(2, rstate, expected_sampling_time + 1.0);
1010  first_trajectory->insertWayPoint(3, rstate, expected_sampling_time);
1011 
1012  second_trajectory->insertWayPoint(0, rstate, expected_sampling_time);
1013  second_trajectory->insertWayPoint(1, rstate, expected_sampling_time);
1014  second_trajectory->insertWayPoint(2, rstate, expected_sampling_time);
1015  second_trajectory->insertWayPoint(3, rstate, expected_sampling_time);
1016 
1017  EXPECT_FALSE(pilz_industrial_motion_planner::determineAndCheckSamplingTime(first_trajectory, second_trajectory,
1018  epsilon, sampling_time));
1019  EXPECT_EQ(expected_sampling_time, sampling_time);
1020 }
1021 
1033 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIsRobotStateEqualPositionUnequal)
1034 {
1035  moveit::core::RobotState rstate_1 = moveit::core::RobotState(robot_model_);
1036  moveit::core::RobotState rstate_2 = moveit::core::RobotState(robot_model_);
1037 
1038  double default_joint_position[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1039  rstate_1.setJointGroupPositions(planning_group_, default_joint_position);
1040  // Ensure that the joint positions of both robot states are different
1041  default_joint_position[0] = default_joint_position[0] + 70.0;
1042  rstate_2.setJointGroupPositions(planning_group_, default_joint_position);
1043 
1044  double epsilon{ 0.0001 };
1045  EXPECT_FALSE(pilz_industrial_motion_planner::isRobotStateEqual(rstate_1, rstate_2, planning_group_, epsilon));
1046 }
1047 
1059 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIsRobotStateEqualVelocityUnequal)
1060 {
1061  moveit::core::RobotState rstate_1 = moveit::core::RobotState(robot_model_);
1062  moveit::core::RobotState rstate_2 = moveit::core::RobotState(robot_model_);
1063 
1064  // Ensure that the joint positions of both robot state are equal
1065  double default_joint_position[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1066  rstate_1.setJointGroupPositions(planning_group_, default_joint_position);
1067  rstate_2.setJointGroupPositions(planning_group_, default_joint_position);
1068 
1069  double default_joint_velocity[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1070  rstate_1.setJointGroupVelocities(planning_group_, default_joint_velocity);
1071  // Ensure that the joint velocites of both robot states are different
1072  default_joint_velocity[1] = default_joint_velocity[1] + 10.0;
1073  rstate_2.setJointGroupVelocities(planning_group_, default_joint_velocity);
1074 
1075  double epsilon{ 0.0001 };
1076  EXPECT_FALSE(pilz_industrial_motion_planner::isRobotStateEqual(rstate_1, rstate_2, planning_group_, epsilon));
1077 }
1078 
1090 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIsRobotStateEqualAccelerationUnequal)
1091 {
1092  moveit::core::RobotState rstate_1 = moveit::core::RobotState(robot_model_);
1093  moveit::core::RobotState rstate_2 = moveit::core::RobotState(robot_model_);
1094 
1095  // Ensure that the joint positions of both robot state are equal
1096  double default_joint_position[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1097  rstate_1.setJointGroupPositions(planning_group_, default_joint_position);
1098  rstate_2.setJointGroupPositions(planning_group_, default_joint_position);
1099 
1100  // Ensure that the joint velocities of both robot state are equal
1101  double default_joint_velocity[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1102  rstate_1.setJointGroupVelocities(planning_group_, default_joint_velocity);
1103  rstate_2.setJointGroupVelocities(planning_group_, default_joint_velocity);
1104 
1105  double default_joint_acceleration[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1106  rstate_1.setJointGroupAccelerations(planning_group_, default_joint_acceleration);
1107  // Ensure that the joint accelerations of both robot states are different
1108  default_joint_acceleration[1] = default_joint_acceleration[1] + 10.0;
1109  rstate_2.setJointGroupAccelerations(planning_group_, default_joint_acceleration);
1110 
1111  double epsilon{ 0.0001 };
1112  EXPECT_FALSE(pilz_industrial_motion_planner::isRobotStateEqual(rstate_1, rstate_2, planning_group_, epsilon));
1113 }
1114 
1126 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIsRobotStateStationaryVelocityUnequal)
1127 {
1128  moveit::core::RobotState rstate_1 = moveit::core::RobotState(robot_model_);
1129 
1130  // Ensure that the joint velocities are NOT zero
1131  double default_joint_velocity[6] = { 1.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1132  rstate_1.setJointGroupVelocities(planning_group_, default_joint_velocity);
1133 
1134  double epsilon{ 0.0001 };
1135  EXPECT_FALSE(pilz_industrial_motion_planner::isRobotStateStationary(rstate_1, planning_group_, epsilon));
1136 }
1137 
1149 TEST_F(TrajectoryFunctionsTestFlangeAndGripper, testIsRobotStateStationaryAccelerationUnequal)
1150 {
1151  moveit::core::RobotState rstate_1 = moveit::core::RobotState(robot_model_);
1152 
1153  // Ensure that the joint velocities are zero
1154  double default_joint_velocity[6] = { 0.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1155  rstate_1.setJointGroupVelocities(planning_group_, default_joint_velocity);
1156 
1157  // Ensure that the joint acceleration are NOT zero
1158  double default_joint_acceleration[6] = { 1.0, 0.0, 0.0, 0.0, 0.0, 0.0 };
1159  rstate_1.setJointGroupAccelerations(planning_group_, default_joint_acceleration);
1160 
1161  double epsilon{ 0.0001 };
1162  EXPECT_FALSE(pilz_industrial_motion_planner::isRobotStateStationary(rstate_1, planning_group_, epsilon));
1163 }
1164 
1165 int main(int argc, char** argv)
1166 {
1167  rclcpp::init(argc, argv);
1168  testing::InitGoogleTest(&argc, argv);
1169  return RUN_ALL_TESTS();
1170 }
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
std::vector< double > getJoints(const moveit::core::JointModelGroup *jmg, const moveit::core::RobotState &state)
get the current joint values of the robot state
void SetUp() override
Create test scenario for trajectory functions.
random_numbers::RandomNumberGenerator rng_
void attachToLink(moveit::core::RobotState &state, const moveit::core::LinkModel *link, const std::string &object_name, const Eigen::Isometry3d &object_pose, const moveit::core::FixedTransformsMap &subframes)
attach a collision object and subframes to a link
moveit::core::RobotModelConstPtr robot_model_
std::map< std::string, double > zero_state_
planning_scene::PlanningSceneConstPtr planning_scene_
bool tfNear(const Eigen::Isometry3d &pose1, const Eigen::Isometry3d &pose2, double epsilon)
check if two transformations are close
bool jointsNear(const std::vector< double > &joints1, const std::vector< double > &joints2, double epsilon)
check if two sets of joint positions are close
moveit::core::RobotStatePtr robot_state_
Parametrized class for tests with and without gripper.
const kinematics::KinematicsBaseConstPtr getSolverInstance() const
const std::vector< std::string > & getActiveJointModelNames() const
Get the names of the active joints in this group. These are the names of the joints returned by getJo...
A link from the robot. Contains the constant transform applied to the link and its geometry.
Definition: link_model.hpp:72
Representation of a robot's state. This includes position, velocity, acceleration and effort.
Definition: robot_state.hpp:90
void setVariablePositions(const double *position)
It is assumed positions is an array containing the new positions for all variables in this state....
void attachBody(std::unique_ptr< AttachedBody > attached_body)
Add an attached body to this state.
void setJointGroupAccelerations(const std::string &joint_group_name, const double *gstate)
Given accelerations for the variables that make up a group, in the order found in the group (includin...
void setJointGroupVelocities(const std::string &joint_group_name, const double *gstate)
Given velocities for the variables that make up a group, in the order found in the group (including v...
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...
const Eigen::Isometry3d & getFrameTransform(const std::string &frame_id, bool *frame_found=nullptr)
Get the transformation matrix from the model frame (root of model) to the frame identified by frame_i...
void setToRandomPositions()
Set all joints to random values. Values will be within default bounds.
double getVariablePosition(const std::string &variable) const
Get the position of a particular variable. An exception is thrown if the variable is not known.
void update(bool force=false)
Update all transforms.
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
bool setFromIK(const JointModelGroup *group, const geometry_msgs::msg::Pose &pose, double timeout=0.0, const GroupStateValidityCallbackFn &constraint=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
If the group this state corresponds to is a chain and a solver is available, then the joint values ca...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
std::map< std::string, Eigen::Isometry3d, std::less< std::string >, Eigen::aligned_allocator< std::pair< const std::string, Eigen::Isometry3d > > > FixedTransformsMap
Map frame names to the transformation matrix that can transform objects from the frame name to the pl...
Definition: transforms.hpp:53
bool computeLinkFK(moveit::core::RobotState &robot_state, const std::string &link_name, const std::map< std::string, double > &joint_state, Eigen::Isometry3d &pose)
compute the pose of a link at a given robot state
bool isRobotStateStationary(const moveit::core::RobotState &state, const std::string &group, double EPSILON)
check if the robot state have zero velocity/acceleration
bool determineAndCheckSamplingTime(const robot_trajectory::RobotTrajectoryPtr &first_trajectory, const robot_trajectory::RobotTrajectoryPtr &second_trajectory, double EPSILON, double &sampling_time)
Determines the sampling time and checks that both trajectroies use the same sampling time.
bool verifySampleJointLimits(const std::map< std::string, double > &position_last, const std::map< std::string, double > &velocity_last, const std::map< std::string, double > &position_current, double duration_last, double duration_current, const JointLimitsContainer &joint_limits)
verify the velocity/acceleration limits of current sample (based on backward difference computation) ...
bool generateJointTrajectory(const planning_scene::PlanningSceneConstPtr &scene, const JointLimitsContainer &joint_limits, const KDL::Trajectory &trajectory, const std::string &group_name, const std::string &link_name, const std::map< std::string, double > &initial_joint_position, double sampling_time, trajectory_msgs::msg::JointTrajectory &joint_trajectory, moveit_msgs::msg::MoveItErrorCodes &error_code, bool check_self_collision=false)
Generate joint trajectory from a KDL Cartesian trajectory.
bool computePoseIK(const planning_scene::PlanningSceneConstPtr &scene, const std::string &group_name, const std::string &link_name, const Eigen::Isometry3d &pose, const std::string &frame_id, const std::map< std::string, double > &seed, std::map< std::string, double > &solution, bool check_self_collision=true, const double timeout=0.0)
compute the inverse kinematics of a given pose, also check robot self collision
bool isRobotStateEqual(const moveit::core::RobotState &state1, const moveit::core::RobotState &state2, const std::string &joint_group_name, double epsilon)
Check if the two robot states have the same joint position/velocity/acceleration.
name
Definition: setup.py:7
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
A set of options for the kinematics solver.
std::vector< CartesianTrajectoryPoint > points
Extends joint_limits_interface::JointLimits with a deceleration parameter.
const std::string PARAM_PLANNING_GROUP_NAME("planning_group")
const std::string RANDOM_TEST_NUMBER("random_test_number")
int main(int argc, char **argv)
const std::string IK_FAST_LINK_NAME("ik_fast_link")
TEST_F(TrajectoryFunctionsTestFlangeAndGripper, TipLinkFK)
Test the forward kinematics function with simple robot poses for robot tip link using robot model wit...
const std::string ROBOT_TCP_LINK_NAME("tcp_link")
const std::string GROUP_TIP_LINK_NAME("group_tip_link")