Skip to content

Commit f1bc4f8

Browse files
authored
Fix format (#1821)
1 parent d4255df commit f1bc4f8

File tree

1 file changed

+4
-3
lines changed

1 file changed

+4
-3
lines changed

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 4 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -404,7 +404,9 @@ TEST_F(TrajectoryControllerTest, time_from_start_populated)
404404
subscribeToState(executor);
405405

406406
// schedule a single waypoint at 100ms:
407-
builtin_interfaces::msg::Duration tfs; tfs.sec = 0; tfs.nanosec = 100000000;
407+
builtin_interfaces::msg::Duration tfs;
408+
tfs.sec = 0;
409+
tfs.nanosec = 100000000;
408410
publish(tfs, {INITIAL_POS_JOINTS}, rclcpp::Time(0));
409411
traj_controller_->wait_for_trajectory(executor);
410412

@@ -414,11 +416,10 @@ TEST_F(TrajectoryControllerTest, time_from_start_populated)
414416

415417
auto state = getState();
416418
ASSERT_TRUE(state);
417-
EXPECT_EQ(state->feedback.time_from_start.sec, 0u);
419+
EXPECT_EQ(state->feedback.time_from_start.sec, 0u);
418420
EXPECT_EQ(state->feedback.time_from_start.nanosec, 100000000u);
419421
}
420422

421-
422423
/**
423424
* @brief check if dynamic parameters are updated
424425
*/

0 commit comments

Comments
 (0)