Skip to content

Commit 0dcdd04

Browse files
JTC: Use std::atomic<bool> (#1720)
Co-authored-by: Sai Kishor Kothakota <[email protected]>
1 parent 2a71217 commit 0dcdd04

File tree

2 files changed

+20
-21
lines changed

2 files changed

+20
-21
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
#ifndef JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
1616
#define JOINT_TRAJECTORY_CONTROLLER__JOINT_TRAJECTORY_CONTROLLER_HPP_
1717

18+
#include <atomic>
1819
#include <functional> // for std::reference_wrapper
1920
#include <memory>
2021
#include <string>
@@ -152,7 +153,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
152153
// Timeout to consider commands old
153154
double cmd_timeout_;
154155
// True if holding position or repeating last trajectory point in case of success
155-
realtime_tools::RealtimeBuffer<bool> rt_is_holding_;
156+
std::atomic<bool> rt_is_holding_;
156157
// TODO(karsten1987): eventually activate and deactivate subscriber directly when its supported
157158
bool subscriber_is_active_ = false;
158159
rclcpp::Subscription<trajectory_msgs::msg::JointTrajectory>::SharedPtr joint_command_subscriber_ =
@@ -179,7 +180,7 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
179180

180181
rclcpp_action::Server<FollowJTrajAction>::SharedPtr action_server_;
181182
RealtimeGoalHandleBuffer rt_active_goal_; ///< Currently active action goal, if any.
182-
realtime_tools::RealtimeBuffer<bool> rt_has_pending_goal_; ///< Is there a pending action goal?
183+
std::atomic<bool> rt_has_pending_goal_; ///< Is there a pending action goal?
183184
rclcpp::TimerBase::SharedPtr goal_handle_timer_;
184185
rclcpp::Duration action_monitor_period_ = rclcpp::Duration(50ms);
185186

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 17 additions & 19 deletions
Original file line numberDiff line numberDiff line change
@@ -157,8 +157,7 @@ controller_interface::return_type JointTrajectoryController::update(
157157
auto new_external_msg = new_trajectory_msg_.readFromRT();
158158
// Discard, if a goal is pending but still not active (somewhere stuck in goal_handle_timer_)
159159
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)
162161
{
163162
fill_partial_goal(*new_external_msg);
164163
sort_to_local_joint_order(*new_external_msg);
@@ -230,7 +229,7 @@ controller_interface::return_type JointTrajectoryController::update(
230229
// have we reached the end, are not holding position, and is a timeout configured?
231230
// Check independently of other tolerances
232231
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 &&
234233
time_difference > cmd_timeout_)
235234
{
236235
RCLCPP_WARN(logger, "Aborted due to command timeout");
@@ -248,15 +247,15 @@ controller_interface::return_type JointTrajectoryController::update(
248247
// is the last point
249248
// print output per default, goal will be aborted afterwards
250249
if (
251-
(before_last_point || first_sample) && *(rt_is_holding_.readFromRT()) == false &&
250+
(before_last_point || first_sample) && !rt_is_holding_ &&
252251
!check_state_tolerance_per_joint(
253252
state_error_, index, active_tol->state_tolerance[index], true /* show_errors */))
254253
{
255254
tolerance_violated_while_moving = true;
256255
}
257256
// past the final point, check that we end up inside goal tolerance
258257
if (
259-
!before_last_point && *(rt_is_holding_.readFromRT()) == false &&
258+
!before_last_point && !rt_is_holding_ &&
260259
!check_state_tolerance_per_joint(
261260
state_error_, index, active_tol->goal_state_tolerance[index], false /* show_errors */))
262261
{
@@ -357,7 +356,7 @@ controller_interface::return_type JointTrajectoryController::update(
357356
// TODO(matthew-reynolds): Need a lock-free write here
358357
// See https://github.com/ros-controls/ros2_controllers/issues/168
359358
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
360-
rt_has_pending_goal_.writeFromNonRT(false);
359+
rt_has_pending_goal_ = false;
361360

362361
RCLCPP_WARN(logger, "Aborted due to state tolerance violation");
363362

@@ -376,7 +375,7 @@ controller_interface::return_type JointTrajectoryController::update(
376375
// TODO(matthew-reynolds): Need a lock-free write here
377376
// See https://github.com/ros-controls/ros2_controllers/issues/168
378377
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
379-
rt_has_pending_goal_.writeFromNonRT(false);
378+
rt_has_pending_goal_ = false;
380379

381380
RCLCPP_INFO(logger, "Goal reached, success!");
382381

@@ -395,7 +394,7 @@ controller_interface::return_type JointTrajectoryController::update(
395394
// TODO(matthew-reynolds): Need a lock-free write here
396395
// See https://github.com/ros-controls/ros2_controllers/issues/168
397396
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
398-
rt_has_pending_goal_.writeFromNonRT(false);
397+
rt_has_pending_goal_ = false;
399398

400399
RCLCPP_WARN(logger, "%s", error_string.c_str());
401400

@@ -404,16 +403,15 @@ controller_interface::return_type JointTrajectoryController::update(
404403
}
405404
}
406405
}
407-
else if (tolerance_violated_while_moving && *(rt_has_pending_goal_.readFromRT()) == false)
406+
else if (tolerance_violated_while_moving && !rt_has_pending_goal_)
408407
{
409408
// we need to ensure that there is no pending goal -> we get a race condition otherwise
410409
RCLCPP_ERROR(logger, "Holding position due to state tolerance violation");
411410

412411
new_trajectory_msg_.reset();
413412
new_trajectory_msg_.initRT(set_hold_position());
414413
}
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_)
417415
{
418416
RCLCPP_ERROR(logger, "Exceeded goal_time_tolerance: holding position...");
419417

@@ -1028,7 +1026,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
10281026

10291027
// The controller should start by holding position at the beginning of active state
10301028
add_new_trajectory_msg(set_hold_position());
1031-
rt_is_holding_.writeFromNonRT(true);
1029+
rt_is_holding_ = true;
10321030

10331031
// parse timeout parameter
10341032
if (params_.cmd_timeout > 0.0)
@@ -1060,7 +1058,7 @@ controller_interface::CallbackReturn JointTrajectoryController::on_deactivate(
10601058
const auto active_goal = *rt_active_goal_.readFromNonRT();
10611059
if (active_goal)
10621060
{
1063-
rt_has_pending_goal_.writeFromNonRT(false);
1061+
rt_has_pending_goal_ = false;
10641062
auto action_res = std::make_shared<FollowJTrajAction::Result>();
10651063
action_res->set__error_code(FollowJTrajAction::Result::INVALID_GOAL);
10661064
action_res->set__error_string("Current goal cancelled during deactivate transition.");
@@ -1178,7 +1176,7 @@ void JointTrajectoryController::topic_callback(
11781176
if (subscriber_is_active_)
11791177
{
11801178
add_new_trajectory_msg(msg);
1181-
rt_is_holding_.writeFromNonRT(false);
1179+
rt_is_holding_ = false;
11821180
}
11831181
};
11841182

@@ -1217,7 +1215,7 @@ rclcpp_action::CancelResponse JointTrajectoryController::goal_cancelled_callback
12171215
get_node()->get_logger(), "Canceling active action goal because cancel callback received.");
12181216

12191217
// Mark the current goal as canceled
1220-
rt_has_pending_goal_.writeFromNonRT(false);
1218+
rt_has_pending_goal_ = false;
12211219
auto action_res = std::make_shared<FollowJTrajAction::Result>();
12221220
active_goal->setCanceled(action_res);
12231221
rt_active_goal_.writeFromNonRT(RealtimeGoalHandlePtr());
@@ -1232,7 +1230,7 @@ void JointTrajectoryController::goal_accepted_callback(
12321230
std::shared_ptr<rclcpp_action::ServerGoalHandle<FollowJTrajAction>> goal_handle)
12331231
{
12341232
// mark a pending goal
1235-
rt_has_pending_goal_.writeFromNonRT(true);
1233+
rt_has_pending_goal_ = true;
12361234

12371235
// Update new trajectory
12381236
{
@@ -1241,7 +1239,7 @@ void JointTrajectoryController::goal_accepted_callback(
12411239
std::make_shared<trajectory_msgs::msg::JointTrajectory>(goal_handle->get_goal()->trajectory);
12421240

12431241
add_new_trajectory_msg(traj_msg);
1244-
rt_is_holding_.writeFromNonRT(false);
1242+
rt_is_holding_ = false;
12451243
}
12461244

12471245
// Update the active goal
@@ -1593,7 +1591,7 @@ JointTrajectoryController::set_hold_position()
15931591
hold_position_msg_ptr_->points[0].positions = state_current_.positions;
15941592

15951593
// set flag, otherwise tolerances will be checked with holding position too
1596-
rt_is_holding_.writeFromNonRT(true);
1594+
rt_is_holding_ = true;
15971595

15981596
return hold_position_msg_ptr_;
15991597
}
@@ -1607,7 +1605,7 @@ JointTrajectoryController::set_success_trajectory_point()
16071605
hold_position_msg_ptr_->points[0].time_from_start = rclcpp::Duration(0, 0);
16081606

16091607
// set flag, otherwise tolerances will be checked with success_trajectory_point too
1610-
rt_is_holding_.writeFromNonRT(true);
1608+
rt_is_holding_ = true;
16111609

16121610
return hold_position_msg_ptr_;
16131611
}

0 commit comments

Comments
 (0)