RIT VEXU Core API
|
#include <motion_controller.h>
Classes | |
struct | motion_controller_config_t |
Public Member Functions | |
MotionController (motion_controller_config_t config) | |
void | set_target (double target_position, double current_position, double current_time) |
double | calculate (double current_position, double current_time, Rotation2d angle=Rotation2d()) |
bool | is_profile_complete () const |
bool | at_target () const |
double | target_position () const |
double | current_position () const |
PIDFF & | get_pidff () |
void | set_profile_config (trapezoid_profile_config_t config) |
A Motion Controller that combines trajectory generation using a trapezoidal profile with feedback and feedforward control using PIDFF.
When given a target position, the controller will automatically generate a trajectory and subsequent calls to calculate() will track along that trajectory.
This class does not handle timing that determines the current motion along the trajectory.
|
inline |
Constructs a MotionController with the given configuration.
config | The configuration parameters. |
|
inline |
Checks if the controller is at the target position.
|
inline |
Calculates the motion controller output based on the current position and time.
current_position | The current position measurement. |
current_time | The current system time. |
angle | The current angle (for gravity compensation). |
|
inline |
Gets the most recent measured position.
|
inline |
|
inline |
Checks if the motion profile is complete.
|
inline |
Updates the motion profile configuration.
config | The new trapezoid profile configuration. |
|
inline |
Sets a new target position, which generates a new trajectory.
target_position | The new target position. |
current_position | The current position (starting point). |
current_time | The current system time (used as the start time for the new trajectory). |
|
inline |
Gets the current target position.