@@ -137,7 +137,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
137137 auto current_external_msg = traj_external_point_ptr_->get_trajectory_msg ();
138138 auto new_external_msg = traj_msg_external_point_ptr_.readFromRT ();
139139 // Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
140- if (current_external_msg != *new_external_msg && (*( rt_has_pending_goal_. readFromRT ()) && !active_goal) == false ) {
140+ if (current_external_msg != *new_external_msg && (rt_has_pending_goal_ && !active_goal) == false ) {
141141 fill_partial_goal (*new_external_msg);
142142 sort_to_local_joint_order (*new_external_msg);
143143 // TODO(denis): Add here integration of position and velocity
@@ -204,8 +204,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
204204
205205 // have we reached the end, are not holding position, and is a timeout configured?
206206 // Check independently of other tolerances
207- if (!before_last_point && *(rt_is_holding_.readFromRT ()) == false && cmd_timeout_ > 0.0 &&
208- time_difference > cmd_timeout_) {
207+ if (!before_last_point && !rt_is_holding_ && cmd_timeout_ > 0.0 && time_difference > cmd_timeout_) {
209208 RCLCPP_WARN (logger, " Aborted due to command timeout" );
210209
211210 traj_msg_external_point_ptr_.reset ();
@@ -219,13 +218,13 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
219218 // Always check the state tolerance on the first sample in case the first sample
220219 // is the last point
221220 // print output per default, goal will be aborted afterwards
222- if ((before_last_point || first_sample) && *( rt_is_holding_. readFromRT ()) == false &&
221+ if ((before_last_point || first_sample) && ! rt_is_holding_ &&
223222 !check_state_tolerance_per_joint (state_error_, index, active_tol->state_tolerance [index],
224223 true /* show_errors */ )) {
225224 tolerance_violated_while_moving = true ;
226225 }
227226 // past the final point, check that we end up inside goal tolerance
228- if (!before_last_point && *( rt_is_holding_. readFromRT ()) == false &&
227+ if (!before_last_point && ! rt_is_holding_ &&
229228 !check_state_tolerance_per_joint (state_error_, index, active_tol->goal_state_tolerance [index],
230229 false /* show_errors */ )) {
231230 outside_goal_tolerance = true ;
@@ -295,7 +294,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
295294 // TODO(matthew-reynolds): Need a lock-free write here
296295 // See https://github.com/ros-controls/ros2_controllers/issues/168
297296 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
298- rt_has_pending_goal_. writeFromNonRT ( false ) ;
297+ rt_has_pending_goal_ = false ;
299298
300299 RCLCPP_WARN (logger, " Aborted due to state tolerance violation" );
301300
@@ -311,7 +310,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
311310 // TODO(matthew-reynolds): Need a lock-free write here
312311 // See https://github.com/ros-controls/ros2_controllers/issues/168
313312 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
314- rt_has_pending_goal_. writeFromNonRT ( false ) ;
313+ rt_has_pending_goal_ = false ;
315314
316315 RCLCPP_INFO (logger, " Goal reached, success!" );
317316
@@ -328,21 +327,21 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
328327 // TODO(matthew-reynolds): Need a lock-free write here
329328 // See https://github.com/ros-controls/ros2_controllers/issues/168
330329 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
331- rt_has_pending_goal_. writeFromNonRT ( false ) ;
330+ rt_has_pending_goal_ = false ;
332331
333332 RCLCPP_WARN (logger, error_string.c_str ());
334333
335334 traj_msg_external_point_ptr_.reset ();
336335 traj_msg_external_point_ptr_.initRT (set_hold_position ());
337336 }
338337 }
339- } else if (tolerance_violated_while_moving && *( rt_has_pending_goal_. readFromRT ()) == false ) {
338+ } else if (tolerance_violated_while_moving && ! rt_has_pending_goal_) {
340339 // we need to ensure that there is no pending goal -> we get a race condition otherwise
341340 RCLCPP_ERROR (logger, " Holding position due to state tolerance violation" );
342341
343342 traj_msg_external_point_ptr_.reset ();
344343 traj_msg_external_point_ptr_.initRT (set_hold_position ());
345- } else if (!before_last_point && !within_goal_time && *( rt_has_pending_goal_. readFromRT ()) == false ) {
344+ } else if (!before_last_point && !within_goal_time && ! rt_has_pending_goal_) {
346345 RCLCPP_ERROR (logger, " Exceeded goal_time_tolerance: holding position..." );
347346
348347 traj_msg_external_point_ptr_.reset ();
0 commit comments