Skip to content

Commit e1ba1c2

Browse files
Improve test criterion for timeout test
1 parent 51d1672 commit e1ba1c2

File tree

1 file changed

+11
-2
lines changed

1 file changed

+11
-2
lines changed

joint_trajectory_controller/test/test_trajectory_controller.cpp

+11-2
Original file line numberDiff line numberDiff line change
@@ -658,7 +658,8 @@ TEST_P(TrajectoryControllerTestParameterized, timeout)
658658
rclcpp::executors::MultiThreadedExecutor executor;
659659
constexpr double cmd_timeout = 0.1;
660660
rclcpp::Parameter cmd_timeout_parameter("cmd_timeout", cmd_timeout);
661-
SetUpAndActivateTrajectoryController(executor, true, {cmd_timeout_parameter}, false);
661+
double kp = 1.0; // activate feedback control for testing velocity/effort PID
662+
SetUpAndActivateTrajectoryController(executor, true, {cmd_timeout_parameter}, false, kp);
662663
subscribeToState();
663664

664665
// send msg
@@ -695,7 +696,15 @@ TEST_P(TrajectoryControllerTestParameterized, timeout)
695696
// should be not more than one point now (from hold position)
696697
EXPECT_FALSE(traj_controller_->has_nontrivial_traj());
697698
// should hold last position with zero velocity
698-
expectHoldingPoint(points.at(2));
699+
if (traj_controller_->has_position_command_interface())
700+
{
701+
expectHoldingPoint(points.at(2));
702+
}
703+
else
704+
{
705+
// no integration to position state interface from velocity/acceleration
706+
expectHoldingPoint(INITIAL_POS_JOINTS);
707+
}
699708

700709
executor.cancel();
701710
}

0 commit comments

Comments
 (0)