moveit2
The MoveIt Motion Planning Framework for ROS 2.
unittest_trajectory_blender_transition_window.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 
49 
55 #include "test_utils.h"
56 
57 #include <rclcpp/rclcpp.hpp>
58 
59 using namespace pilz_industrial_motion_planner;
61 
62 static const std::string PARAM_NAMESPACE_LIMITS = "robot_description_planning";
63 class TrajectoryBlenderTransitionWindowTest : public testing::Test
64 {
65 protected:
70  void SetUp() override
71  {
72  rclcpp::NodeOptions node_options;
73  node_options.automatically_declare_parameters_from_overrides(true);
74  node_ = rclcpp::Node::make_shared("unittest_trajectory_blender_transition_window", node_options);
75 
76  // load robot model
77  rm_loader_ = std::make_unique<robot_model_loader::RobotModelLoader>(node_);
78  robot_model_ = rm_loader_->getModel();
79  ASSERT_TRUE(bool(robot_model_)) << "Failed to load robot model";
80  planning_scene_ = std::make_shared<planning_scene::PlanningScene>(robot_model_);
81 
82  // get parameters
83  ASSERT_TRUE(node_->has_parameter("planning_group"));
84  node_->get_parameter<std::string>("planning_group", planning_group_);
85  ASSERT_TRUE(node_->has_parameter("target_link"));
86  node_->get_parameter<std::string>("target_link", target_link_);
87  ASSERT_TRUE(node_->has_parameter("cartesian_velocity_tolerance"));
88  node_->get_parameter<double>("cartesian_velocity_tolerance", cartesian_velocity_tolerance_);
89  ASSERT_TRUE(node_->has_parameter("cartesian_angular_velocity_tolerance"));
90  node_->get_parameter<double>("cartesian_angular_velocity_tolerance", cartesian_angular_velocity_tolerance_);
91  ASSERT_TRUE(node_->has_parameter("joint_velocity_tolerance"));
92  node_->get_parameter<double>("joint_velocity_tolerance", joint_velocity_tolerance_);
93  ASSERT_TRUE(node_->has_parameter("joint_acceleration_tolerance"));
94  node_->get_parameter<double>("joint_acceleration_tolerance", joint_acceleration_tolerance_);
95  ASSERT_TRUE(node_->has_parameter("sampling_time"));
96  node_->get_parameter<double>("sampling_time", sampling_time_);
97  ASSERT_TRUE(node_->has_parameter("testdata_file_name"));
98  node_->get_parameter<std::string>("testdata_file_name", test_data_file_name_);
99 
100  // load the test data provider
101  data_loader_ = std::make_unique<XmlTestdataLoader>(test_data_file_name_, robot_model_);
102  ASSERT_NE(nullptr, data_loader_) << "Failed to load test data by provider.";
103 
104  // check robot model
105  testutils::checkRobotModel(robot_model_, planning_group_, target_link_);
106 
107  // create the limits container
110  node_, PARAM_NAMESPACE_LIMITS, robot_model_->getActiveJointModels());
111  CartesianLimit cart_limits;
112  cart_limits.setMaxRotationalVelocity(1 * M_PI);
113  cart_limits.setMaxTranslationalAcceleration(2);
114  cart_limits.setMaxTranslationalDeceleration(2);
115  cart_limits.setMaxTranslationalVelocity(1);
116  planner_limits_.setJointLimits(joint_limits);
117  planner_limits_.setCartesianLimits(cart_limits);
118 
119  // initialize trajectory generators and blender
120  lin_generator_ = std::make_unique<TrajectoryGeneratorLIN>(robot_model_, planner_limits_, planning_group_);
121  ASSERT_NE(nullptr, lin_generator_) << "failed to create LIN trajectory generator";
122  blender_ = std::make_unique<TrajectoryBlenderTransitionWindow>(planner_limits_);
123  ASSERT_NE(nullptr, blender_) << "failed to create trajectory blender";
124  }
125 
126  void TearDown() override
127  {
128  robot_model_.reset();
129  }
130 
134  std::vector<planning_interface::MotionPlanResponse> generateLinTrajs(const Sequence& seq, size_t num_cmds)
135  {
136  std::vector<planning_interface::MotionPlanResponse> responses(num_cmds);
137  for (size_t index = 0; index < num_cmds; ++index)
138  {
139  planning_interface::MotionPlanRequest req{ seq.getCmd<LinCart>(index).toRequest() };
140  // Set start state of request to end state of previous trajectory (except
141  // for first)
142  if (index > 0)
143  {
144  moveit::core::robotStateToRobotStateMsg(responses[index - 1].trajectory_->getLastWayPoint(), req.start_state);
145  }
146  // generate trajectory
148  if (!lin_generator_->generate(planning_scene_, req, resp, sampling_time_))
149  {
150  std::runtime_error("Failed to generate trajectory.");
151  }
152  responses.at(index) = resp;
153  }
154  return responses;
155  }
156 
157 protected:
158  // ros stuff
159  rclcpp::Node::SharedPtr node_;
160  moveit::core::RobotModelConstPtr robot_model_;
161  std::unique_ptr<robot_model_loader::RobotModelLoader> rm_loader_;
162  planning_scene::PlanningSceneConstPtr planning_scene_;
163 
164  std::unique_ptr<TrajectoryGenerator> lin_generator_;
165  std::unique_ptr<TrajectoryBlenderTransitionWindow> blender_;
166 
167  // test parameters from parameter server
168  std::string planning_group_, target_link_;
169  double cartesian_velocity_tolerance_, cartesian_angular_velocity_tolerance_, joint_velocity_tolerance_,
172 
173  std::string test_data_file_name_;
175 };
176 
189 {
190  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
191 
192  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
193 
196 
197  blend_req.group_name = "invalid_group_name";
198  blend_req.link_name = target_link_;
199  blend_req.first_trajectory = res.at(0).trajectory_;
200  blend_req.second_trajectory = res.at(1).trajectory_;
201 
202  blend_req.blend_radius = seq.getBlendRadius(0);
203  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
204 }
205 
218 {
219  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
220 
221  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
222 
225 
226  blend_req.group_name = planning_group_;
227  blend_req.link_name = "invalid_target_link";
228  blend_req.first_trajectory = res.at(0).trajectory_;
229  blend_req.second_trajectory = res.at(1).trajectory_;
230 
231  blend_req.blend_radius = seq.getBlendRadius(0);
232  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
233 }
234 
248 {
249  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
250 
251  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
252 
255 
256  blend_req.group_name = planning_group_;
257  blend_req.link_name = target_link_;
258  blend_req.first_trajectory = res.at(0).trajectory_;
259  blend_req.second_trajectory = res.at(1).trajectory_;
260 
261  blend_req.blend_radius = -0.1;
262  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
263 }
264 
277 {
278  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
279 
280  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
281 
284 
285  blend_req.group_name = planning_group_;
286  blend_req.link_name = target_link_;
287  blend_req.first_trajectory = res.at(0).trajectory_;
288  blend_req.second_trajectory = res.at(1).trajectory_;
289 
290  blend_req.blend_radius = 0.;
291  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
292 }
293 
306 TEST_F(TrajectoryBlenderTransitionWindowTest, testDifferentSamplingTimes)
307 {
308  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
309 
310  // perform lin trajectory generation and modify sampling time
311  std::size_t num_cmds{ 2 };
312  std::vector<planning_interface::MotionPlanResponse> responses(num_cmds);
313 
314  for (size_t index = 0; index < num_cmds; ++index)
315  {
316  planning_interface::MotionPlanRequest req{ seq.getCmd<LinCart>(index).toRequest() };
317  // Set start state of request to end state of previous trajectory (except
318  // for first)
319  if (index > 0)
320  {
321  moveit::core::robotStateToRobotStateMsg(responses[index - 1].trajectory_->getLastWayPoint(), req.start_state);
322  sampling_time_ *= 2;
323  }
324  // generate trajectory
326  if (!lin_generator_->generate(planning_scene_, req, resp, sampling_time_))
327  {
328  std::runtime_error("Failed to generate trajectory.");
329  }
330  responses.at(index) = resp;
331  }
332 
335 
336  blend_req.group_name = planning_group_;
337  blend_req.link_name = target_link_;
338  blend_req.first_trajectory = responses[0].trajectory_;
339  blend_req.second_trajectory = responses[1].trajectory_;
340  blend_req.blend_radius = seq.getBlendRadius(0);
341  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
342 }
343 
358 TEST_F(TrajectoryBlenderTransitionWindowTest, testNonUniformSamplingTime)
359 {
360  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
361 
362  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
363 
364  // Modify first time interval
365  EXPECT_GT(res[0].trajectory_->getWayPointCount(), 2u);
366  res[0].trajectory_->setWayPointDurationFromPrevious(1, 2 * sampling_time_);
367 
370 
371  blend_req.group_name = planning_group_;
372  blend_req.link_name = target_link_;
373  blend_req.first_trajectory = res.at(0).trajectory_;
374  blend_req.second_trajectory = res.at(1).trajectory_;
375  blend_req.blend_radius = seq.getBlendRadius(0);
376  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
377 }
378 
392 TEST_F(TrajectoryBlenderTransitionWindowTest, testNotIntersectingTrajectories)
393 {
394  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
395 
396  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 1) };
397 
400 
401  blend_req.group_name = planning_group_;
402  blend_req.link_name = target_link_;
403  blend_req.first_trajectory = res.at(0).trajectory_;
404  // replace the second trajectory to make the two trajectories timely not
405  // intersect
406  blend_req.second_trajectory = res.at(0).trajectory_;
407  blend_req.blend_radius = seq.getBlendRadius(0);
408  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
409 }
410 
424 {
425  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
426 
427  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
428 
431 
432  blend_req.group_name = planning_group_;
433  blend_req.link_name = target_link_;
434  blend_req.blend_radius = seq.getBlendRadius(0);
435 
436  blend_req.first_trajectory = res.at(0).trajectory_;
437  blend_req.second_trajectory = res.at(1).trajectory_;
438 
439  // Modify last waypoint of first trajectory and first point of second
440  // trajectory
441  blend_req.first_trajectory->getLastWayPointPtr()->setVariableVelocity(0, 1.0);
442  blend_req.second_trajectory->getFirstWayPointPtr()->setVariableVelocity(0, 1.0);
443 
444  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
445 }
446 
460 TEST_F(TrajectoryBlenderTransitionWindowTest, testTraj1InsideBlendRadius)
461 {
462  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
463 
464  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
465 
466  double lin1_distance;
467  lin1_distance = (res[0].trajectory_->getFirstWayPoint().getFrameTransform(target_link_).translation() -
468  res[0].trajectory_->getLastWayPoint().getFrameTransform(target_link_).translation())
469  .norm();
470 
473 
474  blend_req.group_name = planning_group_;
475  blend_req.link_name = target_link_;
476  blend_req.blend_radius = 1.1 * lin1_distance;
477 
478  blend_req.first_trajectory = res.at(0).trajectory_;
479  blend_req.second_trajectory = res.at(1).trajectory_;
480 
481  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
482 }
483 
497 TEST_F(TrajectoryBlenderTransitionWindowTest, testTraj2InsideBlendRadius)
498 {
499  Sequence seq{ data_loader_->getSequence("NoIntersectionTraj2") };
500 
501  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
502 
505 
506  blend_req.group_name = planning_group_;
507  blend_req.link_name = target_link_;
508  blend_req.blend_radius = seq.getBlendRadius(0);
509 
510  blend_req.first_trajectory = res.at(0).trajectory_;
511  blend_req.second_trajectory = res.at(1).trajectory_;
512 
513  EXPECT_FALSE(blender_->blend(planning_scene_, blend_req, blend_res));
514 }
515 
535 {
536  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
537 
538  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
539 
542 
543  blend_req.group_name = planning_group_;
544  blend_req.link_name = target_link_;
545  blend_req.blend_radius = seq.getBlendRadius(0);
546 
547  blend_req.first_trajectory = res.at(0).trajectory_;
548  blend_req.second_trajectory = res.at(1).trajectory_;
549 
550  EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res));
551 
552  EXPECT_TRUE(testutils::checkBlendResult(blend_req, blend_res, planner_limits_, joint_velocity_tolerance_,
553  joint_acceleration_tolerance_, cartesian_velocity_tolerance_,
554  cartesian_angular_velocity_tolerance_));
555 }
556 
577 TEST_F(TrajectoryBlenderTransitionWindowTest, testOverlappingBlendTrajectories)
578 {
579  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
580  // Set goal of second traj to start of first traj.
581  seq.getCmd<LinCart>(1).setGoalConfiguration(seq.getCmd<LinCart>(0).getStartConfiguration());
582 
583  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
584 
587 
588  blend_req.group_name = planning_group_;
589  blend_req.link_name = target_link_;
590  blend_req.first_trajectory = res.at(0).trajectory_;
591  blend_req.second_trajectory = res.at(1).trajectory_;
592  blend_req.blend_radius = seq.getBlendRadius(0);
593  EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res));
594 
595  EXPECT_TRUE(testutils::checkBlendResult(blend_req, blend_res, planner_limits_, joint_velocity_tolerance_,
596  joint_acceleration_tolerance_, cartesian_velocity_tolerance_,
597  cartesian_angular_velocity_tolerance_));
598 }
599 
624 {
625  const double sine_scaling_factor{ 0.01 };
626  const double time_scaling_factor{ 10 };
627 
628  Sequence seq{ data_loader_->getSequence("SimpleSequence") };
629 
630  std::vector<planning_interface::MotionPlanResponse> res{ generateLinTrajs(seq, 2) };
631 
632  // prepare looping over trajectories
633  std::vector<robot_trajectory::RobotTrajectoryPtr> sine_trajs(2);
634 
635  for (size_t traj_index = 0; traj_index < 2; ++traj_index)
636  {
637  auto lin_traj{ res.at(traj_index).trajectory_ };
638 
639  CartesianTrajectory cart_traj;
640  trajectory_msgs::msg::JointTrajectory joint_traj;
641  const double duration{ lin_traj->getWayPointDurationFromStart(lin_traj->getWayPointCount()) };
642  // time from start zero does not work
643  const double time_from_start_offset{ time_scaling_factor * lin_traj->getWayPointDurations().back() };
644 
645  // generate modified cartesian trajectory
646  for (size_t i = 0; i < lin_traj->getWayPointCount(); ++i)
647  {
648  // transform time to interval [0, 4*pi]
649  const double sine_arg{ 4 * M_PI * lin_traj->getWayPointDurationFromStart(i) / duration };
650 
651  // get pose
652  CartesianTrajectoryPoint waypoint;
653  const Eigen::Isometry3d eigen_pose{ lin_traj->getWayPointPtr(i)->getFrameTransform(target_link_) };
654  geometry_msgs::msg::Pose waypoint_pose = tf2::toMsg(eigen_pose);
655 
656  // add scaled sine function
657  waypoint_pose.position.x += sine_scaling_factor * sin(sine_arg);
658  waypoint_pose.position.y += sine_scaling_factor * sin(sine_arg);
659  waypoint_pose.position.z += sine_scaling_factor * sin(sine_arg);
660 
661  // add to trajectory
662  waypoint.pose = waypoint_pose;
663  waypoint.time_from_start = rclcpp::Duration::from_seconds(
664  time_from_start_offset + time_scaling_factor * lin_traj->getWayPointDurationFromStart(i));
665  cart_traj.points.push_back(waypoint);
666  }
667 
668  // prepare ik
669  std::map<std::string, double> initial_joint_position, initial_joint_velocity;
670  for (const std::string& joint_name :
671  lin_traj->getFirstWayPointPtr()->getJointModelGroup(planning_group_)->getActiveJointModelNames())
672  {
673  if (traj_index == 0)
674  {
675  initial_joint_position[joint_name] = lin_traj->getFirstWayPoint().getVariablePosition(joint_name);
676  initial_joint_velocity[joint_name] = lin_traj->getFirstWayPoint().getVariableVelocity(joint_name);
677  }
678  else
679  {
680  initial_joint_position[joint_name] =
681  sine_trajs[traj_index - 1]->getLastWayPoint().getVariablePosition(joint_name);
682  initial_joint_velocity[joint_name] =
683  sine_trajs[traj_index - 1]->getLastWayPoint().getVariableVelocity(joint_name);
684  }
685  }
686 
687  moveit_msgs::msg::MoveItErrorCodes error_code;
688  if (!generateJointTrajectory(planning_scene_, planner_limits_.getJointLimitContainer(), cart_traj, planning_group_,
689  target_link_, initial_joint_position, initial_joint_velocity, joint_traj, error_code,
690  true))
691  {
692  std::runtime_error("Failed to generate trajectory.");
693  }
694 
695  joint_traj.points.back().velocities.assign(joint_traj.points.back().velocities.size(), 0.0);
696  joint_traj.points.back().accelerations.assign(joint_traj.points.back().accelerations.size(), 0.0);
697 
698  // convert trajectory_msgs::JointTrajectory to robot_trajectory::RobotTrajectory
699  sine_trajs[traj_index] = std::make_shared<robot_trajectory::RobotTrajectory>(robot_model_, planning_group_);
700  sine_trajs.at(traj_index)->setRobotTrajectoryMsg(lin_traj->getFirstWayPoint(), joint_traj);
701  }
702 
703  TrajectoryBlendRequest blend_req;
704  TrajectoryBlendResponse blend_res;
705 
706  blend_req.group_name = planning_group_;
707  blend_req.link_name = target_link_;
708  blend_req.blend_radius = seq.getBlendRadius(0);
709 
710  blend_req.first_trajectory = sine_trajs.at(0);
711  blend_req.second_trajectory = sine_trajs.at(1);
712 
713  EXPECT_TRUE(blender_->blend(planning_scene_, blend_req, blend_res));
714 
715  EXPECT_TRUE(testutils::checkBlendResult(blend_req, blend_res, planner_limits_, joint_velocity_tolerance_,
716  joint_acceleration_tolerance_, cartesian_velocity_tolerance_,
717  cartesian_angular_velocity_tolerance_));
718 }
719 
720 int main(int argc, char** argv)
721 {
722  rclcpp::init(argc, argv);
723  testing::InitGoogleTest(&argc, argv);
724  return RUN_ALL_TESTS();
725 }
void SetUp() override
Create test scenario for trajectory blender.
std::unique_ptr< TrajectoryBlenderTransitionWindow > blender_
std::unique_ptr< robot_model_loader::RobotModelLoader > rm_loader_
std::vector< planning_interface::MotionPlanResponse > generateLinTrajs(const Sequence &seq, size_t num_cmds)
Generate lin trajectories for blend sequences.
Set of cartesian limits, has values for velocity, acceleration and deceleration of both the translati...
void setMaxRotationalVelocity(double max_rot_vel)
Set the maximum rotational velocity.
void setMaxTranslationalVelocity(double max_trans_vel)
Set the maximal translational velocity.
void setMaxTranslationalAcceleration(double max_trans_acc)
Set the maximum translational acceleration.
void setMaxTranslationalDeceleration(double max_trans_dec)
Set the maximum translational deceleration.
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.
Data class storing all information regarding a linear command.
Definition: lin.h:48
Data class storing all information regarding a Sequence command.
Definition: sequence.h:54
void robotStateToRobotStateMsg(const RobotState &state, moveit_msgs::msg::RobotState &robot_state, bool copy_attached_bodies=true)
Convert a MoveIt robot state to a robot state message.
std::unique_ptr< TestdataLoader > XmlTestDataLoaderUPtr
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, const 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.
TEST_F(GetSolverTipFrameIntegrationTest, TestHasSolverManipulator)
Check if hasSolver() can be called successfully for the manipulator group.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
bool checkBlendResult(const pilz_industrial_motion_planner::TrajectoryBlendRequest &blend_req, const pilz_industrial_motion_planner::TrajectoryBlendResponse &blend_res, const pilz_industrial_motion_planner::LimitsContainer &limits, double joint_velocity_tolerance, double joint_acceleration_tolerance, double cartesian_velocity_tolerance, double cartesian_angular_velocity_tolerance)
check the blending result of lin-lin
void checkRobotModel(const moveit::core::RobotModelConstPtr &robot_model, const std::string &group_name, const std::string &link_name)
std::vector< CartesianTrajectoryPoint > points
int main(int argc, char **argv)