@@ -197,13 +197,12 @@ controller_interface::return_type JointTrajectoryController::update(
197
197
// Adjust time with scaling factor
198
198
TimeData time_data;
199
199
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 ();
201
201
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 ;
203
203
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;
207
206
208
207
bool first_sample = false ;
209
208
// if sampling the first time, set the point before you sample
@@ -951,10 +950,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
951
950
default_tolerances_ = get_segment_tolerances (params_);
952
951
// Setup time_data buffer used for scaling
953
952
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 ();
958
956
959
957
// order all joints in the storage
960
958
for (const auto & interface : params_.command_interfaces )
0 commit comments