Skip to content

Commit 0904e7c

Browse files
committed
Reformat scaling the time period
This avoids writing the explicit conversion by hand Internally that basically does: static_cast<rcl_duration_value_t>(static_cast<long double>(rcl_duration_.nanoseconds) * scale_ld)
1 parent 37aa162 commit 0904e7c

File tree

1 file changed

+1
-1
lines changed

1 file changed

+1
-1
lines changed

joint_trajectory_controller/src/joint_trajectory_controller.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -180,7 +180,7 @@ controller_interface::return_type JointTrajectoryController::update(
180180
TimeData time_data;
181181
time_data.time = time;
182182
rcl_duration_value_t t_period = (time_data.time - time_data_.readFromRT()->time).nanoseconds();
183-
time_data.period = rclcpp::Duration::from_nanoseconds(scaling_factor_ * t_period);
183+
time_data.period = rclcpp::Duration::from_nanoseconds(t_period) * scaling_factor_;
184184
time_data.uptime = time_data_.readFromRT()->uptime + time_data.period;
185185
rclcpp::Time traj_time =
186186
time_data_.readFromRT()->uptime + rclcpp::Duration::from_nanoseconds(t_period);

0 commit comments

Comments
 (0)