39 #include <gtest/gtest.h>
53 void setAccelerationLimits(
const moveit::core::RobotModelPtr& robot_model)
55 const std::vector<moveit::core::JointModel*> joint_models = robot_model->getActiveJointModels();
56 for (
auto& joint_model : joint_models)
58 std::vector<moveit_msgs::msg::JointLimits> joint_bounds_msg(joint_model->getVariableBoundsMsg());
60 for (
auto& joint_bound : joint_bounds_msg)
62 joint_bound.has_acceleration_limits =
true;
63 joint_bound.max_acceleration = 1.0;
65 joint_model->setVariableBounds(joint_bounds_msg);
70 TEST(time_optimal_trajectory_generation, test1)
72 Eigen::VectorXd waypoint(4);
73 std::vector<Eigen::VectorXd> waypoints;
75 waypoint << 1424.0, 984.999694824219, 2126.0, 0.0;
76 waypoints.push_back(waypoint);
77 waypoint << 1423.0, 985.000244140625, 2126.0, 0.0;
78 waypoints.push_back(waypoint);
80 Eigen::VectorXd max_velocities(4);
81 max_velocities << 1.3, 0.67, 0.67, 0.5;
82 Eigen::VectorXd max_accelerations(4);
83 max_accelerations << 0.00249, 0.00249, 0.00249, 0.00249;
85 auto path_maybe = Path::create(waypoints, 100.0);
86 ASSERT_TRUE(path_maybe.has_value());
88 auto trajectory_maybe = Trajectory::create(*path_maybe, max_velocities, max_accelerations, 10.0);
89 ASSERT_TRUE(trajectory_maybe.has_value());
90 const Trajectory& trajectory = trajectory_maybe.value();
92 EXPECT_DOUBLE_EQ(40.080256821829849, trajectory.
getDuration());
95 EXPECT_DOUBLE_EQ(1424.0, trajectory.
getPosition(0.0)[0]);
96 EXPECT_DOUBLE_EQ(984.999694824219, trajectory.
getPosition(0.0)[1]);
97 EXPECT_DOUBLE_EQ(2126.0, trajectory.
getPosition(0.0)[2]);
98 EXPECT_DOUBLE_EQ(0.0, trajectory.
getPosition(0.0)[3]);
107 const double traj_duration = trajectory.
getDuration();
108 EXPECT_NEAR(0.0, trajectory.
getVelocity(0.0)[0], 0.1);
109 EXPECT_NEAR(0.0, trajectory.
getVelocity(traj_duration)[0], 0.1);
112 TEST(time_optimal_trajectory_generation, test2)
114 Eigen::VectorXd waypoint(4);
115 std::vector<Eigen::VectorXd> waypoints;
117 waypoint << 1427.0, 368.0, 690.0, 90.0;
118 waypoints.push_back(waypoint);
119 waypoint << 1427.0, 368.0, 790.0, 90.0;
120 waypoints.push_back(waypoint);
121 waypoint << 952.499938964844, 433.0, 1051.0, 90.0;
122 waypoints.push_back(waypoint);
123 waypoint << 452.5, 533.0, 1051.0, 90.0;
124 waypoints.push_back(waypoint);
125 waypoint << 452.5, 533.0, 951.0, 90.0;
126 waypoints.push_back(waypoint);
128 Eigen::VectorXd max_velocities(4);
129 max_velocities << 1.3, 0.67, 0.67, 0.5;
130 Eigen::VectorXd max_accelerations(4);
131 max_accelerations << 0.002, 0.002, 0.002, 0.002;
133 auto path_maybe = Path::create(waypoints, 100.0);
134 ASSERT_TRUE(path_maybe.has_value());
136 auto trajectory_maybe = Trajectory::create(*path_maybe, max_velocities, max_accelerations, 10.0);
137 ASSERT_TRUE(trajectory_maybe.has_value());
138 const Trajectory& trajectory = trajectory_maybe.value();
140 EXPECT_DOUBLE_EQ(1922.1418427445944, trajectory.
getDuration());
143 EXPECT_DOUBLE_EQ(1427.0, trajectory.
getPosition(0.0)[0]);
144 EXPECT_DOUBLE_EQ(368.0, trajectory.
getPosition(0.0)[1]);
145 EXPECT_DOUBLE_EQ(690.0, trajectory.
getPosition(0.0)[2]);
146 EXPECT_DOUBLE_EQ(90.0, trajectory.
getPosition(0.0)[3]);
155 const double traj_duration = trajectory.
getDuration();
156 EXPECT_NEAR(0.0, trajectory.
getVelocity(0.0)[0], 0.1);
157 EXPECT_NEAR(0.0, trajectory.
getVelocity(traj_duration)[0], 0.1);
160 TEST(time_optimal_trajectory_generation, test3)
162 Eigen::VectorXd waypoint(4);
163 std::vector<Eigen::VectorXd> waypoints;
165 waypoint << 1427.0, 368.0, 690.0, 90.0;
166 waypoints.push_back(waypoint);
167 waypoint << 1427.0, 368.0, 790.0, 90.0;
168 waypoints.push_back(waypoint);
169 waypoint << 952.499938964844, 433.0, 1051.0, 90.0;
170 waypoints.push_back(waypoint);
171 waypoint << 452.5, 533.0, 1051.0, 90.0;
172 waypoints.push_back(waypoint);
173 waypoint << 452.5, 533.0, 951.0, 90.0;
174 waypoints.push_back(waypoint);
176 Eigen::VectorXd max_velocities(4);
177 max_velocities << 1.3, 0.67, 0.67, 0.5;
178 Eigen::VectorXd max_accelerations(4);
179 max_accelerations << 0.002, 0.002, 0.002, 0.002;
181 auto path_maybe = Path::create(waypoints, 100.0);
182 ASSERT_TRUE(path_maybe.has_value());
184 auto trajectory_maybe = Trajectory::create(*path_maybe, max_velocities, max_accelerations);
185 ASSERT_TRUE(trajectory_maybe.has_value());
186 const Trajectory& trajectory = trajectory_maybe.value();
188 EXPECT_DOUBLE_EQ(1919.5597888812974, trajectory.
getDuration());
191 EXPECT_DOUBLE_EQ(1427.0, trajectory.
getPosition(0.0)[0]);
192 EXPECT_DOUBLE_EQ(368.0, trajectory.
getPosition(0.0)[1]);
193 EXPECT_DOUBLE_EQ(690.0, trajectory.
getPosition(0.0)[2]);
194 EXPECT_DOUBLE_EQ(90.0, trajectory.
getPosition(0.0)[3]);
203 const double traj_duration = trajectory.
getDuration();
204 EXPECT_NEAR(0.0, trajectory.
getVelocity(0.0)[0], 0.1);
205 EXPECT_NEAR(0.0, trajectory.
getVelocity(traj_duration)[0], 0.1);
209 TEST(time_optimal_trajectory_generation, testCustomLimits)
211 constexpr
auto robot_name{
"panda" };
212 constexpr
auto group_name{
"panda_arm" };
215 ASSERT_TRUE(robot_model) <<
"Failed to load robot model" << robot_name;
216 setAccelerationLimits(robot_model);
217 auto group = robot_model->getJointModelGroup(group_name);
218 ASSERT_TRUE(group) <<
"Failed to load joint model group " << group_name;
222 const double delta_t = 0.1;
224 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.5, -3.52, 1.35, -2.51, -0.88, 0.63, 0.0 });
226 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.45, -3.2, 1.2, -2.4, -0.8, 0.6, 0.0 });
231 std::unordered_map<std::string, double> vel_limits{ {
"panda_joint1", 1.3 }, {
"panda_joint2", 2.3 },
232 {
"panda_joint3", 3.3 }, {
"panda_joint4", 4.3 },
233 {
"panda_joint5", 5.3 }, {
"panda_joint6", 6.3 },
234 {
"panda_joint7", 7.3 } };
235 std::unordered_map<std::string, double> accel_limits{ {
"panda_joint1", 1.3 }, {
"panda_joint2", 2.3 },
236 {
"panda_joint3", 3.3 }, {
"panda_joint4", 4.3 },
237 {
"panda_joint5", 5.3 }, {
"panda_joint6", 6.3 },
238 {
"panda_joint7", 7.3 } };
239 ASSERT_TRUE(totg.
computeTimeStamps(trajectory, vel_limits, accel_limits)) <<
"Failed to compute time stamps";
243 TEST(time_optimal_trajectory_generation, testLargeAccel)
245 double path_tolerance = 0.1;
246 double resample_dt = 0.1;
247 Eigen::VectorXd waypoint(6);
248 std::vector<Eigen::VectorXd> waypoints;
249 Eigen::VectorXd max_velocities(6);
250 Eigen::VectorXd max_accelerations(6);
254 waypoint << 1.6113056281076339,
255 -0.21400163389235427,
257 9.9653618690354051e-12,
260 waypoints.push_back(waypoint);
262 waypoint << 1.6088016187976597,
263 -0.21792862470933924,
265 0.00010424017303217738,
268 waypoints.push_back(waypoint);
270 waypoint << 1.5887695443178671,
271 -0.24934455124521923,
273 0.00093816147756670078,
276 waypoints.push_back(waypoint);
278 waypoint << 1.1647412393815282,
279 -0.91434018564402375,
281 0.018590164397622583,
284 waypoints.push_back(waypoint);
287 max_velocities << 0.89535390627300004,
294 max_accelerations << 0.82673490883799994,
302 auto path_maybe = Path::create(waypoints, path_tolerance);
303 ASSERT_TRUE(path_maybe.has_value());
305 auto trajectory_maybe = Trajectory::create(*path_maybe, max_velocities, max_accelerations, 0.001);
306 ASSERT_TRUE(trajectory_maybe.has_value());
307 const Trajectory& parameterized = trajectory_maybe.value();
309 size_t sample_count = std::ceil(parameterized.
getDuration() / resample_dt);
310 for (
size_t sample = 0; sample <= sample_count; ++sample)
313 double t = std::min(parameterized.
getDuration(), sample * resample_dt);
316 ASSERT_EQ(acceleration.size(), 6);
317 for (std::size_t i = 0; i < 6; ++i)
318 EXPECT_NEAR(acceleration(i), 0.0, 100.0) <<
"Invalid acceleration at position " << sample_count <<
'\n';
326 TEST(time_optimal_trajectory_generation, AccelerationLimitIsRespected)
328 double path_tolerance = 0.001;
329 double resample_dt = 0.01;
332 std::vector<Eigen::VectorXd> waypoints;
337 Eigen::VectorXd max_velocities = Eigen::VectorXd::Constant(3, 0.1);
338 Eigen::VectorXd max_accelerations = Eigen::VectorXd::Constant(3, 0.5);
340 auto path_maybe = Path::create(waypoints, path_tolerance);
341 ASSERT_TRUE(path_maybe.has_value());
343 auto trajectory_maybe = Trajectory::create(*path_maybe, max_velocities, max_accelerations, 0.001);
344 ASSERT_TRUE(trajectory_maybe.has_value());
345 const Trajectory& parameterized = trajectory_maybe.value();
347 size_t sample_count = std::ceil(parameterized.
getDuration() / resample_dt);
349 for (
size_t sample = 0; sample <= sample_count; ++sample)
351 double t = std::min(parameterized.
getDuration(), sample * resample_dt);
354 double acceleration = (velocity - previous_velocity).norm() / resample_dt;
355 EXPECT_LT(acceleration, max_accelerations.norm() + 1e-3);
356 previous_velocity = velocity;
362 TEST(time_optimal_trajectory_generation, PathMakes180DegreeTurn)
365 std::vector<Eigen::VectorXd> waypoints;
370 EXPECT_FALSE(Path::create(waypoints, 0.01));
375 TEST(time_optimal_trajectory_generation, testLastWaypoint)
377 constexpr
auto robot_name{
"panda" };
378 constexpr
auto group_name{
"panda_arm" };
381 ASSERT_TRUE(robot_model) <<
"Failed to load robot model" << robot_name;
382 setAccelerationLimits(robot_model);
383 auto group = robot_model->getJointModelGroup(group_name);
384 ASSERT_TRUE(group) <<
"Failed to load joint model group " << group_name;
389 auto add_waypoint = [&](
const std::vector<double>& waypoint) {
393 add_waypoint({ 0.000000000, 0.000000000, 0, 0, 0, 0, 0 });
394 add_waypoint({ 0.009521808, 0.009521808, 0, 0, 0, 0, 0 });
395 add_waypoint({ 0.011902261, 0.011902261, 0, 0, 0, 0, 0 });
396 add_waypoint({ 0.016663165, 0.016663165, 0, 0, 0, 0, 0 });
397 add_waypoint({ 0.026184973, 0.026184973, 0, 0, 0, 0, 0 });
398 add_waypoint({ 0.034516555, 0.034516555, 0, 0, 0, 0, 0 });
400 const std::vector<double> expected_last_waypoint = { 0.034516555, 0.034516555, 0, 0, 0, 0, 0 };
401 add_waypoint(expected_last_waypoint);
404 ASSERT_TRUE(totg.
computeTimeStamps(trajectory)) <<
"Failed to compute time stamps";
406 std::vector<double> actual_last_waypoint;
408 EXPECT_TRUE(std::equal(actual_last_waypoint.cbegin(), actual_last_waypoint.cend(), expected_last_waypoint.cbegin(),
409 expected_last_waypoint.cend(), [](
const double rhs,
const double lhs) {
410 return std::abs(rhs - lhs) < std::numeric_limits<double>::epsilon();
414 TEST(time_optimal_trajectory_generation, testPluginAPI)
416 constexpr
auto robot_name{
"panda" };
417 constexpr
auto group_name{
"panda_arm" };
420 ASSERT_TRUE(robot_model) <<
"Failed to load robot model" << robot_name;
421 setAccelerationLimits(robot_model);
422 auto group = robot_model->getJointModelGroup(group_name);
423 ASSERT_TRUE(group) <<
"Failed to load joint model group " << group_name;
428 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.5, -3.52, 1.35, -2.51, -0.88, 0.63, 0.0 });
430 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.5, -3.52, 1.35, -2.51, -0.88, 0.63, 0.0 });
432 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ 0.0, -3.5, 1.4, -1.2, -1.0, -0.2, 0.0 });
434 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.5, -3.00, 1.35, -2.51, -0.88, 0.63, 0.0 });
436 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ 0.0, -3.5, 1.4, -1.2, -1.5, -0.2, 0.0 });
438 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.5, -3.52, 1.35, -2.51, -0.88, 0.63, 0.0 });
442 constexpr
size_t totg_iterations = 10;
445 moveit_msgs::msg::RobotTrajectory first_trajectory_msg_start, first_trajectory_msg_end;
453 ASSERT_EQ(test_bounds.size(), original_bounds.size());
454 for (
size_t bound_idx = 0; bound_idx < test_bounds.at(0)->size(); ++bound_idx)
456 ASSERT_EQ(test_bounds.at(0)->at(bound_idx).max_velocity_, original_bounds.at(0)->at(bound_idx).max_velocity_);
457 ASSERT_EQ(test_bounds.at(0)->at(bound_idx).min_velocity_, original_bounds.at(0)->at(bound_idx).min_velocity_);
458 ASSERT_EQ(test_bounds.at(0)->at(bound_idx).velocity_bounded_,
459 original_bounds.at(0)->at(bound_idx).velocity_bounded_);
461 ASSERT_EQ(test_bounds.at(0)->at(bound_idx).max_acceleration_,
462 original_bounds.at(0)->at(bound_idx).max_acceleration_);
463 ASSERT_EQ(test_bounds.at(0)->at(bound_idx).min_acceleration_,
464 original_bounds.at(0)->at(bound_idx).min_acceleration_);
465 ASSERT_EQ(test_bounds.at(0)->at(bound_idx).acceleration_bounded_,
466 original_bounds.at(0)->at(bound_idx).acceleration_bounded_);
471 ASSERT_TRUE(totg.
computeTimeStamps(test_trajectory)) <<
"Failed to compute time stamps";
476 for (
size_t i = 0; i < totg_iterations; ++i)
479 EXPECT_TRUE(totg_success) <<
"Failed to compute time stamps with a same TOTG instance in iteration " << i;
486 moveit_msgs::msg::RobotTrajectory second_trajectory_msg_start, second_trajectory_msg_end;
492 ASSERT_TRUE(totg.
computeTimeStamps(test_trajectory)) <<
"Failed to compute time stamps";
498 for (
size_t i = 0; i < totg_iterations; ++i)
502 EXPECT_TRUE(totg_success) <<
"Failed to compute time stamps with a new TOTG instance in iteration " << i;
509 ASSERT_EQ(first_trajectory_msg_start, second_trajectory_msg_start);
510 ASSERT_EQ(first_trajectory_msg_end, second_trajectory_msg_end);
513 moveit_msgs::msg::RobotTrajectory third_trajectory_msg_end;
517 ASSERT_TRUE(totg.
computeTimeStamps(trajectory)) <<
"Failed to compute time stamps";
520 for (
size_t i = 0; i < totg_iterations; ++i)
524 ASSERT_TRUE(totg_success) <<
"Failed to compute timestamps on a new TOTG instance in iteration " << i;
531 ASSERT_EQ(first_trajectory_msg_end, third_trajectory_msg_end);
534 TEST(time_optimal_trajectory_generation, testFixedNumWaypoints)
537 constexpr
size_t desired_num_waypoints = 42;
539 constexpr
auto robot_name{
"panda" };
540 constexpr
auto group_name{
"panda_arm" };
543 ASSERT_TRUE(robot_model) <<
"Failed to load robot model" << robot_name;
544 setAccelerationLimits(robot_model);
545 auto group = robot_model->getJointModelGroup(group_name);
546 ASSERT_TRUE(group) <<
"Failed to load joint model group " << group_name;
550 const double delta_t = 0.1;
552 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.5, -3.52, 1.35, -2.51, -0.88, 0.63, 0.0 });
554 waypoint_state.
setJointGroupPositions(group, std::vector<double>{ -0.45, -3.2, 1.2, -2.4, -0.8, 0.6, 0.0 });
563 TEST(time_optimal_trajectory_generation, testSingleDofDiscontinuity)
566 Eigen::VectorXd waypoint(1);
567 std::vector<Eigen::VectorXd> waypoints;
569 const double start_position = 1.881943;
570 waypoint << start_position;
571 waypoints.push_back(waypoint);
572 waypoint << 2.600542;
573 waypoints.push_back(waypoint);
575 Eigen::VectorXd max_velocities(1);
576 max_velocities << 4.54;
577 Eigen::VectorXd max_accelerations(1);
578 max_accelerations << 28.0;
580 auto path_maybe = Path::create(waypoints, 0.1 );
581 ASSERT_TRUE(path_maybe.has_value());
583 auto trajectory_maybe = Trajectory::create(*path_maybe, max_velocities, max_accelerations, 0.001 );
584 ASSERT_TRUE(trajectory_maybe.has_value());
585 const Trajectory& trajectory = trajectory_maybe.value();
588 const double traj_duration = trajectory.
getDuration();
589 EXPECT_NEAR(0.320681, traj_duration, 1e-3);
592 EXPECT_DOUBLE_EQ(start_position, trajectory.
getPosition(0.0)[0]);
594 EXPECT_NEAR(0.0, trajectory.
getVelocity(0.0)[0], 0.1);
595 EXPECT_NEAR(0.0, trajectory.
getVelocity(traj_duration)[0], 0.1);
598 for (
double time = 0; time < traj_duration; time += 0.01)
601 double t_switch = 0.1603407;
604 EXPECT_NEAR(trajectory.
getAcceleration(time)[0], max_accelerations[0], 1e-3) <<
"Time: " << time;
606 else if (time > t_switch)
608 EXPECT_NEAR(trajectory.
getAcceleration(time)[0], -max_accelerations[0], 1e-3) <<
"Time: " << time;
613 TEST(time_optimal_trajectory_generation, testRelevantZeroMaxAccelerationsInvalidateTrajectory)
615 const Eigen::Vector2d max_velocity(1, 1);
616 const Path path = *Path::create({ Eigen::Vector2d(0, 0), Eigen::Vector2d(1, 1) });
618 EXPECT_FALSE(Trajectory::create(path, max_velocity, Eigen::Vector2d(0, 1)));
619 EXPECT_FALSE(Trajectory::create(path, max_velocity, Eigen::Vector2d(1, 0)));
620 EXPECT_FALSE(Trajectory::create(path, max_velocity, Eigen::Vector2d(0, 0)));
623 TEST(time_optimal_trajectory_generation, testIrrelevantZeroMaxAccelerationsDontInvalidateTrajectory)
625 const Eigen::Vector2d max_velocity(1, 1);
627 EXPECT_TRUE(Trajectory::create(*Path::create({ Eigen::Vector2d(0, 0), Eigen::Vector2d(0, 1) }), max_velocity,
628 Eigen::Vector2d(0, 1)));
629 EXPECT_TRUE(Trajectory::create(*Path::create({ Eigen::Vector2d(0, 0), Eigen::Vector2d(1, 0) }), max_velocity,
630 Eigen::Vector2d(1, 0)));
633 TEST(time_optimal_trajectory_generation, testTimeStepZeroMakesTrajectoryInvalid)
635 EXPECT_FALSE(Trajectory::create(*Path::create({ Eigen::Vector2d(0, 0), Eigen::Vector2d(1, 1) }),
636 Eigen::Vector2d(1, 1), Eigen::Vector2d(1, 1),
640 int main(
int argc,
char** argv)
642 testing::InitGoogleTest(&argc, argv);
643 return RUN_ALL_TESTS();
Representation of a robot's state. This includes position, velocity, acceleration and effort.
void setJointGroupPositions(const std::string &joint_group_name, const double *gstate)
Given positions for the variables that make up a group, in the order found in the group (including va...
void copyJointGroupPositions(const std::string &joint_group_name, std::vector< double > &gstate) const
For a given group, copy the position values of the variables that make up the group into another loca...
void setToDefaultValues()
Set all joints to their default positions. The default position is 0, or if that is not within bounds...
Maintain a sequence of waypoints and the time durations between these waypoints.
const moveit::core::RobotModelConstPtr & getRobotModel() const
void getRobotTrajectoryMsg(moveit_msgs::msg::RobotTrajectory &trajectory, const std::vector< std::string > &joint_filter=std::vector< std::string >()) const
RobotTrajectory & addSuffixWayPoint(const moveit::core::RobotState &state, double dt)
Add a point to the trajectory.
std::size_t getWayPointCount() const
double getWayPointDurationFromPrevious(std::size_t index) const
double getDuration() const
const moveit::core::RobotState & getLastWayPoint() const
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
Compute a trajectory with waypoints spaced equally in time (according to resample_dt_)....
Eigen::VectorXd getAcceleration(double time) const
Return the acceleration vector for a given point in time.
Eigen::VectorXd getPosition(double time) const
Return the position/configuration vector for a given point in time.
double getDuration() const
Returns the optimal duration of the trajectory.
Eigen::VectorXd getVelocity(double time) const
Return the velocity vector for a given point in time.
Vec3fX< details::Vec3Data< double > > Vector3d
moveit::core::RobotModelPtr loadTestingRobotModel(const std::string &package_name, const std::string &urdf_relative_path, const std::string &srdf_relative_path)
Loads a robot model given a URDF and SRDF file in a package.
std::vector< const JointModel::Bounds * > JointBoundsVector
bool totgComputeTimeStamps(const size_t num_waypoints, robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0)
Compute a trajectory with the desired number of waypoints. Resampling the trajectory doesn't change t...
int main(int argc, char **argv)
TEST(time_optimal_trajectory_generation, test1)