38 #include <moveit_msgs/msg/joint_limits.hpp> 
   40 #include <rclcpp/logger.hpp> 
   41 #include <rclcpp/logging.hpp> 
   45 static const double DEFAULT_VEL_MAX = 1.0;
 
   46 static const double DEFAULT_ACCEL_MAX = 1.0;
 
   47 static const double ROUNDING_THRESHOLD = 0.01;
 
   49 static const rclcpp::Logger LOGGER = rclcpp::get_logger(
"moveit_trajectory_processing.iterative_time_parameterization");
 
   52                                                                                double max_time_change_per_it)
 
   53   : max_iterations_(max_iterations), max_time_change_per_it_(max_time_change_per_it)
 
   60 void printPoint(
const trajectory_msgs::msg::JointTrajectoryPoint& point, std::size_t i)
 
   62   RCLCPP_DEBUG(LOGGER, 
" time   [%zu]= %f", i, point.time_from_start.sec + point.time_from_start.nanosec / 1e9);
 
   63   if (point.positions.size() >= 7)
 
   65     RCLCPP_DEBUG(LOGGER, 
" pos_   [%zu]= %f %f %f %f %f %f %f", i, point.positions[0], point.positions[1],
 
   66                  point.positions[2], point.positions[3], point.positions[4], point.positions[5], point.positions[6]);
 
   68   if (point.velocities.size() >= 7)
 
   70     RCLCPP_DEBUG(LOGGER, 
"  vel_  [%zu]= %f %f %f %f %f %f %f", i, point.velocities[0], point.velocities[1],
 
   71                  point.velocities[2], point.velocities[3], point.velocities[4], point.velocities[5],
 
   74   if (point.accelerations.size() >= 7)
 
   76     RCLCPP_DEBUG(LOGGER, 
"   acc_ [%zu]= %f %f %f %f %f %f %f", i, point.accelerations[0], point.accelerations[1],
 
   77                  point.accelerations[2], point.accelerations[3], point.accelerations[4], point.accelerations[5],
 
   78                  point.accelerations[6]);
 
   82 void printStats(
const trajectory_msgs::msg::JointTrajectory& trajectory,
 
   83                 const std::vector<moveit_msgs::msg::JointLimits>& limits)
 
   85   RCLCPP_DEBUG(LOGGER, 
"jointNames= %s %s %s %s %s %s %s", limits[0].joint_name.c_str(), limits[1].joint_name.c_str(),
 
   86                limits[2].joint_name.c_str(), limits[3].joint_name.c_str(), limits[4].joint_name.c_str(),
 
   87                limits[5].joint_name.c_str(), limits[6].joint_name.c_str());
 
   88   RCLCPP_DEBUG(LOGGER, 
"maxVelocities= %f %f %f %f %f %f %f", limits[0].max_velocity, limits[1].max_velocity,
 
   89                limits[2].max_velocity, limits[3].max_velocity, limits[4].max_velocity, limits[5].max_velocity,
 
   90                limits[6].max_velocity);
 
   91   RCLCPP_DEBUG(LOGGER, 
"maxAccelerations= %f %f %f %f %f %f %f", limits[0].max_acceleration, limits[1].max_acceleration,
 
   92                limits[2].max_acceleration, limits[3].max_acceleration, limits[4].max_acceleration,
 
   93                limits[5].max_acceleration, limits[6].max_acceleration);
 
   95   for (std::size_t i = 0; i < trajectory.points.size(); ++i)
 
   96     printPoint(trajectory.points[i], i);
 
  103                                                                       std::vector<double>& time_diff,
 
  104                                                                       const double max_velocity_scaling_factor)
 const 
  107   const std::vector<std::string>& vars = 
group->getVariableNames();
 
  108   const std::vector<int>& idx = 
group->getVariableIndexList();
 
  112   double velocity_scaling_factor = 1.0;
 
  114   if (max_velocity_scaling_factor > 0.0 && max_velocity_scaling_factor <= 1.0)
 
  115     velocity_scaling_factor = max_velocity_scaling_factor;
 
  116   else if (max_velocity_scaling_factor == 0.0)
 
  118     RCLCPP_DEBUG(LOGGER, 
"A max_velocity_scaling_factor of 0.0 was specified, defaulting to %f instead.",
 
  119                  velocity_scaling_factor);
 
  123     RCLCPP_WARN(LOGGER, 
"Invalid max_velocity_scaling_factor %f specified, defaulting to %f instead.",
 
  124                 max_velocity_scaling_factor, velocity_scaling_factor);
 
  126   for (
int i = 0; i < num_points - 1; ++i)
 
  128     const moveit::core::RobotStatePtr& curr_waypoint = rob_trajectory.
getWayPointPtr(i);
 
  129     const moveit::core::RobotStatePtr& next_waypoint = rob_trajectory.
getWayPointPtr(i + 1);
 
  131     for (std::size_t j = 0; j < vars.size(); ++j)
 
  133       double v_max = DEFAULT_VEL_MAX;
 
  138       const double dq1 = curr_waypoint->getVariablePosition(idx[j]);
 
  139       const double dq2 = next_waypoint->getVariablePosition(idx[j]);
 
  140       const double t_min = std::abs(dq2 - dq1) / v_max;
 
  141       if (t_min > time_diff[i])
 
  142         time_diff[i] = t_min;
 
  150 double IterativeParabolicTimeParameterization::findT1(
const double dq1, 
const double dq2, 
double dt1, 
const double dt2,
 
  151                                                       const double a_max)
 const 
  153   const double mult_factor = 1.01;
 
  154   double v1 = (dq1) / dt1;
 
  155   double v2 = (dq2) / dt2;
 
  156   double a = 2.0 * (v2 - v1) / (dt1 + dt2);
 
  158   while (std::abs(
a) > a_max)
 
  162     a = 2.0 * (v2 - v1) / (dt1 + dt2);
 
  169 double IterativeParabolicTimeParameterization::findT2(
const double dq1, 
const double dq2, 
const double dt1, 
double dt2,
 
  170                                                       const double a_max)
 const 
  172   const double mult_factor = 1.01;
 
  173   double v1 = (dq1) / dt1;
 
  174   double v2 = (dq2) / dt2;
 
  175   double a = 2.0 * (v2 - v1) / (dt1 + dt2);
 
  177   while (std::abs(
a) > a_max)
 
  181     a = 2.0 * (v2 - v1) / (dt1 + dt2);
 
  195   if (time_diff.empty())
 
  198   double time_sum = 0.0;
 
  200   moveit::core::RobotStatePtr prev_waypoint;
 
  201   moveit::core::RobotStatePtr curr_waypoint;
 
  202   moveit::core::RobotStatePtr next_waypoint;
 
  205   const std::vector<std::string>& vars = 
group->getVariableNames();
 
  206   const std::vector<int>& idx = 
group->getVariableIndexList();
 
  213   for (
int i = 1; i < num_points; ++i)
 
  222   for (
int i = 0; i < num_points; ++i)
 
  229     if (i < num_points - 1)
 
  232     for (std::size_t j = 0; j < vars.size(); ++j)
 
  243         q1 = next_waypoint->getVariablePosition(idx[j]);
 
  244         q2 = curr_waypoint->getVariablePosition(idx[j]);
 
  247         dt1 = dt2 = time_diff[i];
 
  249       else if (i < num_points - 1)
 
  252         q1 = prev_waypoint->getVariablePosition(idx[j]);
 
  253         q2 = curr_waypoint->getVariablePosition(idx[j]);
 
  254         q3 = next_waypoint->getVariablePosition(idx[j]);
 
  256         dt1 = time_diff[i - 1];
 
  262         q1 = prev_waypoint->getVariablePosition(idx[j]);
 
  263         q2 = curr_waypoint->getVariablePosition(idx[j]);
 
  266         dt1 = dt2 = time_diff[i - 1];
 
  271       bool start_velocity = 
false;
 
  272       if (dt1 == 0.0 || dt2 == 0.0)
 
  282           if (curr_waypoint->hasVelocities())
 
  284             start_velocity = 
true;
 
  285             v1 = curr_waypoint->getVariableVelocity(idx[j]);
 
  288         v1 = start_velocity ? v1 : (q2 - q1) / dt1;
 
  290         v2 = start_velocity ? v1 : (q3 - q2) / dt2;  
 
  291         a = 2.0 * (v2 - v1) / (dt1 + dt2);
 
  294       curr_waypoint->setVariableVelocity(idx[j], (v2 + v1) / 2.0);
 
  295       curr_waypoint->setVariableAcceleration(idx[j], 
a);
 
  302 void IterativeParabolicTimeParameterization::applyAccelerationConstraints(
 
  304     const double max_acceleration_scaling_factor)
 const 
  306   moveit::core::RobotStatePtr prev_waypoint;
 
  307   moveit::core::RobotStatePtr curr_waypoint;
 
  308   moveit::core::RobotStatePtr next_waypoint;
 
  311   const std::vector<std::string>& vars = 
group->getVariableNames();
 
  312   const std::vector<int>& idx = 
group->getVariableIndexList();
 
  316   const unsigned int num_joints = 
group->getVariableCount();
 
  319   bool backwards = 
false;
 
  329   double acceleration_scaling_factor = 1.0;
 
  331   if (max_acceleration_scaling_factor > 0.0 && max_acceleration_scaling_factor <= 1.0)
 
  332     acceleration_scaling_factor = max_acceleration_scaling_factor;
 
  333   else if (max_acceleration_scaling_factor == 0.0)
 
  335     RCLCPP_DEBUG(LOGGER, 
"A max_acceleration_scaling_factor of 0.0 was specified, defaulting to %f instead.",
 
  336                  acceleration_scaling_factor);
 
  340     RCLCPP_WARN(LOGGER, 
"Invalid max_acceleration_scaling_factor %f specified, defaulting to %f instead.",
 
  341                 max_acceleration_scaling_factor, acceleration_scaling_factor);
 
  350     for (
unsigned int j = 0; j < num_joints; ++j)
 
  353       for (
int count = 0; count < 2; ++count)
 
  355         for (
int i = 0; i < num_points - 1; ++i)
 
  357           int index = backwards ? (num_points - 1) - i : i;
 
  364           if (index < num_points - 1)
 
  368           double a_max = DEFAULT_ACCEL_MAX;
 
  377             q1 = next_waypoint->getVariablePosition(idx[j]);
 
  378             q2 = curr_waypoint->getVariablePosition(idx[j]);
 
  379             q3 = next_waypoint->getVariablePosition(idx[j]);
 
  381             dt1 = dt2 = time_diff[index];
 
  384           else if (index < num_points - 1)
 
  387             q1 = prev_waypoint->getVariablePosition(idx[j]);
 
  388             q2 = curr_waypoint->getVariablePosition(idx[j]);
 
  389             q3 = next_waypoint->getVariablePosition(idx[j]);
 
  391             dt1 = time_diff[index - 1];
 
  392             dt2 = time_diff[index];
 
  397             q1 = prev_waypoint->getVariablePosition(idx[j]);
 
  398             q2 = curr_waypoint->getVariablePosition(idx[j]);
 
  399             q3 = prev_waypoint->getVariablePosition(idx[j]);
 
  401             dt1 = dt2 = time_diff[index - 1];
 
  405           if (dt1 == 0.0 || dt2 == 0.0)
 
  413             bool start_velocity = 
false;
 
  416               if (curr_waypoint->hasVelocities())
 
  418                 start_velocity = 
true;
 
  419                 v1 = curr_waypoint->getVariableVelocity(idx[j]);
 
  422             v1 = start_velocity ? v1 : (q2 - q1) / dt1;
 
  423             v2 = (q3 - q2) / dt2;
 
  424             a = 2.0 * (v2 - v1) / (dt1 + dt2);
 
  427           if (fabs(
a) > a_max + ROUNDING_THRESHOLD)
 
  431               dt2 = std::min(dt2 + max_time_change_per_it_, findT2(q2 - q1, q3 - q2, dt1, dt2, a_max));
 
  432               time_diff[index] = dt2;
 
  436               dt1 = std::min(dt1 + max_time_change_per_it_, findT1(q2 - q1, q3 - q2, dt1, dt2, a_max));
 
  437               time_diff[index - 1] = dt1;
 
  441             if (dt1 == 0.0 || dt2 == 0.0)
 
  449               v1 = (q2 - q1) / dt1;
 
  450               v2 = (q3 - q2) / dt2;
 
  451               a = 2 * (v2 - v1) / (dt1 + dt2);
 
  455         backwards = !backwards;
 
  460   } 
while (num_updates > 0 && iteration < 
static_cast<int>(max_iterations_));
 
  464                                                                const double max_velocity_scaling_factor,
 
  465                                                                const double max_acceleration_scaling_factor)
 const 
  467   if (trajectory.
empty())
 
  473     RCLCPP_ERROR(LOGGER, 
"It looks like the planner did not set " 
  474                          "the group the plan was computed for");
 
  482   std::vector<double> time_diff(num_points - 1, 0.0);  
 
  484   applyVelocityConstraints(trajectory, time_diff, max_velocity_scaling_factor);
 
  485   applyAccelerationConstraints(trajectory, time_diff, max_acceleration_scaling_factor);
 
  487   updateTrajectory(trajectory, time_diff);
 
  493     const std::unordered_map<std::string, double>& ,
 
  494     const std::unordered_map<std::string, double>& )
 const 
  496   RCLCPP_ERROR(LOGGER, 
"IPTP does not support this version of computeTimeStamps. Try TOTG instead?");
 
Definition of a kinematic model. This class is not thread safe, however multiple instances can be cre...
 
const VariableBounds & getVariableBounds(const std::string &variable) const
Get the bounds for a specific variable. Throw an exception of variable is not found.
 
Maintain a sequence of waypoints and the time durations between these waypoints.
 
RobotTrajectory & setWayPointDurationFromPrevious(std::size_t index, double value)
 
const moveit::core::JointModelGroup * getGroup() const
 
RobotTrajectory & unwind()
 
moveit::core::RobotStatePtr & getWayPointPtr(std::size_t index)
 
std::size_t getWayPointCount() const
 
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const override
 
IterativeParabolicTimeParameterization(unsigned int max_iterations=100, double max_time_change_per_it=.01)
 
bool acceleration_bounded_