moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_trajectory_generator_circ.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 <memory>
36 
37 #include <gtest/gtest.h>
38 
43 #include <tf2_eigen/tf2_eigen.hpp>
44 #include <tf2_geometry_msgs/tf2_geometry_msgs.hpp>
45 
50 #include "test_utils.hpp"
51 
52 #include <rclcpp/rclcpp.hpp>
53 
54 using namespace pilz_industrial_motion_planner;
56 
57 static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
58 
59 class TrajectoryGeneratorCIRCTest : public testing::Test
60 {
61 protected:
66  void SetUp() override
67  {
68  rclcpp::NodeOptions node_options;
69  node_options.automatically_declare_parameters_from_overrides(true);
70  node_ = rclcpp::Node::make_shared("unittest_trajectory_generator_circ", node_options);
71 
72  // load robot model
73  rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
74  robot_model_ = rm_loader_->getModel();
75  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
76  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
77 
78  // get parameters
79  ASSERT_TRUE(node_->has_parameter("testdata_file_name"));
80  node_->get_parameter<std::string>("testdata_file_name", test_data_file_name_);
81  ASSERT_TRUE(node_->has_parameter("planning_group"));
82  node_->get_parameter<std::string>("planning_group", planning_group_);
83  ASSERT_TRUE(node_->has_parameter("target_link"));
84  node_->get_parameter<std::string>("target_link", target_link_);
85  ASSERT_TRUE(node_->has_parameter("cartesian_position_tolerance"));
86  node_->get_parameter<double>("cartesian_position_tolerance", cartesian_position_tolerance_);
87  ASSERT_TRUE(node_->has_parameter("angular_acc_tolerance"));
88  node_->get_parameter<double>("angular_acc_tolerance", angular_acc_tolerance_);
89  ASSERT_TRUE(node_->has_parameter("rot_axis_norm_tolerance"));
90  node_->get_parameter<double>("rot_axis_norm_tolerance", rot_axis_norm_tolerance_);
91  ASSERT_TRUE(node_->has_parameter("acceleration_tolerance"));
92  node_->get_parameter<double>("acceleration_tolerance", acceleration_tolerance_);
93  ASSERT_TRUE(node_->has_parameter("other_tolerance"));
94  node_->get_parameter<double>("other_tolerance", other_tolerance_);
95 
96  // check robot model
97  testutils::checkRobotModel(robot_model_, planning_group_, target_link_);
98 
99  // load the test data provider
100  tdp_ = std::make_unique<pilz_industrial_motion_planner_testutils::XmlTestdataLoader>(test_data_file_name_);
101  ASSERT_NE(nullptr, tdp_) << "Failed to load test data by provider.";
102 
103  tdp_->setRobotModel(robot_model_);
104 
105  // create the limits container
108  node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
109 
110  // Cartesian limits are chose as such values to ease the manually compute the
111  // trajectory
112  cartesian_limits::Params cartesian_limit;
113  cartesian_limit.max_trans_vel = 1.0 * M_PI;
114  cartesian_limit.max_trans_acc = 1.0 * M_PI;
115  cartesian_limit.max_trans_dec = 1.0 * M_PI;
116  cartesian_limit.max_rot_vel = 1.0 * M_PI;
117 
118  planner_limits_.setJointLimits(joint_limits);
119  planner_limits_.setCartesianLimits(cartesian_limit);
120 
121  // initialize the LIN trajectory generator
122  circ_ = std::make_unique<TrajectoryGeneratorCIRC>(robot_model_, planner_limits_, planning_group_);
123  ASSERT_NE(nullptr, circ_) << "failed to create CIRC trajectory generator";
124  }
125 
128  {
129  moveit_msgs::msg::MotionPlanResponse res_msg;
130  res.getMessage(res_msg);
131  EXPECT_TRUE(testutils::isGoalReached(res.trajectory->getFirstWayPointPtr()->getRobotModel(),
132  res_msg.trajectory.joint_trajectory, req, other_tolerance_));
133 
134  EXPECT_TRUE(
135  testutils::checkJointTrajectory(res_msg.trajectory.joint_trajectory, planner_limits_.getJointLimitContainer()));
136 
137  EXPECT_EQ(req.path_constraints.position_constraints.size(), 1u);
138  EXPECT_EQ(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.size(), 1u);
139 
140  // Check that all point have the equal distance to the center
141  Eigen::Vector3d circ_center;
142  getCircCenter(req, res, circ_center);
143 
144  for (std::size_t i = 0; i < res.trajectory->getWayPointCount(); ++i)
145  {
146  Eigen::Affine3d waypoint_pose = res.trajectory->getWayPointPtr(i)->getFrameTransform(target_link_);
147  EXPECT_NEAR(
148  (res.trajectory->getFirstWayPointPtr()->getFrameTransform(target_link_).translation() - circ_center).norm(),
149  (circ_center - waypoint_pose.translation()).norm(), cartesian_position_tolerance_);
150  }
151 
152  // check translational and rotational paths
153  ASSERT_TRUE(testutils::checkCartesianTranslationalPath(res.trajectory, target_link_, acceleration_tolerance_));
154  ASSERT_TRUE(testutils::checkCartesianRotationalPath(res.trajectory, target_link_, angular_acc_tolerance_,
155  rot_axis_norm_tolerance_));
156 
157  for (size_t idx = 0; idx < res.trajectory->getLastWayPointPtr()->getVariableCount(); ++idx)
158  {
159  EXPECT_NEAR(0.0, res.trajectory->getLastWayPointPtr()->getVariableVelocity(idx), other_tolerance_);
160  EXPECT_NEAR(0.0, res.trajectory->getLastWayPointPtr()->getVariableAcceleration(idx), other_tolerance_);
161  }
162  }
163 
164  void TearDown() override
165  {
166  robot_model_.reset();
167  }
168 
171  {
172  if (req.path_constraints.name == "center")
173  {
174  tf2::fromMsg(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position,
175  circ_center);
176  }
177  else if (req.path_constraints.name == "interim")
178  {
179  Eigen::Vector3d interim;
180  tf2::fromMsg(req.path_constraints.position_constraints.at(0).constraint_region.primitive_poses.at(0).position,
181  interim);
182  Eigen::Vector3d start = res.trajectory->getFirstWayPointPtr()->getFrameTransform(target_link_).translation();
183  Eigen::Vector3d goal = res.trajectory->getLastWayPointPtr()->getFrameTransform(target_link_).translation();
184 
185  const Eigen::Vector3d t = interim - start;
186  const Eigen::Vector3d u = goal - start;
187  const Eigen::Vector3d v = goal - interim;
188 
189  const Eigen::Vector3d w = t.cross(u);
190 
191  ASSERT_GT(w.norm(), 1e-8) << "Circle center not well defined for given start, interim and goal.";
192 
193  circ_center = start + (u * t.dot(t) * u.dot(v) - t * u.dot(u) * t.dot(v)) * 0.5 / pow(w.norm(), 2);
194  }
195  }
196 
197 protected:
198  // ros stuff
199  rclcpp::Node::SharedPtr node_;
200  moveit::core::RobotModelConstPtr robot_model_;
201  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
202  planning_scene::PlanningSceneConstPtr planning_scene_;
203 
204  std::unique_ptr<TrajectoryGeneratorCIRC> circ_;
205  // test data provider
206  std::unique_ptr<pilz_industrial_motion_planner_testutils::TestdataLoader> tdp_;
207 
208  // test parameters from parameter server
209  std::string planning_group_, target_link_, test_data_file_name_;
211  double cartesian_position_tolerance_, angular_acc_tolerance_, rot_axis_norm_tolerance_, acceleration_tolerance_,
214 };
215 
220 TEST_F(TrajectoryGeneratorCIRCTest, TestExceptionErrorCodeMapping)
221 {
222  {
223  auto cnp_ex = std::make_shared<CircleNoPlane>("");
224  EXPECT_EQ(cnp_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
225  }
226 
227  {
228  auto cts_ex = std::make_shared<CircleToSmall>("");
229  EXPECT_EQ(cts_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
230  }
231 
232  {
233  auto cpdr_ex = std::make_shared<CenterPointDifferentRadius>("");
234  EXPECT_EQ(cpdr_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
235  }
236 
237  {
238  auto ctcf_ex = std::make_shared<CircTrajectoryConversionFailure>("");
239  EXPECT_EQ(ctcf_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
240  }
241 
242  {
243  auto upcn_ex = std::make_shared<UnknownPathConstraintName>("");
244  EXPECT_EQ(upcn_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
245  }
246 
247  {
248  auto npc_ex = std::make_shared<NoPositionConstraints>("");
249  EXPECT_EQ(npc_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
250  }
251 
252  {
253  auto npp_ex = std::make_shared<NoPrimitivePose>("");
254  EXPECT_EQ(npp_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
255  }
256 
257  {
258  auto ulnoap_ex = std::make_shared<UnknownLinkNameOfAuxiliaryPoint>("");
259  EXPECT_EQ(ulnoap_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
260  }
261 
262  {
263  auto nocm_ex = std::make_shared<NumberOfConstraintsMismatch>("");
264  EXPECT_EQ(nocm_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
265  }
266 
267  {
268  auto cifgi_ex = std::make_shared<CircInverseForGoalIncalculable>("");
269  EXPECT_EQ(cifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
270  }
271 }
272 
276 TEST_F(TrajectoryGeneratorCIRCTest, nonZeroStartVelocity)
277 {
278  moveit_msgs::msg::MotionPlanRequest req{ tdp_->getCircJointCenterCart("circ1_center_2").toRequest() };
279 
280  // start state has non-zero velocity
281  req.start_state.joint_state.velocity.push_back(1.0);
283  circ_->generate(planning_scene_, req, res);
284  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
285  req.start_state.joint_state.velocity.clear();
286 }
287 
289 {
290  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
291 
293  circ_->generate(planning_scene_, circ.toRequest(), res);
294  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
295 }
296 
301 {
302  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
303 
304  circ.setVelocityScale(1.0);
306  circ_->generate(planning_scene_, circ.toRequest(), res);
307  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
308 }
309 
314 {
315  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
316 
317  circ.setAccelerationScale(1.0);
319  circ_->generate(planning_scene_, circ.toRequest(), res);
320  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
321 }
322 
327 TEST_F(TrajectoryGeneratorCIRCTest, samePointsWithCenter)
328 {
329  // Define auxiliary point and goal to be the same as the start
330  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
331  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
332  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
333  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
334  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
335  circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
336  circ.getGoalConfiguration().getPose().position.x -= 1e-8;
337  circ.getGoalConfiguration().getPose().position.y -= 1e-8;
338  circ.getGoalConfiguration().getPose().position.z -= 1e-8;
339 
341  circ_->generate(planning_scene_, circ.toRequest(), res);
342  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
343 }
344 
350 TEST_F(TrajectoryGeneratorCIRCTest, samePointsWithInterim)
351 {
352  // Define auxiliary point and goal to be the same as the start
353  auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
354  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
355  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
356  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
357  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
358  circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
359  circ.getGoalConfiguration().getPose().position.x -= 1e-8;
360  circ.getGoalConfiguration().getPose().position.y -= 1e-8;
361  circ.getGoalConfiguration().getPose().position.z -= 1e-8;
362 
364  circ_->generate(planning_scene_, circ.toRequest(), res);
365  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
366 }
367 
372 {
373  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
374 
375  planning_interface::MotionPlanRequest req = circ.toRequest();
376 
377  req.path_constraints.position_constraints.clear();
378 
380  circ_->generate(planning_scene_, req, res);
381  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
382 }
383 
388 {
389  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
390 
391  planning_interface::MotionPlanRequest req = circ.toRequest();
392 
393  req.path_constraints.name = "";
394 
396  circ_->generate(planning_scene_, req, res);
397  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
398 }
399 
405 {
406  auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
407 
408  planning_interface::MotionPlanRequest req = circ.toRequest();
409 
410  req.path_constraints.position_constraints.front().link_name = "INVALID";
411 
413  circ_->generate(planning_scene_, req, res);
414  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
415 }
416 
421 {
422  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
423  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
424  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1;
425 
427  circ_->generate(planning_scene_, circ.toRequest(), res);
428  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
429 }
430 
437 {
438  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
439  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
440  circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
441 
442  // Stretch start and goal pose along line
443  circ.getStartConfiguration().getPose().position.x -= 0.1;
444  circ.getGoalConfiguration().getPose().position.x += 0.1;
445 
447  circ_->generate(planning_scene_, circ.toRequest(), res);
448  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
449 }
450 
458 {
459  auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
460  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
461  circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
462 
463  // Stretch start and goal pose along line
464  circ.getStartConfiguration().getPose().position.x -= 0.1;
465  circ.getGoalConfiguration().getPose().position.x += 0.1;
466 
468  circ_->generate(planning_scene_, circ.toRequest(), res);
469  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
470 }
471 
480 TEST_F(TrajectoryGeneratorCIRCTest, colinearCenterDueToInterim)
481 {
482  // get the test data from xml
483  auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
484 
486  circ_->generate(planning_scene_, circ.toRequest(), res);
487  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
488 }
489 
500 TEST_F(TrajectoryGeneratorCIRCTest, colinearCenterAndInterim)
501 {
502  auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
503 
504  // alter start, interim and goal such that start/center and interim are
505  // colinear
506  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
507  circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
508 
509  circ.getStartConfiguration().getPose().position.x -= 0.2;
510  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.2;
511  circ.getGoalConfiguration().getPose().position.y -= 0.2;
512 
513  circ.setAccelerationScale(0.05);
514  circ.setVelocityScale(0.05);
515 
516  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
517 
519  circ_->generate(planning_scene_, req, res);
520  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
521  checkCircResult(req, res);
522 }
523 
533 TEST_F(TrajectoryGeneratorCIRCTest, interimLarger180Degree)
534 {
535  auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
536 
537  // alter start, interim and goal such that start/center and interim are
538  // colinear
539  circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
540  circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
541 
542  circ.getStartConfiguration().getPose().position.x -= 0.2;
543  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.14142136;
544  circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y -= 0.14142136;
545  circ.getGoalConfiguration().getPose().position.y -= 0.2;
546 
547  circ.setAccelerationScale(0.05);
548  circ.setVelocityScale(0.05);
549 
550  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
551 
553  circ_->generate(planning_scene_, req, res);
554  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
555  checkCircResult(req, res);
556 }
557 
561 TEST_F(TrajectoryGeneratorCIRCTest, centerPointJointGoal)
562 {
563  auto circ{ tdp_->getCircJointCenterCart("circ1_center_2") };
564  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
565 
567  circ_->generate(planning_scene_, req, res);
568  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
569  checkCircResult(req, res);
570 }
571 
577 TEST_F(TrajectoryGeneratorCIRCTest, InvalidAdditionalPrimitivePose)
578 {
579  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
580 
581  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
582 
583  // Contains one pose (interim / center)
584  ASSERT_EQ(req.path_constraints.position_constraints.back().constraint_region.primitive_poses.size(), 1u);
585 
586  // Define a additional pose here
587  geometry_msgs::msg::Pose center_position;
588  center_position.position.x = 0.0;
589  center_position.position.y = 0.0;
590  center_position.position.z = 0.65;
591  req.path_constraints.position_constraints.back().constraint_region.primitive_poses.push_back(center_position);
592 
594  circ_->generate(planning_scene_, req, res);
595  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
596 }
597 
604 TEST_F(TrajectoryGeneratorCIRCTest, InvalidExtraJointConstraint)
605 {
606  auto circ{ tdp_->getCircJointCenterCart("circ1_center_2") };
607 
608  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
609 
610  // Define the additional joint constraint
611  moveit_msgs::msg::JointConstraint joint_constraint;
612  joint_constraint.joint_name = req.goal_constraints.front().joint_constraints.front().joint_name;
613  req.goal_constraints.front().joint_constraints.push_back(joint_constraint); //<-- Additional constraint
614 
616  circ_->generate(planning_scene_, req, res);
617  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
618 }
619 
623 TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoal)
624 {
625  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
626 
627  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
628 
630  circ_->generate(planning_scene_, req, res);
631  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
632  checkCircResult(req, res);
633 }
634 
638 TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdPositionConstraints)
639 {
640  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
641 
642  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
643 
644  req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
645 
647  circ_->generate(planning_scene_, req, res);
648  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
649  checkCircResult(req, res);
650 }
651 
655 TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdOrientationConstraints)
656 {
657  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
658 
659  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
660  req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
661 
663  circ_->generate(planning_scene_, req, res);
664  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
665  checkCircResult(req, res);
666 }
667 
671 TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdBothConstraints)
672 {
673  auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
674 
675  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
676 
677  // Both set
678  req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
679  req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
680 
682  circ_->generate(planning_scene_, req, res);
683  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
684  checkCircResult(req, res);
685 }
686 
690 TEST_F(TrajectoryGeneratorCIRCTest, InterimPointJointGoal)
691 {
692  auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
693 
694  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
695 
697  circ_->generate(planning_scene_, req, res);
698  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
699  checkCircResult(req, res);
700 }
701 
708 TEST_F(TrajectoryGeneratorCIRCTest, InterimPointJointGoalStartVelNearZero)
709 {
710  auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
711 
712  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
713 
714  // Set velocity near zero
715  req.start_state.joint_state.velocity = std::vector<double>(req.start_state.joint_state.position.size(), 1e-16);
716 
718  circ_->generate(planning_scene_, req, res);
719  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
720  checkCircResult(req, res);
721 }
722 
726 TEST_F(TrajectoryGeneratorCIRCTest, InterimPointPoseGoal)
727 {
728  auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
729  moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
730 
732  circ_->generate(planning_scene_, req, res);
733  EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
734  checkCircResult(req, res);
735 }
736 
737 int main(int argc, char** argv)
738 {
739  rclcpp::init(argc, argv);
740  testing::InitGoogleTest(&argc, argv);
741  return RUN_ALL_TESTS();
742 }
void SetUp() override
Create test scenario for circ trajectory generator.
std::unique_ptr< TrajectoryGeneratorCIRC > circ_
std::unique_ptr< pilz_industrial_motion_planner_testutils::TestdataLoader > tdp_
void getCircCenter(const planning_interface::MotionPlanRequest &req, const planning_interface::MotionPlanResponse &res, Eigen::Vector3d &circ_center)
moveit::core::RobotModelConstPtr robot_model_
void checkCircResult(const planning_interface::MotionPlanRequest &req, const planning_interface::MotionPlanResponse &res)
planning_scene::PlanningSceneConstPtr planning_scene_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
static JointLimitsContainer getAggregatedLimits(const rclcpp::Node::SharedPtr &node, const std::string &param_namespace, const std::vector< const moveit::core::JointModel * > &joint_models)
Aggregates(combines) the joint limits from joint model and node parameters. The rules for the combina...
Container for JointLimits, essentially a map with convenience functions. Adds the ability to as for l...
This class combines CartesianLimit and JointLimits into on single class.
Vec3fX< details::Vec3Data< double > > Vector3d
Definition: fcl_compat.hpp:89
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
bool isGoalReached(const trajectory_msgs::msg::JointTrajectory &trajectory, const std::vector< moveit_msgs::msg::JointConstraint > &goal, const double joint_position_tolerance, const double joint_velocity_tolerance=1.0e-6)
check if the goal given in joint space is reached Only the last point in the trajectory is verified.
Definition: test_utils.cpp:118
::testing::AssertionResult checkCartesianTranslationalPath(const robot_trajectory::RobotTrajectoryConstPtr &trajectory, const std::string &link_name, const double acc_tol=DEFAULT_ACCELERATION_EQUALITY_TOLERANCE)
Check that the translational path of a given trajectory has a trapezoid velocity profile.
bool checkJointTrajectory(const trajectory_msgs::msg::JointTrajectory &trajectory, const pilz_industrial_motion_planner::JointLimitsContainer &joint_limits)
check joint trajectory of consistency, position, velocity and acceleration limits
Definition: test_utils.cpp:460
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
::testing::AssertionResult checkCartesianRotationalPath(const robot_trajectory::RobotTrajectoryConstPtr &trajectory, const std::string &link_name, const double rot_axis_tol=DEFAULT_ROTATION_AXIS_EQUALITY_TOLERANCE, const double acc_tol=DEFAULT_ACCELERATION_EQUALITY_TOLERANCE)
Check that the rotational path of a given trajectory is a quaternion slerp.
moveit::core::MoveItErrorCode error_code
robot_trajectory::RobotTrajectoryPtr trajectory
void getMessage(moveit_msgs::msg::MotionPlanResponse &msg) const
Construct a ROS message from struct data.
int main(int argc, char **argv)
const std::string PARAM_NAMESPACE_LIMITS