Skip to content

Commit

Permalink
Use period directly instead of calculating an own period
Browse files Browse the repository at this point in the history
  • Loading branch information
fmauch committed Jul 23, 2024
1 parent 0a3b974 commit 09bea48
Showing 1 changed file with 3 additions and 7 deletions.
10 changes: 3 additions & 7 deletions joint_trajectory_controller/src/joint_trajectory_controller.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -205,19 +205,16 @@ controller_interface::return_type JointTrajectoryController::update(
// currently carrying out a trajectory
if (has_active_trajectory())
{
// Time passed since the last update call
rcl_duration_value_t t_period = (time - time_data_.time).nanoseconds();

// scaled time period
time_data_.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_;
time_data_.period = period * scaling_factor_;

// scaled time spent in the trajectory
time_data_.uptime = time_data_.uptime + time_data_.period;

// time in the trajectory with a non-scaled current step
rclcpp::Time traj_time = time_data_.uptime + rclcpp::Duration::from_nanoseconds(t_period);
rclcpp::Time traj_time = time_data_.uptime + period;

time_data_.time = time;
// time_data_.time = time;

bool first_sample = false;
// if sampling the first time, set the point before you sample
Expand Down Expand Up @@ -948,7 +945,6 @@ controller_interface::CallbackReturn JointTrajectoryController::on_activate(
// parse remaining parameters
default_tolerances_ = get_segment_tolerances(logger, 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();
Expand Down

0 comments on commit 09bea48

Please sign in to comment.