38 #include <moveit_msgs/JointLimits.h>
48 double max_time_change_per_it)
49 : max_iterations_(max_iterations), max_time_change_per_it_(max_time_change_per_it)
53 #if 0 // unused functions
56 void printPoint(
const trajectory_msgs::JointTrajectoryPoint&
point, std::size_t i)
58 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" time [%zu]= %f", i,
59 point.time_from_start.toSec());
60 if (
point.positions.size() >= 7)
62 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" pos_ [%zu]= %f %f %f %f %f %f %f", i,
66 if (
point.velocities.size() >= 7)
68 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" vel_ [%zu]= %f %f %f %f %f %f %f", i,
72 if (
point.accelerations.size() >= 7)
74 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" acc_ [%zu]= %f %f %f %f %f %f %f", i,
80 void printStats(
const trajectory_msgs::JointTrajectory& trajectory,
const std::vector<moveit_msgs::JointLimits>& limits)
82 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
"jointNames= %s %s %s %s %s %s %s",
83 limits[0].joint_name.c_str(), limits[1].joint_name.c_str(), limits[2].joint_name.c_str(),
84 limits[3].joint_name.c_str(), limits[4].joint_name.c_str(), limits[5].joint_name.c_str(),
85 limits[6].joint_name.c_str());
86 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
"maxVelocities= %f %f %f %f %f %f %f",
87 limits[0].max_velocity, limits[1].max_velocity, limits[2].max_velocity, limits[3].max_velocity,
88 limits[4].max_velocity, limits[5].max_velocity, limits[6].max_velocity);
89 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
"maxAccelerations= %f %f %f %f %f %f %f",
90 limits[0].max_acceleration, limits[1].max_acceleration, limits[2].max_acceleration,
91 limits[3].max_acceleration, limits[4].max_acceleration, limits[5].max_acceleration,
92 limits[6].max_acceleration);
94 for (std::size_t i = 0; i < trajectory.points.size(); ++i)
95 printPoint(trajectory.points[i], i);
102 std::vector<double>& time_diff,
103 const double max_velocity_scaling_factor)
const
111 double velocity_scaling_factor = 1.0;
113 if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
114 velocity_scaling_factor = max_velocity_scaling_factor;
115 else if (max_velocity_scaling_factor == 0.0)
116 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
117 "A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
118 velocity_scaling_factor);
120 ROS_WARN_NAMED(
"trajectory_processing.iterative_time_parameterization",
121 "Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
122 max_velocity_scaling_factor, velocity_scaling_factor);
124 for (
int i = 0; i < num_points - 1; ++i)
126 const moveit::core::RobotStatePtr& curr_waypoint = rob_trajectory.
getWayPointPtr(i);
127 const moveit::core::RobotStatePtr& next_waypoint = rob_trajectory.
getWayPointPtr(i + 1);
129 for (std::size_t j = 0; j < vars.size(); ++j)
136 const double dq1 = curr_waypoint->getVariablePosition(idx[j]);
137 const double dq2 = next_waypoint->getVariablePosition(idx[j]);
138 const double t_min = std::abs(dq2 - dq1) / v_max;
139 if (t_min > time_diff[i])
140 time_diff[i] = t_min;
148 double IterativeParabolicTimeParameterization::findT1(
const double dq1,
const double dq2,
double dt1,
const double dt2,
149 const double a_max)
const
151 const double mult_factor = 1.01;
152 double v1 = (dq1) / dt1;
153 double v2 = (dq2) / dt2;
154 double a = 2.0 * (v2 - v1) / (dt1 + dt2);
156 while (std::abs(a) > a_max)
160 a = 2.0 * (v2 - v1) / (dt1 + dt2);
167 double IterativeParabolicTimeParameterization::findT2(
const double dq1,
const double dq2,
const double dt1,
double dt2,
168 const double a_max)
const
170 const double mult_factor = 1.01;
171 double v1 = (dq1) / dt1;
172 double v2 = (dq2) / dt2;
173 double a = 2.0 * (v2 - v1) / (dt1 + dt2);
175 while (std::abs(a) > a_max)
179 a = 2.0 * (v2 - v1) / (dt1 + dt2);
189 const std::vector<double>& time_diff)
192 if (time_diff.empty())
195 double time_sum = 0.0;
197 moveit::core::RobotStatePtr prev_waypoint;
198 moveit::core::RobotStatePtr curr_waypoint;
199 moveit::core::RobotStatePtr next_waypoint;
210 for (
int i = 1; i < num_points; ++i)
219 for (
int i = 0; i < num_points; ++i)
226 if (i < num_points - 1)
229 for (std::size_t j = 0; j < vars.size(); ++j)
240 q1 = next_waypoint->getVariablePosition(idx[j]);
241 q2 = curr_waypoint->getVariablePosition(idx[j]);
244 dt1 = dt2 = time_diff[i];
246 else if (i < num_points - 1)
249 q1 = prev_waypoint->getVariablePosition(idx[j]);
250 q2 = curr_waypoint->getVariablePosition(idx[j]);
251 q3 = next_waypoint->getVariablePosition(idx[j]);
253 dt1 = time_diff[i - 1];
259 q1 = prev_waypoint->getVariablePosition(idx[j]);
260 q2 = curr_waypoint->getVariablePosition(idx[j]);
263 dt1 = dt2 = time_diff[i - 1];
268 bool start_velocity =
false;
269 if (dt1 == 0.0 || dt2 == 0.0)
279 if (curr_waypoint->hasVelocities())
281 start_velocity =
true;
282 v1 = curr_waypoint->getVariableVelocity(idx[j]);
285 v1 = start_velocity ? v1 : (q2 - q1) / dt1;
287 v2 = start_velocity ? v1 : (q3 - q2) / dt2;
288 a = 2.0 * (v2 - v1) / (dt1 + dt2);
291 curr_waypoint->setVariableVelocity(idx[j], (v2 + v1) / 2.0);
292 curr_waypoint->setVariableAcceleration(idx[j], a);
298 void IterativeParabolicTimeParameterization::applyAccelerationConstraints(
300 const double max_acceleration_scaling_factor)
const
302 moveit::core::RobotStatePtr prev_waypoint;
303 moveit::core::RobotStatePtr curr_waypoint;
304 moveit::core::RobotStatePtr next_waypoint;
315 bool backwards =
false;
325 double acceleration_scaling_factor = 1.0;
327 if (max_acceleration_scaling_factor > 0.0 && max_acceleration_scaling_factor <= 1.0)
328 acceleration_scaling_factor = max_acceleration_scaling_factor;
329 else if (max_acceleration_scaling_factor == 0.0)
331 "A max_acceleration_scaling_factor of 0.0 was specified, defaulting to %f instead.",
332 acceleration_scaling_factor);
334 ROS_WARN_NAMED(
"trajectory_processing.iterative_time_parameterization",
335 "Invalid max_acceleration_scaling_factor %f specified, defaulting to %f instead.",
336 max_acceleration_scaling_factor, acceleration_scaling_factor);
345 for (
unsigned int j = 0; j < num_joints; ++j)
348 for (
int count = 0; count < 2; ++count)
350 for (
int i = 0; i < num_points - 1; ++i)
352 int index = backwards ? (num_points - 1) - i : i;
359 if (index < num_points - 1)
372 q1 = next_waypoint->getVariablePosition(idx[j]);
373 q2 = curr_waypoint->getVariablePosition(idx[j]);
374 q3 = next_waypoint->getVariablePosition(idx[j]);
376 dt1 = dt2 = time_diff[
index];
379 else if (index < num_points - 1)
382 q1 = prev_waypoint->getVariablePosition(idx[j]);
383 q2 = curr_waypoint->getVariablePosition(idx[j]);
384 q3 = next_waypoint->getVariablePosition(idx[j]);
386 dt1 = time_diff[
index - 1];
387 dt2 = time_diff[
index];
392 q1 = prev_waypoint->getVariablePosition(idx[j]);
393 q2 = curr_waypoint->getVariablePosition(idx[j]);
394 q3 = prev_waypoint->getVariablePosition(idx[j]);
396 dt1 = dt2 = time_diff[
index - 1];
400 if (dt1 == 0.0 || dt2 == 0.0)
408 bool start_velocity =
false;
411 if (curr_waypoint->hasVelocities())
413 start_velocity =
true;
414 v1 = curr_waypoint->getVariableVelocity(idx[j]);
417 v1 = start_velocity ? v1 : (q2 - q1) / dt1;
418 v2 = (q3 - q2) / dt2;
419 a = 2.0 * (v2 - v1) / (dt1 + dt2);
426 dt2 = std::min(dt2 + max_time_change_per_it_, findT2(q2 - q1, q3 - q2, dt1, dt2, a_max));
427 time_diff[
index] = dt2;
431 dt1 = std::min(dt1 + max_time_change_per_it_, findT1(q2 - q1, q3 - q2, dt1, dt2, a_max));
432 time_diff[
index - 1] = dt1;
436 if (dt1 == 0.0 || dt2 == 0.0)
444 v1 = (q2 - q1) / dt1;
445 v2 = (q3 - q2) / dt2;
446 a = 2 * (v2 - v1) / (dt1 + dt2);
450 backwards = !backwards;
455 }
while (num_updates > 0 && iteration <
static_cast<int>(max_iterations_));
459 const double max_velocity_scaling_factor,
460 const double max_acceleration_scaling_factor)
const
462 if (trajectory.
empty())
468 ROS_ERROR_NAMED(
"trajectory_processing.iterative_time_parameterization",
"It looks like the planner did not set "
469 "the group the plan was computed for");
477 std::vector<double> time_diff(num_points - 1, 0.0);
479 applyVelocityConstraints(trajectory, time_diff, max_velocity_scaling_factor);
480 applyAccelerationConstraints(trajectory, time_diff, max_acceleration_scaling_factor);
482 IterativeParabolicTimeParameterization::updateTrajectory(trajectory, time_diff);