Skip to content

Commit e247b24

Browse files
author
Felix Exner
committed
Do not put the time_data_ into a RealtimeBuffer
It is accessed from the RT thread only, anyway.
1 parent 4fb2e72 commit e247b24

File tree

2 files changed

+8
-10
lines changed

2 files changed

+8
-10
lines changed

joint_trajectory_controller/include/joint_trajectory_controller/joint_trajectory_controller.hpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -173,8 +173,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
173173
std::vector<double> tmp_command_;
174174

175175
// Things around speed scaling
176-
realtime_tools::RealtimeBuffer<TimeData> time_data_;
177176
double scaling_factor_{1.0};
177+
TimeData time_data_;
178178

179179
// Timeout to consider commands old
180180
double cmd_timeout_;

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -197,13 +197,12 @@ controller_interface::return_type JointTrajectoryController::update(
197197
// Adjust time with scaling factor
198198
TimeData time_data;
199199
time_data.time = time;
200-
rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds();
200+
rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds();
201201
time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_;
202-
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
202+
time_data.uptime = time_data_.uptime + time_data.period;
203203
rclcpp::Time traj_time =
204-
time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period);
205-
time_data_.reset();
206-
time_data_.initRT(time_data);
204+
time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period);
205+
time_data_ = time_data;
207206

208207
bool first_sample = false;
209208
// if sampling the first time, set the point before you sample
@@ -951,10 +950,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
951950
default_tolerances_ = get_segment_tolerances(params_);
952951
// Setup time_data buffer used for scaling
953952
TimeData time_data;
954-
time_data.time = get_node()->now();
955-
time_data.period = rclcpp::Duration::from_nanoseconds(0);
956-
time_data.uptime = get_node()->now();
957-
time_data_.initRT(time_data);
953+
time_data_.time = get_node()->now();
954+
time_data_.period = rclcpp::Duration::from_nanoseconds(0);
955+
time_data_.uptime = get_node()->now();
958956

959957
// order all joints in the storage
960958
for (const auto & interface : params_.command_interfaces)

0 commit comments

Comments
 (0)