moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
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.h"
51
52#include <rclcpp/rclcpp.hpp>
53
54using namespace pilz_industrial_motion_planner;
56
57static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
58
59class TrajectoryGeneratorCIRCTest : public testing::Test
60{
61protected:
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
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
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
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
170 const planning_interface::MotionPlanResponse& res, Eigen::Vector3d& circ_center)
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
197protected:
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
214};
215
220TEST_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 cjmiss_ex = std::make_shared<CircJointMissingInStartState>("");
269 EXPECT_EQ(cjmiss_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
270 }
271
272 {
273 auto cifgi_ex = std::make_shared<CircInverseForGoalIncalculable>("");
274 EXPECT_EQ(cifgi_ex->getErrorCode(), moveit_msgs::msg::MoveItErrorCodes::NO_IK_SOLUTION);
275 }
276}
277
283{
284 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
285
286 planning_interface::MotionPlanRequest req{ circ.toRequest() };
287 EXPECT_GT(req.start_state.joint_state.name.size(), 1u);
288 req.start_state.joint_state.name.resize(1);
289 req.start_state.joint_state.position.resize(1); // prevent failing check for equal sizes
290
292 circ_->generate(planning_scene_, req, res);
293 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
294}
295
300{
301 moveit_msgs::msg::MotionPlanRequest req{ tdp_->getCircJointCenterCart("circ1_center_2").toRequest() };
302
303 // start state has non-zero velocity
304 req.start_state.joint_state.velocity.push_back(1.0);
306 circ_->generate(planning_scene_, req, res);
307 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_ROBOT_STATE);
308 req.start_state.joint_state.velocity.clear();
309}
310
312{
313 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
314
316 circ_->generate(planning_scene_, circ.toRequest(), res);
317 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
318}
319
324{
325 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
326
327 circ.setVelocityScale(1.0);
329 circ_->generate(planning_scene_, circ.toRequest(), res);
330 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
331}
332
337{
338 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
339
340 circ.setAccelerationScale(1.0);
342 circ_->generate(planning_scene_, circ.toRequest(), res);
343 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::PLANNING_FAILED);
344}
345
351{
352 // Define auxiliary point and goal to be the same as the start
353 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
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
373TEST_F(TrajectoryGeneratorCIRCTest, samePointsWithInterim)
374{
375 // Define auxiliary point and goal to be the same as the start
376 auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
377 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
378 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 1e-8;
379 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1e-8;
380 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.z += 1e-8;
381 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
382 circ.getGoalConfiguration().getPose().position.x -= 1e-8;
383 circ.getGoalConfiguration().getPose().position.y -= 1e-8;
384 circ.getGoalConfiguration().getPose().position.z -= 1e-8;
385
387 circ_->generate(planning_scene_, circ.toRequest(), res);
388 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
389}
390
395{
396 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
397
398 planning_interface::MotionPlanRequest req = circ.toRequest();
399
400 req.path_constraints.position_constraints.clear();
401
403 circ_->generate(planning_scene_, req, res);
404 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
405}
406
411{
412 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
413
414 planning_interface::MotionPlanRequest req = circ.toRequest();
415
416 req.path_constraints.name = "";
417
419 circ_->generate(planning_scene_, req, res);
420 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
421}
422
428{
429 auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
430
431 planning_interface::MotionPlanRequest req = circ.toRequest();
432
433 req.path_constraints.position_constraints.front().link_name = "INVALID";
434
436 circ_->generate(planning_scene_, req, res);
437 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_LINK_NAME);
438}
439
444{
445 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
446 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
447 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y += 1;
448
450 circ_->generate(planning_scene_, circ.toRequest(), res);
451 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
452}
453
460{
461 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
462 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
463 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
464
465 // Stretch start and goal pose along line
466 circ.getStartConfiguration().getPose().position.x -= 0.1;
467 circ.getGoalConfiguration().getPose().position.x += 0.1;
468
470 circ_->generate(planning_scene_, circ.toRequest(), res);
471 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
472}
473
481{
482 auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
483 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
484 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
485
486 // Stretch start and goal pose along line
487 circ.getStartConfiguration().getPose().position.x -= 0.1;
488 circ.getGoalConfiguration().getPose().position.x += 0.1;
489
491 circ_->generate(planning_scene_, circ.toRequest(), res);
492 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
493}
494
503TEST_F(TrajectoryGeneratorCIRCTest, colinearCenterDueToInterim)
504{
505 // get the test data from xml
506 auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
507
509 circ_->generate(planning_scene_, circ.toRequest(), res);
510 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
511}
512
523TEST_F(TrajectoryGeneratorCIRCTest, colinearCenterAndInterim)
524{
525 auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
526
527 // alter start, interim and goal such that start/center and interim are
528 // colinear
529 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
530 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
531
532 circ.getStartConfiguration().getPose().position.x -= 0.2;
533 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.2;
534 circ.getGoalConfiguration().getPose().position.y -= 0.2;
535
536 circ.setAccelerationScale(0.05);
537 circ.setVelocityScale(0.05);
538
539 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
540
542 circ_->generate(planning_scene_, req, res);
543 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
544 checkCircResult(req, res);
545}
546
556TEST_F(TrajectoryGeneratorCIRCTest, interimLarger180Degree)
557{
558 auto circ{ tdp_->getCircCartInterimCart("circ3_interim") };
559
560 // alter start, interim and goal such that start/center and interim are
561 // colinear
562 circ.getAuxiliaryConfiguration().getConfiguration().setPose(circ.getStartConfiguration().getPose());
563 circ.getGoalConfiguration().setPose(circ.getStartConfiguration().getPose());
564
565 circ.getStartConfiguration().getPose().position.x -= 0.2;
566 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.x += 0.14142136;
567 circ.getAuxiliaryConfiguration().getConfiguration().getPose().position.y -= 0.14142136;
568 circ.getGoalConfiguration().getPose().position.y -= 0.2;
569
570 circ.setAccelerationScale(0.05);
571 circ.setVelocityScale(0.05);
572
573 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
574
576 circ_->generate(planning_scene_, req, res);
577 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
578 checkCircResult(req, res);
579}
580
585{
586 auto circ{ tdp_->getCircJointCenterCart("circ1_center_2") };
587 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
588
590 circ_->generate(planning_scene_, req, res);
591 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
592 checkCircResult(req, res);
593}
594
600TEST_F(TrajectoryGeneratorCIRCTest, InvalidAdditionalPrimitivePose)
601{
602 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
603
604 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
605
606 // Contains one pose (interim / center)
607 ASSERT_EQ(req.path_constraints.position_constraints.back().constraint_region.primitive_poses.size(), 1u);
608
609 // Define a additional pose here
610 geometry_msgs::msg::Pose center_position;
611 center_position.position.x = 0.0;
612 center_position.position.y = 0.0;
613 center_position.position.z = 0.65;
614 req.path_constraints.position_constraints.back().constraint_region.primitive_poses.push_back(center_position);
615
617 circ_->generate(planning_scene_, req, res);
618 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_MOTION_PLAN);
619}
620
627TEST_F(TrajectoryGeneratorCIRCTest, InvalidExtraJointConstraint)
628{
629 auto circ{ tdp_->getCircJointCenterCart("circ1_center_2") };
630
631 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
632
633 // Define the additional joint constraint
634 moveit_msgs::msg::JointConstraint joint_constraint;
635 joint_constraint.joint_name = req.goal_constraints.front().joint_constraints.front().joint_name;
636 req.goal_constraints.front().joint_constraints.push_back(joint_constraint); //<-- Additional constraint
637
639 circ_->generate(planning_scene_, req, res);
640 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::INVALID_GOAL_CONSTRAINTS);
641}
642
647{
648 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
649
650 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
651
653 circ_->generate(planning_scene_, req, res);
654 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
655 checkCircResult(req, res);
656}
657
661TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdPositionConstraints)
662{
663 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
664
665 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
666
667 req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
668
670 circ_->generate(planning_scene_, req, res);
671 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
672 checkCircResult(req, res);
673}
674
678TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdOrientationConstraints)
679{
680 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
681
682 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
683 req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
684
686 circ_->generate(planning_scene_, req, res);
687 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
688 checkCircResult(req, res);
689}
690
694TEST_F(TrajectoryGeneratorCIRCTest, CenterPointPoseGoalFrameIdBothConstraints)
695{
696 auto circ{ tdp_->getCircCartCenterCart("circ1_center_2") };
697
698 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
699
700 // Both set
701 req.goal_constraints.front().position_constraints.front().header.frame_id = robot_model_->getModelFrame();
702 req.goal_constraints.front().orientation_constraints.front().header.frame_id = robot_model_->getModelFrame();
703
705 circ_->generate(planning_scene_, req, res);
706 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
707 checkCircResult(req, res);
708}
709
713TEST_F(TrajectoryGeneratorCIRCTest, InterimPointJointGoal)
714{
715 auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
716
717 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
718
720 circ_->generate(planning_scene_, req, res);
721 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
722 checkCircResult(req, res);
723}
724
731TEST_F(TrajectoryGeneratorCIRCTest, InterimPointJointGoalStartVelNearZero)
732{
733 auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
734
735 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
736
737 // Set velocity near zero
738 req.start_state.joint_state.velocity = std::vector<double>(req.start_state.joint_state.position.size(), 1e-16);
739
741 circ_->generate(planning_scene_, req, res);
742 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
743 checkCircResult(req, res);
744}
745
750{
751 auto circ{ tdp_->getCircJointInterimCart("circ3_interim") };
752 moveit_msgs::msg::MotionPlanRequest req = circ.toRequest();
753
755 circ_->generate(planning_scene_, req, res);
756 EXPECT_EQ(res.error_code.val, moveit_msgs::msg::MoveItErrorCodes::SUCCESS);
757 checkCircResult(req, res);
758}
759
760int main(int argc, char** argv)
761{
762 rclcpp::init(argc, argv);
763 testing::InitGoogleTest(&argc, argv);
764 return RUN_ALL_TESTS();
765}
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.
void setCartesianLimits(cartesian_limits::Params &cartesian_limit)
Set cartesian limits.
void setJointLimits(JointLimitsContainer &joint_limits)
Set joint limits.
const JointLimitsContainer & getJointLimitContainer() const
Obtain the Joint Limits from the container.
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.
::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
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.
Response to a planning query.
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)