Skip to content

Commit 7b15431

Browse files
use reset+initRT due to missing writeFromRT
Co-authored-by: Christoph Fröhlich <[email protected]>
1 parent 3044026 commit 7b15431

File tree

1 file changed

+2
-1
lines changed

1 file changed

+2
-1
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 2 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -210,7 +210,8 @@ controller_interface::return_type JointTrajectoryController::update(
210210
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
211211
rclcpp::Time traj_time =
212212
time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period);
213-
time_data_.writeFromNonRT(time_data);
213+
time_data_.reset();
214+
time_data_.initRT(time_data);
214215

215216
bool first_sample = false;
216217
// if sampling the first time, set the point before you sample

0 commit comments

Comments
 (0)