38 #include <moveit_msgs/JointLimits.h> 47 static void fit_cubic_spline(
const int n,
const double dt[],
const double x[],
double x1[],
double x2[]);
48 static void adjust_two_positions(
const int n,
const double dt[],
double x[],
double x1[],
double x2[],
49 const double x2_i,
const double x2_f);
50 static void init_times(
const int n,
double dt[],
const double x[],
const double max_velocity,
51 const double min_velocity);
53 const double max_velocity,
const double min_velocity,
54 const double max_acceleration,
const double min_acceleration,
55 const double tfactor);
57 const double max_velocity,
const double min_velocity,
58 const double max_acceleration,
const double min_acceleration);
74 void globalAdjustment(std::vector<SingleJointTrajectory>& t2,
int num_joints,
const int num_points,
75 std::vector<double>& time_diff);
86 const double max_velocity_scaling_factor,
87 const double max_acceleration_scaling_factor)
const 89 if (trajectory.
empty())
95 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
"It looks like the planner did not set " 96 "the group the plan was computed for");
102 double velocity_scaling_factor = 1.0;
103 double acceleration_scaling_factor = 1.0;
108 if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
109 velocity_scaling_factor = max_velocity_scaling_factor;
110 else if (max_velocity_scaling_factor == 0.0)
111 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_spline_parameterization",
112 "A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
113 velocity_scaling_factor);
115 ROS_WARN_NAMED(
"trajectory_processing.iterative_spline_parameterization",
116 "Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
117 max_velocity_scaling_factor, velocity_scaling_factor);
119 if (max_acceleration_scaling_factor > 0.0 && max_acceleration_scaling_factor <= 1.0)
120 acceleration_scaling_factor = max_acceleration_scaling_factor;
121 else if (max_acceleration_scaling_factor == 0.0)
122 ROS_DEBUG_NAMED(
"trajectory_processing.iterative_spline_parameterization",
123 "A max_acceleration_scaling_factor of 0.0 was specified, defaulting to %f instead.",
124 acceleration_scaling_factor);
126 ROS_WARN_NAMED(
"trajectory_processing.iterative_spline_parameterization",
127 "Invalid max_acceleration_scaling_factor %f specified, defaulting to %f instead.",
128 max_acceleration_scaling_factor, acceleration_scaling_factor);
140 robot_state::RobotStatePtr p0, p1;
145 for (
unsigned int j = 0; j < num_joints; j++)
148 (9 * p0->getVariablePosition(idx[j]) + 1 * p1->getVariablePosition(idx[j])) / 10);
156 for (
unsigned int j = 0; j < num_joints; j++)
159 (1 * p0->getVariablePosition(idx[j]) + 9 * p1->getVariablePosition(idx[j])) / 10);
170 std::vector<SingleJointTrajectory> t2(num_joints);
172 for (
unsigned int j = 0; j < num_joints; j++)
175 t2[j].positions.resize(num_points, 0.0);
176 for (
unsigned int i = 0; i < num_points; i++)
178 t2[j].positions[i] = trajectory.
getWayPointPtr(i)->getVariablePosition(idx[j]);
182 t2[j].velocities.resize(num_points, 0.0);
185 t2[j].velocities[0] = trajectory.
getWayPointPtr(0)->getVariableVelocity(idx[j]);
187 t2[j].velocities[num_points - 1] = trajectory.
getWayPointPtr(num_points - 1)->getVariableVelocity(idx[j]);
190 t2[j].accelerations.resize(num_points, 0.0);
191 t2[j].initial_acceleration = 0.0;
192 t2[j].final_acceleration = 0.0;
195 t2[j].initial_acceleration = trajectory.
getWayPointPtr(0)->getVariableAcceleration(idx[j]);
196 t2[j].accelerations[0] = t2[j].initial_acceleration;
197 if (trajectory.
getWayPointPtr(num_points - 1)->hasAccelerations())
198 t2[j].final_acceleration = trajectory.
getWayPointPtr(num_points - 1)->getVariableAcceleration(idx[j]);
199 t2[j].accelerations[num_points - 1] = t2[j].final_acceleration;
203 t2[j].max_velocity =
VLIMIT;
204 t2[j].min_velocity = -
VLIMIT;
209 if (t2[j].min_velocity == 0.0)
210 t2[j].min_velocity = -t2[j].max_velocity;
212 t2[j].max_velocity *= velocity_scaling_factor;
213 t2[j].min_velocity *= velocity_scaling_factor;
215 t2[j].max_acceleration =
ALIMIT;
216 t2[j].min_acceleration = -
ALIMIT;
221 if (t2[j].min_acceleration == 0.0)
222 t2[j].min_acceleration = -t2[j].max_acceleration;
224 t2[j].max_acceleration *= acceleration_scaling_factor;
225 t2[j].min_acceleration *= acceleration_scaling_factor;
228 if (t2[j].max_velocity <= 0.0 || t2[j].max_acceleration <= 0.0)
230 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
231 "Joint %d max velocity %f and max acceleration %f must be greater than zero " 232 "or a solution won't be found.\n",
233 j, t2[j].max_velocity, t2[j].max_acceleration);
236 if (t2[j].min_velocity >= 0.0 || t2[j].min_acceleration >= 0.0)
238 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
239 "Joint %d min velocity %f and min acceleration %f must be less than zero " 240 "or a solution won't be found.\n",
241 j, t2[j].min_velocity, t2[j].min_acceleration);
249 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
250 "number of waypoints %d, needs to be greater than 3.\n", num_points);
253 for (
unsigned int j = 0; j < num_joints; j++)
255 if (t2[j].velocities[0] > t2[j].max_velocity || t2[j].velocities[0] < t2[j].min_velocity)
257 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
"Initial velocity %f out of bounds\n",
258 t2[j].velocities[0]);
261 else if (t2[j].velocities[num_points - 1] > t2[j].max_velocity ||
262 t2[j].velocities[num_points - 1] < t2[j].min_velocity)
264 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
"Final velocity %f out of bounds\n",
265 t2[j].velocities[num_points - 1]);
268 else if (t2[j].accelerations[0] > t2[j].max_acceleration || t2[j].accelerations[0] < t2[j].min_acceleration)
270 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
271 "Initial acceleration %f out of bounds\n", t2[j].accelerations[0]);
274 else if (t2[j].accelerations[num_points - 1] > t2[j].max_acceleration ||
275 t2[j].accelerations[num_points - 1] < t2[j].min_acceleration)
277 ROS_ERROR_NAMED(
"trajectory_processing.iterative_spline_parameterization",
278 "Final acceleration %f out of bounds\n", t2[j].accelerations[num_points - 1]);
286 std::vector<double> time_diff(trajectory.
getWayPointCount() - 1, std::numeric_limits<double>::epsilon());
287 for (
unsigned int j = 0; j < num_joints; j++)
288 init_times(num_points, &time_diff[0], &t2[j].positions[0], t2[j].max_velocity, t2[j].min_velocity);
296 std::vector<double> time_factor(num_points - 1, 1.00);
297 for (
unsigned j = 0; j < num_joints; j++)
303 &t2[j].accelerations[0], t2[j].initial_acceleration, t2[j].final_acceleration);
306 fit_cubic_spline(num_points, &time_diff[0], &t2[j].positions[0], &t2[j].velocities[0], &t2[j].accelerations[0]);
307 for (
unsigned i = 0; i < num_points; i++)
309 const double acc = t2[j].accelerations[i];
310 double atfactor = 1.0;
311 if (acc > t2[j].max_acceleration)
312 atfactor =
sqrt(acc / t2[j].max_acceleration);
313 if (acc < t2[j].min_acceleration)
314 atfactor =
sqrt(acc / t2[j].min_acceleration);
317 atfactor = (atfactor - 1.0) / 16.0 + 1.0;
319 time_factor[i - 1] = std::max(time_factor[i - 1], atfactor);
320 if (i < num_points - 1)
321 time_factor[i] = std::max(time_factor[i], atfactor);
329 for (
unsigned i = 0; i < num_points - 1; i++)
330 time_diff[i] *= time_factor[i];
337 for (
unsigned int i = 1; i < num_points; i++)
339 for (
unsigned int i = 0; i < num_points; i++)
341 for (
unsigned int j = 0; j < num_joints; j++)
343 trajectory.
getWayPointPtr(i)->setVariableVelocity(idx[j], t2[j].velocities[i]);
344 trajectory.
getWayPointPtr(i)->setVariableAcceleration(idx[j], t2[j].accelerations[i]);
348 if (
add_points_ && (i == 1 || i == num_points - 2))
350 for (
unsigned int j = 0; j < num_joints; j++)
352 trajectory.
getWayPointPtr(i)->setVariablePosition(idx[j], t2[j].positions[i]);
395 static void fit_cubic_spline(
const int n,
const double dt[],
const double x[],
double x1[],
double x2[])
398 const double x1_i = x1[0], x1_f = x1[n - 1];
403 double *c = x1, *
d = x2;
405 d[0] = 3.0 * ((x[1] - x[0]) / dt[0] - x1_i) / dt[0];
406 for (i = 1; i <= n - 2; i++)
408 const double dt2 = dt[i - 1] + dt[i];
409 const double a = dt[i - 1] / dt2;
410 const double denom = 2.0 - a * c[i - 1];
411 c[i] = (1.0 - a) / denom;
412 d[i] = 6.0 * ((x[i + 1] - x[i]) / dt[i] - (x[i] - x[i - 1]) / dt[i - 1]) / dt2;
413 d[i] = (d[i] - a * d[i - 1]) / denom;
415 const double denom = dt[n - 2] * (2.0 - c[n - 2]);
416 d[n - 1] = 6.0 * (x1_f - (x[n - 1] - x[n - 2]) / dt[n - 2]);
417 d[n - 1] = (d[n - 1] - dt[n - 2] * d[n - 2]) / denom;
421 x2[n - 1] = d[n - 1];
422 for (i = n - 2; i >= 0; i--)
423 x2[i] = d[i] - c[i] * x2[i + 1];
427 for (i = 1; i < n - 1; i++)
428 x1[i] = (x[i + 1] - x[i]) / dt[i] - (2 * x2[i] + x2[i + 1]) * dt[i] / 6.0;
442 const double x2_i,
const double x2_f)
448 double b0 = x2[n - 1];
454 double b2 = x2[n - 1];
458 x[1] = x[0] + ((x[2] - x[0]) / (a2 - a0)) * (x2_i - a0);
460 x[n - 2] = x[n - 3] + ((x[n - 1] - x[n - 3]) / (b2 - b0)) * (x2_f - b0);
468 static void init_times(
const int n,
double dt[],
const double x[],
const double max_velocity,
const double min_velocity)
471 for (i = 0; i < n - 1; i++)
474 double dx = x[i + 1] - x[i];
476 time = (dx / max_velocity);
478 time = (dx / min_velocity);
479 time += std::numeric_limits<double>::epsilon();
507 const double max_velocity,
const double min_velocity,
508 const double max_acceleration,
const double min_acceleration,
509 const double tfactor)
516 for (i = 0; i < n - 1; i++)
518 const double vel = x1[i];
519 const double vel2 = x1[i + 1];
520 if (vel > max_velocity || vel < min_velocity || vel2 > max_velocity || vel2 < min_velocity)
529 for (i = 0; i < n - 1; i++)
531 const double acc = x2[i];
532 const double acc2 = x2[i + 1];
533 if (acc > max_acceleration || acc < min_acceleration || acc2 > max_acceleration || acc2 < min_acceleration)
549 const double max_velocity,
const double min_velocity,
550 const double max_acceleration,
const double min_acceleration)
553 double tfactor2 = 1.00;
557 for (i = 0; i < n; i++)
560 tfactor = x1[i] / max_velocity;
561 if (tfactor2 < tfactor)
563 tfactor = x1[i] / min_velocity;
564 if (tfactor2 < tfactor)
569 tfactor =
sqrt(fabs(x2[i] / max_acceleration));
570 if (tfactor2 < tfactor)
575 tfactor =
sqrt(fabs(x2[i] / min_acceleration));
576 if (tfactor2 < tfactor)
585 void globalAdjustment(std::vector<SingleJointTrajectory>& t2,
int num_joints,
const int num_points,
586 std::vector<double>& time_diff)
588 double gtfactor = 1.0;
589 for (
int j = 0; j < num_joints; j++)
593 &t2[j].accelerations[0], t2[j].max_velocity, t2[j].min_velocity,
594 t2[j].max_acceleration, t2[j].min_acceleration);
595 if (tfactor > gtfactor)
600 for (
int i = 0; i < num_points - 1; i++)
601 time_diff[i] *= gtfactor;
603 for (
int j = 0; j < num_joints; j++)
605 fit_cubic_spline(num_points, &time_diff[0], &t2[j].positions[0], &t2[j].velocities[0], &t2[j].accelerations[0]);
std::vector< double > accelerations
const RobotModel & getParentModel() const
Get the kinematic model this group is part of.
robot_state::RobotStatePtr & getWayPointPtr(std::size_t index)
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...
std::vector< double > velocities
#define ROS_WARN_NAMED(name,...)
static void adjust_two_positions(const int n, const double dt[], double x[], double x1[], double x2[], const double x2_i, const double x2_f)
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
void globalAdjustment(std::vector< SingleJointTrajectory > &t2, int num_joints, const int num_points, std::vector< double > &time_diff)
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
static double global_adjustment_factor(const int n, double dt[], const double x[], double x1[], double x2[], const double max_velocity, const double min_velocity, const double max_acceleration, const double min_acceleration)
unsigned int getVariableCount() const
Get the number of variables that describe this joint group. This includes variables necessary for mim...
#define ROS_DEBUG_NAMED(name,...)
static int fit_spline_and_adjust_times(const int n, double dt[], const double x[], double x1[], double x2[], const double max_velocity, const double min_velocity, const double max_acceleration, const double min_acceleration, const double tfactor)
static const double ALIMIT
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const
double initial_acceleration
~IterativeSplineParameterization()
const robot_model::JointModelGroup * getGroup() const
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
Maintain a sequence of waypoints and the time durations between these waypoints.
void insertWayPoint(std::size_t index, const robot_state::RobotState &state, double dt)
INLINE Rall1d< T, V, S > sqrt(const Rall1d< T, V, S > &arg)
static const double VLIMIT
void setWayPointDurationFromPrevious(std::size_t index, double value)
const robot_state::RobotState & getWayPoint(std::size_t index) const
std::size_t getWayPointCount() const
const std::vector< int > & getVariableIndexList() const
Get the index locations in the complete robot state for all the variables in this group...
static void fit_cubic_spline(const int n, const double dt[], const double x[], double x1[], double x2[])
std::vector< double > positions
double final_acceleration
#define ROS_ERROR_NAMED(name,...)
Representation of a robot's state. This includes position, velocity, acceleration and effort...
IterativeSplineParameterization(bool add_points=true)
void setVariablePosition(const std::string &variable, double value)
Set the position of a single variable. An exception is thrown if the variable name is not known...
bool acceleration_bounded_
moveit::core::RobotModelConstPtr rmodel
static void init_times(const int n, double dt[], const double x[], const double max_velocity, const double min_velocity)