|
| TrapezoidalTrajectory () |
| Constructor.
|
|
void | setTargetPosition (double startTimestamp, double initialPosition, double initialVelocity, double targetPosition, double refSpeed, double refAcceleration) |
| Set motion parameters (using target position).
|
|
void | setTargetVelocity (double startTimestamp, double initialPosition, double initialVelocity, double targetVelocity, double refAcceleration) |
| Set motion parameters (infinite motion).
|
|
void | reset (double currentPosition) |
| Reset state, remember current position (units).
|
|
Reference | update (double timestamp) |
| Update trajectory state, must be called on regular intervals of period .
|
|
double | getTargetPosition () const |
| Query configured target position (units).
|
|
double | queryPosition () const |
| Retrieve last position reference (units).
|
|
double | queryVelocity () const |
| Retrieve last velocity reference (units/seconds).
|
|
double | queryAcceleration () const |
| Retrieve last acceleration reference (units/seconds^2).
|
|
double | queryTime () const |
| Retrieve elapsed time since start (seconds).
|
|
bool | isActive () const |
| Whether the trajectory is currently ongoing.
|
|
|
void | configure (double startTimestamp, double initialPosition, double initialVelocity, double targetPosition, double refSpeed, double refAcceleration) |
|
|
double | ta |
|
double | a1 |
|
double | a2 |
|
double | a3 |
|
double | tb |
|
double | b2 |
|
double | b3 |
|
double | tc |
|
double | c1 |
|
double | c2 |
|
double | c3 |
|
double | startTimestamp |
|
double | targetPosition |
|
double | positionReference |
|
double | velocityReference |
|
double | accelerationReference |
|
double | elapsedTime |
|
bool | active |
|
std::mutex | mutex |
|
The documentation for this class was generated from the following files: