@@ -157,8 +157,7 @@ controller_interface::return_type JointTrajectoryController::update(
157
157
auto new_external_msg = new_trajectory_msg_.readFromRT ();
158
158
// Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
159
159
if (
160
- current_trajectory_msg != *new_external_msg &&
161
- (*(rt_has_pending_goal_.readFromRT ()) && !active_goal) == false )
160
+ current_trajectory_msg != *new_external_msg && (rt_has_pending_goal_ && !active_goal) == false )
162
161
{
163
162
fill_partial_goal (*new_external_msg);
164
163
sort_to_local_joint_order (*new_external_msg);
@@ -230,7 +229,7 @@ controller_interface::return_type JointTrajectoryController::update(
230
229
// have we reached the end, are not holding position, and is a timeout configured?
231
230
// Check independently of other tolerances
232
231
if (
233
- !before_last_point && *( rt_is_holding_. readFromRT ()) == false && cmd_timeout_ > 0.0 &&
232
+ !before_last_point && ! rt_is_holding_ && cmd_timeout_ > 0.0 &&
234
233
time_difference > cmd_timeout_)
235
234
{
236
235
RCLCPP_WARN (logger, " Aborted due to command timeout" );
@@ -248,15 +247,15 @@ controller_interface::return_type JointTrajectoryController::update(
248
247
// is the last point
249
248
// print output per default, goal will be aborted afterwards
250
249
if (
251
- (before_last_point || first_sample) && *( rt_is_holding_. readFromRT ()) == false &&
250
+ (before_last_point || first_sample) && ! rt_is_holding_ &&
252
251
!check_state_tolerance_per_joint (
253
252
state_error_, index , active_tol->state_tolerance [index ], true /* show_errors */ ))
254
253
{
255
254
tolerance_violated_while_moving = true ;
256
255
}
257
256
// past the final point, check that we end up inside goal tolerance
258
257
if (
259
- !before_last_point && *( rt_is_holding_. readFromRT ()) == false &&
258
+ !before_last_point && ! rt_is_holding_ &&
260
259
!check_state_tolerance_per_joint (
261
260
state_error_, index , active_tol->goal_state_tolerance [index ], false /* show_errors */ ))
262
261
{
@@ -357,7 +356,7 @@ controller_interface::return_type JointTrajectoryController::update(
357
356
// TODO(matthew-reynolds): Need a lock-free write here
358
357
// See https://github.com/ros-controls/ros2_controllers/issues/168
359
358
rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
360
- rt_has_pending_goal_. writeFromNonRT ( false ) ;
359
+ rt_has_pending_goal_ = false ;
361
360
362
361
RCLCPP_WARN (logger, " Aborted due to state tolerance violation" );
363
362
@@ -376,7 +375,7 @@ controller_interface::return_type JointTrajectoryController::update(
376
375
// TODO(matthew-reynolds): Need a lock-free write here
377
376
// See https://github.com/ros-controls/ros2_controllers/issues/168
378
377
rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
379
- rt_has_pending_goal_. writeFromNonRT ( false ) ;
378
+ rt_has_pending_goal_ = false ;
380
379
381
380
RCLCPP_INFO (logger, " Goal reached, success!" );
382
381
@@ -395,7 +394,7 @@ controller_interface::return_type JointTrajectoryController::update(
395
394
// TODO(matthew-reynolds): Need a lock-free write here
396
395
// See https://github.com/ros-controls/ros2_controllers/issues/168
397
396
rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
398
- rt_has_pending_goal_. writeFromNonRT ( false ) ;
397
+ rt_has_pending_goal_ = false ;
399
398
400
399
RCLCPP_WARN (logger, " %s" , error_string.c_str ());
401
400
@@ -404,16 +403,15 @@ controller_interface::return_type JointTrajectoryController::update(
404
403
}
405
404
}
406
405
}
407
- else if (tolerance_violated_while_moving && *( rt_has_pending_goal_. readFromRT ()) == false )
406
+ else if (tolerance_violated_while_moving && ! rt_has_pending_goal_)
408
407
{
409
408
// we need to ensure that there is no pending goal -> we get a race condition otherwise
410
409
RCLCPP_ERROR (logger, " Holding position due to state tolerance violation" );
411
410
412
411
new_trajectory_msg_.reset ();
413
412
new_trajectory_msg_.initRT (set_hold_position ());
414
413
}
415
- else if (
416
- !before_last_point && !within_goal_time && *(rt_has_pending_goal_.readFromRT ()) == false )
414
+ else if (!before_last_point && !within_goal_time && !rt_has_pending_goal_)
417
415
{
418
416
RCLCPP_ERROR (logger, " Exceeded goal_time_tolerance: holding position..." );
419
417
@@ -1028,7 +1026,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
1028
1026
1029
1027
// The controller should start by holding position at the beginning of active state
1030
1028
add_new_trajectory_msg (set_hold_position ());
1031
- rt_is_holding_. writeFromNonRT ( true ) ;
1029
+ rt_is_holding_ = true ;
1032
1030
1033
1031
// parse timeout parameter
1034
1032
if (params_.cmd_timeout > 0.0 )
@@ -1060,7 +1058,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
1060
1058
const auto active_goal = *rt_active_goal_.readFromNonRT ();
1061
1059
if (active_goal)
1062
1060
{
1063
- rt_has_pending_goal_. writeFromNonRT ( false ) ;
1061
+ rt_has_pending_goal_ = false ;
1064
1062
auto action_res = std::make_shared<FollowJTrajAction::Result>();
1065
1063
action_res->set__error_code (FollowJTrajAction::Result::INVALID_GOAL);
1066
1064
action_res->set__error_string (" Current goal cancelled during deactivate transition." );
@@ -1178,7 +1176,7 @@ void JointTrajectoryController::topic_callback(
1178
1176
if (subscriber_is_active_)
1179
1177
{
1180
1178
add_new_trajectory_msg (msg);
1181
- rt_is_holding_. writeFromNonRT ( false ) ;
1179
+ rt_is_holding_ = false ;
1182
1180
}
1183
1181
};
1184
1182
@@ -1217,7 +1215,7 @@ rclcpp_action::CancelResponse JointTrajectoryController::goal_cancelled_callback
1217
1215
get_node ()->get_logger (), " Canceling active action goal because cancel callback received." );
1218
1216
1219
1217
// Mark the current goal as canceled
1220
- rt_has_pending_goal_. writeFromNonRT ( false ) ;
1218
+ rt_has_pending_goal_ = false ;
1221
1219
auto action_res = std::make_shared<FollowJTrajAction::Result>();
1222
1220
active_goal->setCanceled (action_res);
1223
1221
rt_active_goal_.writeFromNonRT (RealtimeGoalHandlePtr ());
@@ -1232,7 +1230,7 @@ void JointTrajectoryController::goal_accepted_callback(
1232
1230
std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle)
1233
1231
{
1234
1232
// mark a pending goal
1235
- rt_has_pending_goal_. writeFromNonRT ( true ) ;
1233
+ rt_has_pending_goal_ = true ;
1236
1234
1237
1235
// Update new trajectory
1238
1236
{
@@ -1241,7 +1239,7 @@ void JointTrajectoryController::goal_accepted_callback(
1241
1239
std::make_shared<trajectory_msgs::msg::JointTrajectory>(goal_handle->get_goal ()->trajectory );
1242
1240
1243
1241
add_new_trajectory_msg (traj_msg);
1244
- rt_is_holding_. writeFromNonRT ( false ) ;
1242
+ rt_is_holding_ = false ;
1245
1243
}
1246
1244
1247
1245
// Update the active goal
@@ -1593,7 +1591,7 @@ JointTrajectoryController::set_hold_position()
1593
1591
hold_position_msg_ptr_->points [0 ].positions = state_current_.positions ;
1594
1592
1595
1593
// set flag, otherwise tolerances will be checked with holding position too
1596
- rt_is_holding_. writeFromNonRT ( true ) ;
1594
+ rt_is_holding_ = true ;
1597
1595
1598
1596
return hold_position_msg_ptr_;
1599
1597
}
@@ -1607,7 +1605,7 @@ JointTrajectoryController::set_success_trajectory_point()
1607
1605
hold_position_msg_ptr_->points [0 ].time_from_start = rclcpp::Duration (0 , 0 );
1608
1606
1609
1607
// set flag, otherwise tolerances will be checked with success_trajectory_point too
1610
- rt_is_holding_. writeFromNonRT ( true ) ;
1608
+ rt_is_holding_ = true ;
1611
1609
1612
1610
return hold_position_msg_ptr_;
1613
1611
}
0 commit comments