Skip to content

Commit

Permalink
Fix period calculation in trajectory_actions test
Browse files Browse the repository at this point in the history
The generated period was more of an uptime
  • Loading branch information
fmauch committed Nov 27, 2024
1 parent 0aa4a56 commit 17adfc3
Showing 1 changed file with 6 additions and 2 deletions.
8 changes: 6 additions & 2 deletions joint_trajectory_controller/test/test_trajectory_actions.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -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;
}
});

Expand Down

0 comments on commit 17adfc3

Please sign in to comment.