PathPlannerLib
Loading...
Searching...
No Matches
pathplanner::DriveFeedforwards Struct Reference

Public Member Functions

DriveFeedforwards interpolate (const DriveFeedforwards &endVal, const double t) const
 
DriveFeedforwards reverse () const
 
DriveFeedforwards flip () const
 

Static Public Member Functions

static DriveFeedforwards zeros (const size_t numModules)
 

Public Attributes

std::vector< units::meters_per_second_squared_t > accelerations
 
std::vector< units::newton_t > linearForces
 
std::vector< units::ampere_t > torqueCurrents
 
std::vector< units::newton_t > robotRelativeForcesX
 
std::vector< units::newton_t > robotRelativeForcesY
 

Member Function Documentation

◆ flip()

DriveFeedforwards pathplanner::DriveFeedforwards::flip ( ) const
inline

Flip the feedforwards for the other side of the field. Only does anything if mirrored symmetry is used

Returns
Flipped feedforwards

◆ reverse()

DriveFeedforwards pathplanner::DriveFeedforwards::reverse ( ) const
inline

Reverse the feedforwards for driving backwards. This should only be used for differential drive robots.

Returns
Reversed feedforwards

◆ zeros()

static DriveFeedforwards pathplanner::DriveFeedforwards::zeros ( const size_t  numModules)
inlinestatic

Create drive feedforwards consisting of all zeros

Parameters
numModulesNumber of drive modules
Returns
Zero feedforwards

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