Skip to content

Commit e59a007

Browse files
christophfroehlichbmagyar
authored andcommitted
[JTC] Add time-out for trajectory interfaces (backport #609)
1 parent dc20b17 commit e59a007

7 files changed

+212
-12
lines changed

joint_trajectory_controller/doc/parameters.rst

+10
Original file line numberDiff line numberDiff line change
@@ -73,6 +73,16 @@ allow_nonzero_velocity_at_trajectory_end (boolean)
7373

7474
Default: true
7575

76+
cmd_timeout (double)
77+
Timeout after which the input command is considered stale.
78+
Timeout is counted from the end of the trajectory (the last point).
79+
``cmd_timeout`` must be greater than ``constraints.goal_time``,
80+
otherwise ignored.
81+
82+
If zero, timeout is deactivated"
83+
84+
Default: 0.0
85+
7686
constraints (structure)
7787
Default values for tolerances if no explicit values are states in JointTrajectory message.
7888

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -173,7 +173,10 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
173173
// reserved storage for result of the command when closed loop pid adapter is used
174174
std::vector<double> tmp_command_;
175175

176-
realtime_tools::RealtimeBuffer<bool> rt_is_holding_; ///< are we holding position?
176+
// Timeout to consider commands old
177+
double cmd_timeout_;
178+
// Are we holding position?
179+
realtime_tools::RealtimeBuffer<bool> rt_is_holding_;
177180
// TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
178181
bool subscriber_is_active_ = false;
179182
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =

joint_trajectory_controller/include/joint_trajectory_controller/trajectory.hpp

-3
Original file line numberDiff line numberDiff line change
@@ -139,9 +139,6 @@ class Trajectory
139139
return trajectory_msg_;
140140
}
141141

142-
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
143-
rclcpp::Time get_trajectory_start_time() const { return trajectory_start_time_; }
144-
145142
JOINT_TRAJECTORY_CONTROLLER_PUBLIC
146143
bool is_sampled_already() const { return sampled_already_; }
147144

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+42-8
Original file line numberDiff line numberDiff line change
@@ -189,7 +189,7 @@ controller_interface::return_type JointTrajectoryController::update(
189189
state_current_.time_from_start.set__sec(0);
190190
read_state_from_hardware(state_current_);
191191

192-
// currently carrying out a trajectory.
192+
// currently carrying out a trajectory
193193
if (has_active_trajectory())
194194
{
195195
bool first_sample = false;
@@ -214,12 +214,32 @@ controller_interface::return_type JointTrajectoryController::update(
214214

215215
if (valid_point)
216216
{
217+
const rclcpp::Time traj_start = traj_external_point_ptr_->time_from_start();
218+
// this is the time instance
219+
// - started with the first segment: when the first point will be reached (in the future)
220+
// - later: when the point of the current segment was reached
221+
const rclcpp::Time segment_time_from_start = traj_start + start_segment_itr->time_from_start;
222+
// time_difference is
223+
// - negative until first point is reached
224+
// - counting from zero to time_from_start of next point
225+
double time_difference = time.seconds() - segment_time_from_start.seconds();
217226
bool tolerance_violated_while_moving = false;
218227
bool outside_goal_tolerance = false;
219228
bool within_goal_time = true;
220-
double time_difference = 0.0;
221229
const bool before_last_point = end_segment_itr != traj_external_point_ptr_->end();
222230

231+
// have we reached the end, are not holding position, and is a timeout configured?
232+
// Check independently of other tolerances
233+
if (
234+
!before_last_point && *(rt_is_holding_.readFromRT()) == false && cmd_timeout_ > 0.0 &&
235+
time_difference > cmd_timeout_)
236+
{
237+
RCLCPP_WARN(get_node()->get_logger(), "Aborted due to command timeout");
238+
239+
traj_msg_external_point_ptr_.reset();
240+
traj_msg_external_point_ptr_.initRT(set_hold_position());
241+
}
242+
223243
// Check state/goal tolerance
224244
for (size_t index = 0; index < dof_; ++index)
225245
{
@@ -246,12 +266,6 @@ controller_interface::return_type JointTrajectoryController::update(
246266

247267
if (default_tolerances_.goal_time_tolerance != 0.0)
248268
{
249-
// if we exceed goal_time_tolerance set it to aborted
250-
const rclcpp::Time traj_start = traj_external_point_ptr_->get_trajectory_start_time();
251-
const rclcpp::Time traj_end = traj_start + start_segment_itr->time_from_start;
252-
253-
time_difference = time.seconds() - traj_end.seconds();
254-
255269
if (time_difference > default_tolerances_.goal_time_tolerance)
256270
{
257271
within_goal_time = false;
@@ -946,6 +960,26 @@ controller_interface::CallbackReturn JointTrajectoryController::on_configure(
946960
std::string(get_node()->get_name()) + "/query_state",
947961
std::bind(&JointTrajectoryController::query_state_service, this, _1, _2));
948962

963+
if (params_.cmd_timeout > 0.0)
964+
{
965+
if (params_.cmd_timeout > default_tolerances_.goal_time_tolerance)
966+
{
967+
cmd_timeout_ = params_.cmd_timeout;
968+
}
969+
else
970+
{
971+
// deactivate timeout
972+
RCLCPP_WARN(
973+
logger, "Command timeout must be higher than goal_time tolerance (%f vs. %f)",
974+
params_.cmd_timeout, default_tolerances_.goal_time_tolerance);
975+
cmd_timeout_ = 0.0;
976+
}
977+
}
978+
else
979+
{
980+
cmd_timeout_ = 0.0;
981+
}
982+
949983
return CallbackReturn::SUCCESS;
950984
}
951985

joint_trajectory_controller/src/joint_trajectory_controller_parameters.yaml

+8
Original file line numberDiff line numberDiff line change
@@ -91,6 +91,14 @@ joint_trajectory_controller:
9191
default_value: true,
9292
description: "If false, the last velocity point has to be zero or the goal will be rejected",
9393
}
94+
cmd_timeout: {
95+
type: double,
96+
default_value: 0.0, # seconds
97+
description: "Timeout after which the input command is considered stale.
98+
Timeout is counted from the end of the trajectory (the last point).
99+
cmd_timeout must be greater than constraints.goal_time, otherwise ignored.
100+
If zero, timeout is deactivated",
101+
}
94102
gains:
95103
__map_joints:
96104
p: {

joint_trajectory_controller/test/test_trajectory_controller.cpp

+141
Original file line numberDiff line numberDiff line change
@@ -617,6 +617,147 @@ TEST_P(TrajectoryControllerTestParameterized, position_error_not_normalized)
617617
executor.cancel();
618618
}
619619

620+
/**
621+
* @brief cmd_timeout must be greater than constraints.goal_time
622+
*/
623+
TEST_P(TrajectoryControllerTestParameterized, accept_correct_cmd_timeout)
624+
{
625+
rclcpp::executors::MultiThreadedExecutor executor;
626+
// zero is default value, just for demonstration
627+
double cmd_timeout = 3.0;
628+
rclcpp::Parameter cmd_timeout_parameter("cmd_timeout", cmd_timeout);
629+
rclcpp::Parameter goal_time_parameter("constraints.goal_time", 2.0);
630+
SetUpAndActivateTrajectoryController(
631+
executor, {cmd_timeout_parameter, goal_time_parameter}, false);
632+
633+
EXPECT_DOUBLE_EQ(cmd_timeout, traj_controller_->get_cmd_timeout());
634+
}
635+
636+
/**
637+
* @brief cmd_timeout must be greater than constraints.goal_time
638+
*/
639+
TEST_P(TrajectoryControllerTestParameterized, decline_false_cmd_timeout)
640+
{
641+
rclcpp::executors::MultiThreadedExecutor executor;
642+
// zero is default value, just for demonstration
643+
rclcpp::Parameter cmd_timeout_parameter("cmd_timeout", 1.0);
644+
rclcpp::Parameter goal_time_parameter("constraints.goal_time", 2.0);
645+
SetUpAndActivateTrajectoryController(
646+
executor, {cmd_timeout_parameter, goal_time_parameter}, false);
647+
648+
EXPECT_DOUBLE_EQ(0.0, traj_controller_->get_cmd_timeout());
649+
}
650+
651+
/**
652+
* @brief check if no timeout is triggered
653+
*/
654+
TEST_P(TrajectoryControllerTestParameterized, no_timeout)
655+
{
656+
rclcpp::executors::MultiThreadedExecutor executor;
657+
// zero is default value, just for demonstration
658+
rclcpp::Parameter cmd_timeout_parameter("cmd_timeout", 0.0);
659+
SetUpAndActivateTrajectoryController(executor, {cmd_timeout_parameter}, false);
660+
subscribeToState();
661+
662+
size_t n_joints = joint_names_.size();
663+
664+
// send msg
665+
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
666+
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
667+
// *INDENT-OFF*
668+
std::vector<std::vector<double>> points{
669+
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
670+
std::vector<std::vector<double>> points_velocities{
671+
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
672+
// *INDENT-ON*
673+
publish(time_from_start, points, rclcpp::Time(0, 0, RCL_STEADY_TIME), {}, points_velocities);
674+
traj_controller_->wait_for_trajectory(executor);
675+
676+
// first update
677+
updateController(rclcpp::Duration(FIRST_POINT_TIME) * 4);
678+
679+
// Spin to receive latest state
680+
executor.spin_some();
681+
auto state_msg = getState();
682+
ASSERT_TRUE(state_msg);
683+
684+
// has the msg the correct vector sizes?
685+
EXPECT_EQ(n_joints, state_msg->reference.positions.size());
686+
687+
// is the trajectory still active?
688+
EXPECT_TRUE(traj_controller_->has_active_traj());
689+
// should still hold the points from above
690+
EXPECT_TRUE(traj_controller_->has_nontrivial_traj());
691+
EXPECT_NEAR(state_msg->reference.positions[0], points.at(2).at(0), 1e-2);
692+
EXPECT_NEAR(state_msg->reference.positions[1], points.at(2).at(1), 1e-2);
693+
EXPECT_NEAR(state_msg->reference.positions[2], points.at(2).at(2), 1e-2);
694+
// value of velocities is different from above due to spline interpolation
695+
EXPECT_GT(state_msg->reference.velocities[0], 0.0);
696+
EXPECT_GT(state_msg->reference.velocities[1], 0.0);
697+
EXPECT_GT(state_msg->reference.velocities[2], 0.0);
698+
699+
executor.cancel();
700+
}
701+
702+
/**
703+
* @brief check if timeout is triggered
704+
*/
705+
TEST_P(TrajectoryControllerTestParameterized, timeout)
706+
{
707+
rclcpp::executors::MultiThreadedExecutor executor;
708+
constexpr double cmd_timeout = 0.1;
709+
rclcpp::Parameter cmd_timeout_parameter("cmd_timeout", cmd_timeout);
710+
double kp = 1.0; // activate feedback control for testing velocity/effort PID
711+
SetUpAndActivateTrajectoryController(executor, {cmd_timeout_parameter}, false, kp);
712+
subscribeToState();
713+
714+
// send msg
715+
constexpr auto FIRST_POINT_TIME = std::chrono::milliseconds(250);
716+
builtin_interfaces::msg::Duration time_from_start{rclcpp::Duration(FIRST_POINT_TIME)};
717+
// *INDENT-OFF*
718+
std::vector<std::vector<double>> points{
719+
{{3.3, 4.4, 6.6}}, {{7.7, 8.8, 9.9}}, {{10.10, 11.11, 12.12}}};
720+
std::vector<std::vector<double>> points_velocities{
721+
{{0.01, 0.01, 0.01}}, {{0.05, 0.05, 0.05}}, {{0.06, 0.06, 0.06}}};
722+
// *INDENT-ON*
723+
724+
publish(time_from_start, points, rclcpp::Time(0, 0, RCL_STEADY_TIME), {}, points_velocities);
725+
traj_controller_->wait_for_trajectory(executor);
726+
727+
// update until end of trajectory -> no timeout should have occurred
728+
updateController(rclcpp::Duration(FIRST_POINT_TIME) * 3);
729+
// is a trajectory active?
730+
EXPECT_TRUE(traj_controller_->has_active_traj());
731+
// should have the trajectory with three points
732+
EXPECT_TRUE(traj_controller_->has_nontrivial_traj());
733+
734+
// update until timeout should have happened
735+
updateController(rclcpp::Duration(FIRST_POINT_TIME));
736+
737+
// Spin to receive latest state
738+
executor.spin_some();
739+
auto state_msg = getState();
740+
ASSERT_TRUE(state_msg);
741+
742+
// after timeout, set_hold_position adds a new trajectory
743+
// is a trajectory active?
744+
EXPECT_TRUE(traj_controller_->has_active_traj());
745+
// should be not more than one point now (from hold position)
746+
EXPECT_FALSE(traj_controller_->has_nontrivial_traj());
747+
// should hold last position with zero velocity
748+
if (traj_controller_->has_position_command_interface())
749+
{
750+
expectHoldingPoint(points.at(2));
751+
}
752+
else
753+
{
754+
// no integration to position state interface from velocity/acceleration
755+
expectHoldingPoint(INITIAL_POS_JOINTS);
756+
}
757+
758+
executor.cancel();
759+
}
760+
620761
/**
621762
* @brief check if position error of revolute joints are normalized if configured so
622763
*/

joint_trajectory_controller/test/test_trajectory_controller_utils.hpp

+7
Original file line numberDiff line numberDiff line change
@@ -137,6 +137,13 @@ class TestableJointTrajectoryController
137137
return has_active_trajectory() && traj_external_point_ptr_->has_nontrivial_msg() == false;
138138
}
139139

140+
bool has_nontrivial_traj()
141+
{
142+
return has_active_trajectory() && traj_external_point_ptr_->has_nontrivial_msg();
143+
}
144+
145+
double get_cmd_timeout() { return cmd_timeout_; }
146+
140147
rclcpp::WaitSet joint_cmd_sub_wait_set_;
141148
};
142149

0 commit comments

Comments
 (0)