@@ -1092,7 +1092,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_old_trajectory)
10921092
10931093 RCLCPP_INFO (traj_controller_->get_node ()->get_logger (), " Sending new trajectory in the past" );
10941094 // New trajectory will end before current time
1095- rclcpp::Time new_traj_start = rclcpp::Clock ().now () - delay - std::chrono::milliseconds (100 );
1095+ rclcpp::Time new_traj_start =
1096+ rclcpp::Clock (RCL_STEADY_TIME).now () - delay - std::chrono::milliseconds (100 );
10961097 expected_actual.positions = {points_old[1 ].begin (), points_old[1 ].end ()};
10971098 expected_desired = expected_actual;
10981099 std::cout << " Sending old trajectory" << std::endl;
@@ -1108,23 +1109,27 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_partial_old_trajectory
11081109
11091110 std::vector<std::vector<double >> points_old{{{2 ., 3 ., 4 .}, {4 ., 5 ., 6 .}}};
11101111 std::vector<std::vector<double >> points_new{{{-1 ., -2 ., -3 .}, {-2 ., -4 ., -6 .}}};
1111-
1112+ trajectory_msgs::msg::JointTrajectoryPoint expected_actual, expected_desired;
11121113 const auto delay = std::chrono::milliseconds (500 );
11131114 builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration (delay)};
1115+
1116+ // send points_old and wait to reach first point
11141117 publish (time_from_start, points_old, rclcpp::Time ());
1115- trajectory_msgs::msg::JointTrajectoryPoint expected_actual, expected_desired;
11161118 expected_actual.positions = {points_old[0 ].begin (), points_old[0 ].end ()};
11171119 expected_desired = expected_actual;
11181120 // Check that we reached end of points_old[0]trajectory
11191121 waitAndCompareState (expected_actual, expected_desired, executor, rclcpp::Duration (delay), 0.1 );
11201122
1123+ // send points_new before the old trajectory is finished
11211124 RCLCPP_INFO (
11221125 traj_controller_->get_node ()->get_logger (), " Sending new trajectory partially in the past" );
11231126 // New trajectory first point is in the past, second is in the future
1124- rclcpp::Time new_traj_start = rclcpp::Clock ().now () - delay - std::chrono::milliseconds (100 );
1125- expected_actual.positions = {points_new[1 ].begin (), points_new[1 ].end ()};
1126- expected_desired = expected_actual;
1127+ rclcpp::Time new_traj_start =
1128+ rclcpp::Clock (RCL_STEADY_TIME).now () - delay - std::chrono::milliseconds (100 );
11271129 publish (time_from_start, points_new, new_traj_start);
1130+ // it should not have accepted the new goal but finish the old one
1131+ expected_actual.positions = {points_old[1 ].begin (), points_old[1 ].end ()};
1132+ expected_desired.positions = {points_old[1 ].begin (), points_old[1 ].end ()};
11281133 waitAndCompareState (expected_actual, expected_desired, executor, rclcpp::Duration (delay), 0.1 );
11291134}
11301135
@@ -1163,7 +1168,8 @@ TEST_P(TrajectoryControllerTestParameterized, test_execute_partial_traj_in_futur
11631168 // Send partial trajectory starting after full trajecotry is complete
11641169 RCLCPP_INFO (traj_controller_->get_node ()->get_logger (), " Sending new trajectory in the future" );
11651170 publish (
1166- points_delay, partial_traj, rclcpp::Clock ().now () + delay * 2 , {}, partial_traj_velocities);
1171+ points_delay, partial_traj, rclcpp::Clock (RCL_STEADY_TIME).now () + delay * 2 , {},
1172+ partial_traj_velocities);
11671173 // Wait until the end start and end of partial traj
11681174
11691175 expected_actual.positions = {partial_traj.back ()[0 ], partial_traj.back ()[1 ], full_traj.back ()[2 ]};
0 commit comments