Skip to content

Commit d8d6616

Browse files
authored
Use system time in all tests to avoid error with different time sources. (#334)
1 parent 001d896 commit d8d6616

File tree

2 files changed

+13
-11
lines changed

2 files changed

+13
-11
lines changed

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 12 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -78,7 +78,7 @@ TEST_P(TrajectoryControllerTestParameterized, configure)
7878
time_from_start.sec = 1;
7979
time_from_start.nanosec = 0;
8080
std::vector<std::vector<double>> points{{{3.3, 4.4, 5.5}}};
81-
publish(time_from_start, points);
81+
publish(time_from_start, points, rclcpp::Time());
8282
std::this_thread::sleep_for(std::chrono::milliseconds(10));
8383

8484
traj_controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));
@@ -141,7 +141,7 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
141141
// time_from_start.sec = 1;
142142
// time_from_start.nanosec = 0;
143143
// std::vector<std::vector<double>> points {{{3.3, 4.4, 5.5}}};
144-
// publish(time_from_start, points);
144+
// publish(time_from_start, points, rclcpp::Time());
145145
// // wait for msg is be published to the system
146146
// std::this_thread::sleep_for(std::chrono::milliseconds(1000));
147147
// executor.spin_once();
@@ -189,7 +189,7 @@ TEST_P(TrajectoryControllerTestParameterized, activate)
189189
// {{10.10, 11.11, 12.12}}
190190
// };
191191
// // *INDENT-ON*
192-
// publish(time_from_start, points);
192+
// publish(time_from_start, points, rclcpp::Time());
193193
// // wait for msg is be published to the system
194194
// std::this_thread::sleep_for(std::chrono::milliseconds(500));
195195
// executor.spin_once();
@@ -241,7 +241,7 @@ TEST_P(TrajectoryControllerTestParameterized, cleanup)
241241
time_from_start.sec = 1;
242242
time_from_start.nanosec = 0;
243243
std::vector<std::vector<double>> points{{{3.3, 4.4, 5.5}}};
244-
publish(time_from_start, points);
244+
publish(time_from_start, points, rclcpp::Time());
245245
traj_controller_->wait_for_trajectory(executor);
246246
traj_controller_->update(rclcpp::Time(0), rclcpp::Duration::from_seconds(0.01));
247247

@@ -847,9 +847,10 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_old_trajectory)
847847
std::vector<std::vector<double>> points_old{{{2., 3., 4.}, {4., 5., 6.}}};
848848
std::vector<std::vector<double>> points_new{{{-1., -2., -3.}}};
849849

850+
RCLCPP_INFO(traj_controller_->get_node()->get_logger(), "Sending new trajectory in the future");
850851
const auto delay = std::chrono::milliseconds(500);
851852
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(delay)};
852-
publish(time_from_start, points_old);
853+
publish(time_from_start, points_old, rclcpp::Time());
853854
trajectory_msgs::msg::JointTrajectoryPoint expected_actual, expected_desired;
854855
expected_actual.positions = {points_old[0].begin(), points_old[0].end()};
855856
expected_desired = expected_actual;
@@ -861,6 +862,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_old_trajectory)
861862
rclcpp::Time new_traj_start = rclcpp::Clock().now() - delay - std::chrono::milliseconds(100);
862863
expected_actual.positions = {points_old[1].begin(), points_old[1].end()};
863864
expected_desired = expected_actual;
865+
std::cout << "Sending old trajectory" << std::endl;
864866
publish(time_from_start, points_new, new_traj_start);
865867
waitAndCompareState(expected_actual, expected_desired, executor, rclcpp::Duration(delay), 0.1);
866868
}
@@ -876,7 +878,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_ignore_partial_old_trajectory
876878

877879
const auto delay = std::chrono::milliseconds(500);
878880
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(delay)};
879-
publish(time_from_start, points_old);
881+
publish(time_from_start, points_old, rclcpp::Time());
880882
trajectory_msgs::msg::JointTrajectoryPoint expected_actual, expected_desired;
881883
expected_actual.positions = {points_old[0].begin(), points_old[0].end()};
882884
expected_desired = expected_actual;
@@ -1014,7 +1016,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_jump_when_state_tracking_erro
10141016

10151017
// Move joint back to the first goal
10161018
points = {{first_goal}};
1017-
publish(time_from_start, points);
1019+
publish(time_from_start, points, rclcpp::Time());
10181020
traj_controller_->wait_for_trajectory(executor);
10191021

10201022
// One the first update(s) there should be a "jump" in the goal direction from command
@@ -1057,7 +1059,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
10571059
time_from_start.sec = 1;
10581060
time_from_start.nanosec = 0;
10591061
std::vector<std::vector<double>> points{{first_goal}};
1060-
publish(time_from_start, points);
1062+
publish(time_from_start, points, rclcpp::Time());
10611063
traj_controller_->wait_for_trajectory(executor);
10621064
updateController(rclcpp::Duration::from_seconds(1.1));
10631065

@@ -1074,7 +1076,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
10741076

10751077
// Move joint further in the same direction as before (to the second goal)
10761078
points = {{second_goal}};
1077-
publish(time_from_start, points);
1079+
publish(time_from_start, points, rclcpp::Time());
10781080
traj_controller_->wait_for_trajectory(executor);
10791081

10801082
// One the first update(s) there **should not** be a "jump" in opposite direction from command
@@ -1101,7 +1103,7 @@ TEST_P(TrajectoryControllerTestParameterized, test_no_jump_when_state_tracking_e
11011103

11021104
// Move joint back to the first goal
11031105
points = {{first_goal}};
1104-
publish(time_from_start, points);
1106+
publish(time_from_start, points, rclcpp::Time());
11051107
traj_controller_->wait_for_trajectory(executor);
11061108

11071109
// One the first update(s) there **should not** be a "jump" in the goal direction from command

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -279,7 +279,7 @@ class TrajectoryControllerTest : public ::testing::Test
279279
*/
280280
void publish(
281281
const builtin_interfaces::msg::Duration & delay_btwn_points,
282-
const std::vector<std::vector<double>> & points, rclcpp::Time start_time = rclcpp::Time(),
282+
const std::vector<std::vector<double>> & points, rclcpp::Time start_time,
283283
const std::vector<std::string> & joint_names = {},
284284
const std::vector<std::vector<double>> & points_velocities = {})
285285
{

0 commit comments

Comments
 (0)