From 17adfc369961a116cfb83fcbaaad7468e469201e Mon Sep 17 00:00:00 2001 From: Felix Exner Date: Sun, 13 Oct 2024 22:25:30 +0200 Subject: [PATCH] Fix period calculation in trajectory_actions test The generated period was more of an uptime --- .../test/test_trajectory_actions.cpp | 8 ++++++-- 1 file changed, 6 insertions(+), 2 deletions(-) diff --git a/joint_trajectory_controller/test/test_trajectory_actions.cpp b/joint_trajectory_controller/test/test_trajectory_actions.cpp index 164f7d0e11..8f45fb66af 100644 --- a/joint_trajectory_controller/test/test_trajectory_actions.cpp +++ b/joint_trajectory_controller/test/test_trajectory_actions.cpp @@ -83,12 +83,16 @@ class TestTrajectoryActions : public TrajectoryControllerTest { // controller hardware cycle update loop auto clock = rclcpp::Clock(RCL_STEADY_TIME); - auto start_time = clock.now(); + auto now_time = clock.now(); + auto start_time = now_time; + auto last_time = start_time; rclcpp::Duration wait = rclcpp::Duration::from_seconds(2.0); auto end_time = start_time + wait; while (clock.now() < end_time) { - traj_controller_->update(clock.now(), clock.now() - start_time); + now_time = clock.now(); + traj_controller_->update(now_time, now_time - last_time); + last_time = now_time; } });