Skip to content

Commit 391ad84

Browse files
[JTC] Fix time sources and wrong checks in tests (#686)
* Fix time sources and wrong checks in tests * Use time from update-method instead of node clock * Readd test of last command in test_goal_tolerances_fail --------- Co-authored-by: Bence Magyar <[email protected]>
1 parent ddd5f7c commit 391ad84

File tree

4 files changed

+28
-27
lines changed

4 files changed

+28
-27
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -231,7 +231,7 @@ controller_interface::return_type JointTrajectoryController::update(
231231
const rclcpp::Time traj_start = (*traj_point_active_ptr_)->get_trajectory_start_time();
232232
const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start;
233233

234-
time_difference = get_node()->now().seconds() - traj_end.seconds();
234+
time_difference = time.seconds() - traj_end.seconds();
235235

236236
if (time_difference > default_tolerances_.goal_time_tolerance)
237237
{

joint_trajectory_controller/test/test_trajectory_actions.cpp

Lines changed: 13 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -66,11 +66,14 @@ class TestTrajectoryActions : public TrajectoryControllerTest
6666
goal_options_.feedback_callback = nullptr;
6767
}
6868

69-
void SetUpExecutor(const std::vector<rclcpp::Parameter> & parameters = {})
69+
void SetUpExecutor(
70+
const std::vector<rclcpp::Parameter> & parameters = {},
71+
bool separate_cmd_and_state_values = false)
7072
{
7173
setup_executor_ = true;
7274

73-
SetUpAndActivateTrajectoryController(executor_, true, parameters);
75+
SetUpAndActivateTrajectoryController(
76+
executor_, true, parameters, separate_cmd_and_state_values);
7477

7578
SetUpActionClient();
7679

@@ -472,15 +475,13 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_goal_tolerances_fail)
472475
rclcpp::Parameter("constraints.joint3.goal", goal_tol),
473476
rclcpp::Parameter("constraints.goal_time", goal_time)};
474477

475-
SetUpExecutor(params);
478+
// separate command from states -> goal won't never be reached
479+
bool separate_cmd_and_state_values = true;
480+
SetUpExecutor(params, separate_cmd_and_state_values);
476481
SetUpControllerHardware();
477482

478-
const double init_pos1 = joint_pos_[0];
479-
const double init_pos2 = joint_pos_[1];
480-
const double init_pos3 = joint_pos_[2];
481-
482483
std::shared_future<typename GoalHandle::SharedPtr> gh_future;
483-
// send goal
484+
// send goal; one point only -> command is directly set to reach this goal (no interpolation)
484485
{
485486
std::vector<JointTrajectoryPoint> points;
486487
JointTrajectoryPoint point;
@@ -502,14 +503,14 @@ TEST_P(TestTrajectoryActionsTestParameterized, test_goal_tolerances_fail)
502503
control_msgs::action::FollowJointTrajectory_Result::GOAL_TOLERANCE_VIOLATED,
503504
common_action_result_code_);
504505

505-
// run an update, it should be holding
506+
// run an update, it should be holding the last received goal
506507
updateController(rclcpp::Duration::from_seconds(0.01));
507508

508509
if (traj_controller_->has_position_command_interface())
509510
{
510-
EXPECT_NEAR(init_pos1, joint_pos_[0], COMMON_THRESHOLD);
511-
EXPECT_NEAR(init_pos2, joint_pos_[1], COMMON_THRESHOLD);
512-
EXPECT_NEAR(init_pos3, joint_pos_[2], COMMON_THRESHOLD);
511+
EXPECT_NEAR(4.0, joint_pos_[0], COMMON_THRESHOLD);
512+
EXPECT_NEAR(5.0, joint_pos_[1], COMMON_THRESHOLD);
513+
EXPECT_NEAR(6.0, joint_pos_[2], COMMON_THRESHOLD);
513514
}
514515
}
515516

joint_trajectory_controller/test/test_trajectory_controller.cpp

Lines changed: 13 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -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]};

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

Lines changed: 1 addition & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -366,13 +366,7 @@ class TrajectoryControllerTest : public ::testing::Test
366366
const auto end_time = start_time + wait_time;
367367
while (clock.now() < end_time)
368368
{
369-
// TODO(christophfroehlich): use the node's clock here for internal comparison
370-
// if using RCL_STEADY_TIME ->
371-
// C++ exception with description
372-
// "can't compare times with different time sources" thrown in the test body.
373-
// traj_controller_->update(clock.now(), clock.now() - start_time);
374-
// maybe we can set the node clock to use RCL_STEADY_TIME too?
375-
traj_controller_->update(node_->get_clock()->now(), clock.now() - start_time);
369+
traj_controller_->update(clock.now(), clock.now() - start_time);
376370
}
377371
}
378372

0 commit comments

Comments
 (0)