Skip to content

Commit

Permalink
Do not put the time_data_ into a RealtimeBuffer
Browse files Browse the repository at this point in the history
It is accessed from the RT thread only, anyway.
  • Loading branch information
fmauch committed Jul 3, 2024
1 parent 71ccb39 commit 1fb38b8
Show file tree
Hide file tree
Showing 2 changed files with 8 additions and 10 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -173,8 +173,8 @@ class JointTrajectoryController : public controller_interface::ControllerInterfa
std::vector<double> tmp_command_;

// Things around speed scaling
realtime_tools::RealtimeBuffer<TimeData> time_data_;
double scaling_factor_{1.0};
TimeData time_data_;

// Timeout to consider commands old
double cmd_timeout_;
Expand Down
16 changes: 7 additions & 9 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -197,13 +197,12 @@ controller_interface::return_type JointTrajectoryController::update(
// Adjust time with scaling factor
TimeData time_data;
time_data.time = time;
rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds();
rcl_duration_value_t t_period = (time_data.time - time_data_.time).nanoseconds();
time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_;
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
time_data.uptime = time_data_.uptime + time_data.period;
rclcpp::Time traj_time =
time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period);
time_data_.reset();
time_data_.initRT(time_data);
time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period);
time_data_ = time_data;

bool first_sample = false;
// if sampling the first time, set the point before you sample
Expand Down Expand Up @@ -948,10 +947,9 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
default_tolerances_ = get_segment_tolerances(params_);
// Setup time_data buffer used for scaling
TimeData time_data;
time_data.time = get_node()->now();
time_data.period = rclcpp::Duration::from_nanoseconds(0);
time_data.uptime = get_node()->now();
time_data_.initRT(time_data);
time_data_.time = get_node()->now();
time_data_.period = rclcpp::Duration::from_nanoseconds(0);
time_data_.uptime = get_node()->now();

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

0 comments on commit 1fb38b8

Please sign in to comment.