diff --git a/moveit_core/trajectory_processing/src/trajectory_tools.cpp b/moveit_core/trajectory_processing/src/trajectory_tools.cpp index b15f0ca9a3..d260a06438 100644 --- a/moveit_core/trajectory_processing/src/trajectory_tools.cpp +++ b/moveit_core/trajectory_processing/src/trajectory_tools.cpp @@ -89,7 +89,7 @@ trajectory_msgs::msg::JointTrajectory createTrajectoryMessage(const std::vector< const double time_step = 1.0 / static_cast(sampling_rate); const int n_samples = static_cast(trajectory.getDuration() / time_step) + 1; trajectory_msg.points.reserve(n_samples); - for (int sample = 0; sample < n_samples; ++sample) + for (int sample = 0; sample <= n_samples; ++sample) { const double t = sample * time_step; trajectory_msgs::msg::JointTrajectoryPoint point;