Skip to content

Commit 1e8e2db

Browse files
committed
Fixe race condition from ros-controls#565
1 parent 8e6697b commit 1e8e2db

File tree

1 file changed

+6
-0
lines changed

1 file changed

+6
-0
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -155,6 +155,8 @@ controller_interface::return_type JointTrajectoryController::update(
155155
sort_to_local_joint_order(*new_external_msg);
156156
// TODO(denis): Add here integration of position and velocity
157157
traj_external_point_ptr_->update(*new_external_msg);
158+
// set the active trajectory pointer to the new goal
159+
traj_point_active_ptr_ = &traj_external_point_ptr_;
158160
}
159161

160162
// TODO(anyone): can I here also use const on joint_interface since the reference_wrapper is not
@@ -318,6 +320,8 @@ controller_interface::return_type JointTrajectoryController::update(
318320
// TODO(matthew-reynolds): Need a lock-free write here
319321
// See https://github.com/ros-controls/ros2_controllers/issues/168
320322
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
323+
// remove the active trajectory pointer so that we stop commanding the hardware
324+
traj_point_active_ptr_ = nullptr;
321325

322326
// check goal tolerance
323327
}
@@ -331,6 +335,8 @@ controller_interface::return_type JointTrajectoryController::update(
331335
// TODO(matthew-reynolds): Need a lock-free write here
332336
// See https://github.com/ros-controls/ros2_controllers/issues/168
333337
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
338+
// remove the active trajectory pointer so that we stop commanding the hardware
339+
traj_point_active_ptr_ = nullptr;
334340

335341
RCLCPP_INFO(get_node()->get_logger(), "Goal reached, success!");
336342
}

0 commit comments

Comments
 (0)