38 #ifndef MOVEIT_TRAJECTORY_PROCESSING_ITERATIVE_SPLINE_PARAMETERIZATION__ 39 #define MOVEIT_TRAJECTORY_PROCESSING_ITERATIVE_SPLINE_PARAMETERIZATION__ 41 #include <trajectory_msgs/JointTrajectory.h> 42 #include <moveit_msgs/JointLimits.h> 43 #include <moveit_msgs/RobotState.h> 81 const double max_acceleration_scaling_factor = 1.0)
const;
bool computeTimeStamps(robot_trajectory::RobotTrajectory &trajectory, const double max_velocity_scaling_factor=1.0, const double max_acceleration_scaling_factor=1.0) const
~IterativeSplineParameterization()
robot_trajectory::RobotTrajectory trajectory(rmodel,"right_arm")
Maintain a sequence of waypoints and the time durations between these waypoints.
IterativeSplineParameterization(bool add_points=true)
This class sets the timestamps of a trajectory to enforce velocity, acceleration constraints. Initial/final velocities and accelerations may be specified in the trajectory. Velocity and acceleration limits are specified in the model.