RIT VEXU Core API
Loading...
Searching...
No Matches
core::MotionController Class Reference

#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
 
PIDFFget_pidff ()
 
void set_profile_config (trapezoid_profile_config_t config)
 

Detailed Description

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.

Author
Ryan McGee, Jack Cammarata
Date
7/13/2022, 6/27/2025

Constructor & Destructor Documentation

◆ MotionController()

core::MotionController::MotionController ( motion_controller_config_t config)
inline

Constructs a MotionController with the given configuration.

Parameters
configThe configuration parameters.

Member Function Documentation

◆ at_target()

bool core::MotionController::at_target ( ) const
inline

Checks if the controller is at the target position.

Returns
True if the current position is at the target position within tolerance.

◆ calculate()

double core::MotionController::calculate ( double current_position,
double current_time,
Rotation2d angle = Rotation2d() )
inline

Calculates the motion controller output based on the current position and time.

Parameters
current_positionThe current position measurement.
current_timeThe current system time.
angleThe current angle (for gravity compensation).
Returns
The calculated control output.

◆ current_position()

double core::MotionController::current_position ( ) const
inline

Gets the most recent measured position.

Returns
The current position.

◆ get_pidff()

PIDFF & core::MotionController::get_pidff ( )
inline

Returns the PIDFF controller.

Returns
Reference to the internal PIDFF controller.

◆ is_profile_complete()

bool core::MotionController::is_profile_complete ( ) const
inline

Checks if the motion profile is complete.

Returns
True if the profile has completed.

◆ set_profile_config()

void core::MotionController::set_profile_config ( trapezoid_profile_config_t config)
inline

Updates the motion profile configuration.

Parameters
configThe new trapezoid profile configuration.

◆ set_target()

void core::MotionController::set_target ( double target_position,
double current_position,
double current_time )
inline

Sets a new target position, which generates a new trajectory.

Parameters
target_positionThe new target position.
current_positionThe current position (starting point).
current_timeThe current system time (used as the start time for the new trajectory).

◆ target_position()

double core::MotionController::target_position ( ) const
inline

Gets the current target position.

Returns
The target position.

The documentation for this class was generated from the following file: