Skip to content

Commit eac9765

Browse files
Break deadlock
1 parent 6d17547 commit eac9765

File tree

2 files changed

+5
-2
lines changed

2 files changed

+5
-2
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

+1-1
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
177177
// Timeout to consider commands old
178178
std::chrono::milliseconds cmd_timeout_{500};
179179
// save the timestamp when the last msg was received
180-
rclcpp::Time last_msg_received_;
180+
rclcpp::Time last_msg_received_{0};
181181

182182
// TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
183183
bool subscriber_is_active_ = false;

joint_trajectory_controller/src/joint_trajectory_controller.cpp

+4-1
Original file line numberDiff line numberDiff line change
@@ -177,7 +177,7 @@ controller_interface::return_type JointTrajectoryController::update(
177177
// is timeout configured?
178178
if (params_.cmd_timeout > 0.0)
179179
{
180-
if (time - last_msg_received_ > cmd_timeout_)
180+
if (last_msg_received_.seconds() > 0 && (time - last_msg_received_ > cmd_timeout_))
181181
{
182182
RCLCPP_WARN(get_node()->get_logger(), "Aborted due to timeout");
183183
set_hold_position();
@@ -1410,6 +1410,9 @@ void JointTrajectoryController::set_hold_position()
14101410

14111411
auto traj_msg = std::make_shared<trajectory_msgs::msg::JointTrajectory>(empty_msg);
14121412
add_new_trajectory_msg(traj_msg);
1413+
1414+
// otherwise we will end up in a loop after timeout
1415+
last_msg_received_ = rclcpp::Time(0, 0, last_msg_received_.get_clock_type());
14131416
}
14141417

14151418
bool JointTrajectoryController::contains_interface_type(

0 commit comments

Comments
 (0)