@@ -115,7 +115,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
115115 const auto current_trajectory_msg = current_trajectory_->get_trajectory_msg ();
116116 auto new_external_msg = new_trajectory_msg_.readFromRT ();
117117 // Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
118- if (current_trajectory_msg != *new_external_msg && (*( rt_has_pending_goal_. readFromRT ()) && !active_goal) == false ) {
118+ if (current_trajectory_msg != *new_external_msg && (rt_has_pending_goal_ && !active_goal) == false ) {
119119 fill_partial_goal (*new_external_msg);
120120 sort_to_local_joint_order (*new_external_msg);
121121 // TODO(denis): Add here integration of position and velocity
@@ -175,8 +175,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
175175
176176 // have we reached the end, are not holding position, and is a timeout configured?
177177 // Check independently of other tolerances
178- if (!before_last_point && *(rt_is_holding_.readFromRT ()) == false && cmd_timeout_ > 0.0 &&
179- time_difference > cmd_timeout_) {
178+ if (!before_last_point && !rt_is_holding_ && cmd_timeout_ > 0.0 && time_difference > cmd_timeout_) {
180179 RCLCPP_WARN (logger, " Aborted due to command timeout" );
181180
182181 new_trajectory_msg_.reset ();
@@ -190,13 +189,13 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
190189 // Always check the state tolerance on the first sample in case the first sample
191190 // is the last point
192191 // print output per default, goal will be aborted afterwards
193- if ((before_last_point || first_sample) && *( rt_is_holding_. readFromRT ()) == false &&
192+ if ((before_last_point || first_sample) && ! rt_is_holding_ &&
194193 !check_state_tolerance_per_joint (state_error_, index, active_tol->state_tolerance [index],
195194 true /* show_errors */ )) {
196195 tolerance_violated_while_moving = true ;
197196 }
198197 // past the final point, check that we end up inside goal tolerance
199- if (!before_last_point && *( rt_is_holding_. readFromRT ()) == false &&
198+ if (!before_last_point && ! rt_is_holding_ &&
200199 !check_state_tolerance_per_joint (state_error_, index, active_tol->goal_state_tolerance [index],
201200 false /* show_errors */ )) {
202201 outside_goal_tolerance = true ;
@@ -277,7 +276,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
277276 // TODO(matthew-reynolds): Need a lock-free write here
278277 // See https://github.com/ros-controls/ros2_controllers/issues/168
279278 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
280- rt_has_pending_goal_. writeFromNonRT ( false ) ;
279+ rt_has_pending_goal_ = false ;
281280
282281 RCLCPP_WARN (logger, " Aborted due to state tolerance violation" );
283282
@@ -293,7 +292,7 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
293292 // TODO(matthew-reynolds): Need a lock-free write here
294293 // See https://github.com/ros-controls/ros2_controllers/issues/168
295294 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
296- rt_has_pending_goal_. writeFromNonRT ( false ) ;
295+ rt_has_pending_goal_ = false ;
297296
298297 RCLCPP_INFO (logger, " Goal reached, success!" );
299298
@@ -310,21 +309,21 @@ controller_interface::return_type ScaledJointTrajectoryController::update(const
310309 // TODO(matthew-reynolds): Need a lock-free write here
311310 // See https://github.com/ros-controls/ros2_controllers/issues/168
312311 rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
313- rt_has_pending_goal_. writeFromNonRT ( false ) ;
312+ rt_has_pending_goal_ = false ;
314313
315314 RCLCPP_WARN (logger, " %s" , error_string.c_str ());
316315
317316 new_trajectory_msg_.reset ();
318317 new_trajectory_msg_.initRT (set_hold_position ());
319318 }
320319 }
321- } else if (tolerance_violated_while_moving && *( rt_has_pending_goal_. readFromRT ()) == false ) {
320+ } else if (tolerance_violated_while_moving && ! rt_has_pending_goal_) {
322321 // we need to ensure that there is no pending goal -> we get a race condition otherwise
323322 RCLCPP_ERROR (logger, " Holding position due to state tolerance violation" );
324323
325324 new_trajectory_msg_.reset ();
326325 new_trajectory_msg_.initRT (set_hold_position ());
327- } else if (!before_last_point && !within_goal_time && *( rt_has_pending_goal_. readFromRT ()) == false ) {
326+ } else if (!before_last_point && !within_goal_time && ! rt_has_pending_goal_) {
328327 RCLCPP_ERROR (logger, " Exceeded goal_time_tolerance: holding position..." );
329328
330329 new_trajectory_msg_.reset ();
0 commit comments