|
| RobotConfig (units::kilogram_t mass, units::kilogram_square_meter_t MOI, ModuleConfig moduleConfig, std::vector< frc::Translation2d > moduleOffsets) |
|
| RobotConfig (units::kilogram_t mass, units::kilogram_square_meter_t MOI, ModuleConfig moduleConfig, units::meter_t trackwidth) |
|
std::vector< frc::SwerveModuleState > | toSwerveModuleStates (frc::ChassisSpeeds speeds) const |
|
frc::ChassisSpeeds | toChassisSpeeds (std::vector< SwerveModuleTrajectoryState > states) const |
|
frc::ChassisSpeeds | toChassisSpeeds (std::vector< frc::SwerveModuleState > states) const |
|
std::vector< frc::SwerveModuleState > | desaturateWheelSpeeds (std::vector< frc::SwerveModuleState > moduleStates, units::meters_per_second_t maxSpeed) const |
|
std::vector< frc::Translation2d > | chassisForcesToWheelForceVectors (frc::ChassisSpeeds chassisForces) const |
|
|
units::kilogram_t | mass |
|
units::kilogram_square_meter_t | MOI |
|
ModuleConfig | moduleConfig |
|
std::vector< frc::Translation2d > | moduleLocations |
|
bool | isHolonomic |
|
size_t | numModules |
|
std::vector< units::meter_t > | modulePivotDistance |
|
units::newton_t | wheelFrictionForce |
|
units::newton_meter_t | maxTorqueFriction |
|
◆ desaturateWheelSpeeds()
std::vector< frc::SwerveModuleState > RobotConfig::desaturateWheelSpeeds |
( |
std::vector< frc::SwerveModuleState > |
moduleStates, |
|
|
units::meters_per_second_t |
maxSpeed |
|
) |
| const |
Desaturate wheel speeds to respect velocity limits.
- Parameters
-
moduleStates | The module states to desaturate |
maxSpeed | The maximum speed that the robot can reach while actually driving the robot at full output |
- Returns
- The desaturated module states
◆ toChassisSpeeds() [1/2]
frc::ChassisSpeeds RobotConfig::toChassisSpeeds |
( |
std::vector< frc::SwerveModuleState > |
states | ) |
const |
Convert a vector of swerve module states to robot-relative chassis speeds. This will use differential kinematics for diff drive robots.
- Parameters
-
states | Vector of swerve module states |
- Returns
- Robot-relative chassis speeds
◆ toChassisSpeeds() [2/2]
Convert a vector of swerve module states to robot-relative chassis speeds. This will use differential kinematics for diff drive robots.
- Parameters
-
states | Vector of swerve module states |
- Returns
- Robot-relative chassis speeds
◆ toSwerveModuleStates()
std::vector< frc::SwerveModuleState > RobotConfig::toSwerveModuleStates |
( |
frc::ChassisSpeeds |
speeds | ) |
const |
Convert robot-relative chassis speeds to a vector of swerve module states. This will use differential kinematics for diff drive robots, then convert the wheel speeds to module states.
- Parameters
-
speeds | Robot-relative chassis speeds |
- Returns
- Vector of swerve module states
The documentation for this class was generated from the following files:
- src/main/native/include/pathplanner/lib/config/RobotConfig.h
- src/main/native/cpp/pathplanner/lib/config/RobotConfig.cpp