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)
55 void printPoint(
const trajectory_msgs::JointTrajectoryPoint& point, std::size_t i)
57 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" time [%zu]= %f", i,
58 point.time_from_start.toSec());
59 if (point.positions.size() >= 7)
61 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" pos_ [%zu]= %f %f %f %f %f %f %f", i,
62 point.positions[0], point.positions[1], point.positions[2], point.positions[3], point.positions[4],
63 point.positions[5], point.positions[6]);
65 if (point.velocities.size() >= 7)
67 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" vel_ [%zu]= %f %f %f %f %f %f %f", i,
68 point.velocities[0], point.velocities[1], point.velocities[2], point.velocities[3],
69 point.velocities[4], point.velocities[5], point.velocities[6]);
71 if (point.accelerations.size() >= 7)
73 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
" acc_ [%zu]= %f %f %f %f %f %f %f", i,
74 point.accelerations[0], point.accelerations[1], point.accelerations[2], point.accelerations[3],
75 point.accelerations[4], point.accelerations[5], point.accelerations[6]);
79 void printStats(
const trajectory_msgs::JointTrajectory& trajectory,
const std::vector<moveit_msgs::JointLimits>& limits)
81 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
"jointNames= %s %s %s %s %s %s %s",
82 limits[0].joint_name.c_str(), limits[1].joint_name.c_str(), limits[2].joint_name.c_str(),
83 limits[3].joint_name.c_str(), limits[4].joint_name.c_str(), limits[5].joint_name.c_str(),
84 limits[6].joint_name.c_str());
85 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
"maxVelocities= %f %f %f %f %f %f %f",
86 limits[0].max_velocity, limits[1].max_velocity, limits[2].max_velocity, limits[3].max_velocity,
87 limits[4].max_velocity, limits[5].max_velocity, limits[6].max_velocity);
88 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
"maxAccelerations= %f %f %f %f %f %f %f",
89 limits[0].max_acceleration, limits[1].max_acceleration, limits[2].max_acceleration,
90 limits[3].max_acceleration, limits[4].max_acceleration, limits[5].max_acceleration,
91 limits[6].max_acceleration);
93 for (std::size_t i = 0; i < trajectory.points.size(); ++i)
94 printPoint(trajectory.points[i], i);
100 std::vector<double>& time_diff,
101 const double max_velocity_scaling_factor)
const 109 double velocity_scaling_factor = 1.0;
111 if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
112 velocity_scaling_factor = max_velocity_scaling_factor;
113 else if (max_velocity_scaling_factor == 0.0)
114 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
115 "A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
116 velocity_scaling_factor);
118 ROS_WARN_NAMED(
"trajectory_processing.iterative_time_parameterization",
119 "Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
120 max_velocity_scaling_factor, velocity_scaling_factor);
122 for (
int i = 0; i < num_points - 1; ++i)
124 const robot_state::RobotStatePtr& curr_waypoint = rob_trajectory.
getWayPointPtr(i);
125 const robot_state::RobotStatePtr& next_waypoint = rob_trajectory.
getWayPointPtr(i + 1);
127 for (std::size_t j = 0; j < vars.size(); ++j)
134 const double dq1 = curr_waypoint->getVariablePosition(idx[j]);
135 const double dq2 = next_waypoint->getVariablePosition(idx[j]);
136 const double t_min = std::abs(dq2 - dq1) / v_max;
137 if (t_min > time_diff[i])
138 time_diff[i] = t_min;
147 const double a_max)
const 149 const double mult_factor = 1.01;
150 double v1 = (dq1) / dt1;
151 double v2 = (dq2) / dt2;
152 double a = 2.0 * (v2 - v1) / (dt1 + dt2);
154 while (std::abs(a) > a_max)
158 a = 2.0 * (v2 - v1) / (dt1 + dt2);
166 const double a_max)
const 168 const double mult_factor = 1.01;
169 double v1 = (dq1) / dt1;
170 double v2 = (dq2) / dt2;
171 double a = 2.0 * (v2 - v1) / (dt1 + dt2);
173 while (std::abs(a) > a_max)
177 a = 2.0 * (v2 - v1) / (dt1 + dt2);
191 if (time_diff.empty())
194 double time_sum = 0.0;
196 robot_state::RobotStatePtr prev_waypoint;
197 robot_state::RobotStatePtr curr_waypoint;
198 robot_state::RobotStatePtr next_waypoint;
209 for (
int i = 1; i < num_points; ++i)
218 for (
int i = 0; i < num_points; ++i)
225 if (i < num_points - 1)
228 for (std::size_t j = 0; j < vars.size(); ++j)
239 q1 = next_waypoint->getVariablePosition(idx[j]);
240 q2 = curr_waypoint->getVariablePosition(idx[j]);
243 dt1 = dt2 = time_diff[i];
245 else if (i < num_points - 1)
248 q1 = prev_waypoint->getVariablePosition(idx[j]);
249 q2 = curr_waypoint->getVariablePosition(idx[j]);
250 q3 = next_waypoint->getVariablePosition(idx[j]);
252 dt1 = time_diff[i - 1];
258 q1 = prev_waypoint->getVariablePosition(idx[j]);
259 q2 = curr_waypoint->getVariablePosition(idx[j]);
262 dt1 = dt2 = time_diff[i - 1];
267 bool start_velocity =
false;
268 if (dt1 == 0.0 || dt2 == 0.0)
278 if (curr_waypoint->hasVelocities())
280 start_velocity =
true;
281 v1 = curr_waypoint->getVariableVelocity(idx[j]);
284 v1 = start_velocity ? v1 : (q2 - q1) / dt1;
286 v2 = start_velocity ? v1 : (q3 - q2) / dt2;
287 a = 2.0 * (v2 - v1) / (dt1 + dt2);
290 curr_waypoint->setVariableVelocity(idx[j], (v2 + v1) / 2.0);
291 curr_waypoint->setVariableAcceleration(idx[j], a);
300 const double max_acceleration_scaling_factor)
const 302 robot_state::RobotStatePtr prev_waypoint;
303 robot_state::RobotStatePtr curr_waypoint;
304 robot_state::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)
330 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_time_parameterization",
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);
427 time_diff[index] = dt2;
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);
482 updateTrajectory(trajectory, time_diff);
void applyVelocityConstraints(robot_trajectory::RobotTrajectory &rob_trajectory, std::vector< double > &time_diff, const double max_velocity_scaling_factor) const
maximum allowed time change per iteration in seconds
robot_state::RobotStatePtr & getWayPointPtr(std::size_t index)
double findT2(const double d1, const double d2, const double t1, double t2, const double a_max) const
#define ROS_WARN_NAMED(name,...)
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
void applyAccelerationConstraints(robot_trajectory::RobotTrajectory &rob_trajectory, std::vector< double > &time_diff, const double max_acceleration_scaling_factor) const
const std::vector< std::string > & getVariableNames() const
Get the names of the variables that make up the joints included in this group. The number of returned...
static const double ROUNDING_THRESHOLD
double max_time_change_per_it_
maximum number of iterations to find solution
std::size_t getWayPointCount() const
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
#define ROS_DEBUG_NAMED(name,...)
const robot_model::JointModelGroup * getGroup() const
Maintain a sequence of waypoints and the time durations between these waypoints.
static const double DEFAULT_VEL_MAX
void setWayPointDurationFromPrevious(std::size_t index, double value)
unsigned int max_iterations_
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group...
#define ROS_ERROR_NAMED(name,...)
IterativeParabolicTimeParameterization(unsigned int max_iterations=100, double max_time_change_per_it=.01)
static const double DEFAULT_ACCEL_MAX
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
bool acceleration_bounded_
double findT1(const double d1, const double d2, double t1, const double t2, const double a_max) const
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.