Skip to content

Commit

Permalink
fix: removes last trajectory segment with different sampling time.
Browse files Browse the repository at this point in the history
this ensures that the new sample time will be lowered, thus not violating precomputed distance interpolation constraints

at the same time avoids the issue on the last point generating small displacement interpolation
  • Loading branch information
MarcoMagriDev committed Feb 6, 2025
1 parent 3511d7c commit eb933e5
Showing 1 changed file with 4 additions and 3 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -217,11 +217,12 @@ bool pilz_industrial_motion_planner::generateJointTrajectory(
rclcpp::Time generation_begin = clock.now();

// generate the time samples
const double epsilon = 10e-06; // avoid adding the last time sample twice
std::vector<double> time_samples;
for (double t_sample = 0.0; t_sample < trajectory.Duration() - epsilon; t_sample += sampling_time)
int num_samples = std::floor(trajectory.Duration() / sampling_time);
sampling_time = trajectory.Duration() / num_samples;
for (int i = 0; i < num_samples; ++i)
{
time_samples.push_back(t_sample);
time_samples.push_back(i * sampling_time);
}
time_samples.push_back(trajectory.Duration());

Expand Down

0 comments on commit eb933e5

Please sign in to comment.