$search
Generates velocities at waypoints by finite differencing. Accelerations are set to zero. More...
#include <linear_trajectory.h>
Public Member Functions | |
LinearTrajectory () | |
bool | parameterize (const trajectory_msgs::JointTrajectory &trajectory_in, const std::vector< arm_navigation_msgs::JointLimits > &limits, spline_smoother::SplineTrajectory &spline) |
A pure virtual function that must be implemented by each different trajectory generation algorithm. | |
Private Member Functions | |
double | calculateMinimumTime (const trajectory_msgs::JointTrajectoryPoint &start, const trajectory_msgs::JointTrajectoryPoint &end, const std::vector< arm_navigation_msgs::JointLimits > &limits) |
Private Attributes | |
bool | apply_limits_ |
Generates velocities at waypoints by finite differencing. Accelerations are set to zero.
Definition at line 47 of file linear_trajectory.h.
spline_smoother::LinearTrajectory::LinearTrajectory | ( | ) |
Definition at line 42 of file linear_trajectory.cpp.
double spline_smoother::LinearTrajectory::calculateMinimumTime | ( | const trajectory_msgs::JointTrajectoryPoint & | start, | |
const trajectory_msgs::JointTrajectoryPoint & | end, | |||
const std::vector< arm_navigation_msgs::JointLimits > & | limits | |||
) | [private] |
Definition at line 47 of file linear_trajectory.cpp.
bool spline_smoother::LinearTrajectory::parameterize | ( | const trajectory_msgs::JointTrajectory & | trajectory_in, | |
const std::vector< arm_navigation_msgs::JointLimits > & | limits, | |||
spline_smoother::SplineTrajectory & | spline | |||
) |
A pure virtual function that must be implemented by each different trajectory generation algorithm.
trajectory_in | The input trajectory. It could contain position, velocity and acceleration information | |
spline | The output spline trajectory. The number of spline segments = number of trajectory points - 1 |
Definition at line 65 of file linear_trajectory.cpp.
bool spline_smoother::LinearTrajectory::apply_limits_ [private] |
Definition at line 70 of file linear_trajectory.h.