librmb 1.0
Rambunction 4330 Utility Library
|
#include <rmb/drive/SwerveModule.h>
Public Member Functions | |
SwerveModule (const SwerveModule &)=delete | |
SwerveModule (SwerveModule &&)=default | |
SwerveModule (std::unique_ptr< LinearVelocityController > velocityController, std::unique_ptr< AngularPositionController > angularController, const frc::Translation2d &moduleTranslation, bool breakMode=false) | |
void | setState (const units::meters_per_second_t &velocity, const frc::Rotation2d &angle) |
void | smartdashboardDisplayTargetState (const std::string &name) const |
void | setState (const frc::SwerveModuleState &state) |
frc::SwerveModuleState | getState () const |
frc::SwerveModulePosition | getPosition () const |
frc::SwerveModuleState | getTargetState () const |
units::meters_per_second_t | getTargetVelocity () const |
frc::Rotation2d | getTargetRotation () const |
void | setPower (double power, const frc::Rotation2d &angle) |
void | setPower (const SwerveModulePower &power) |
void | stop () |
SwerveModulePower | getPower () |
const frc::Translation2d & | getModuleTranslation () const |
virtual void | InitSendable (wpi::SendableBuilder &builder) override |
double | getAngle () |
Class managing the motion of a swerve module
rmb::SwerveModule::SwerveModule | ( | std::unique_ptr< LinearVelocityController > | velocityController, |
std::unique_ptr< AngularPositionController > | angularController, | ||
const frc::Translation2d & | moduleTranslation, | ||
bool | breakMode = false ) |
Constructs a SwerveModule object for controlling module states.
angularController | Controller of the angle of module. |
angularController | Controller of the velocioty of module. |
moduleTranslation | the position of teh modlue reletive to the center of the robot for kinematics. |
const frc::Translation2d & rmb::SwerveModule::getModuleTranslation | ( | ) | const |
Returns the position fo the module reletive to the center of the robot for kinematics.
frc::SwerveModulePosition rmb::SwerveModule::getPosition | ( | ) | const |
Returns the current position of the module useful for more accurate odometry.
frc::SwerveModuleState rmb::SwerveModule::getState | ( | ) | const |
Returns the current state of the module.
frc::SwerveModuleState rmb::SwerveModule::getTargetState | ( | ) | const |
void rmb::SwerveModule::setPower | ( | const SwerveModulePower & | power | ) |
Sets the desired open loop power of the swerve module. This is helpful for teleoperated driving as drivers tend power based control to be more natural.
power | The desired power output of the swerve module. |
Sets the desired open loop powerof the swerve module. Tghis is helpful for teleoperated driving as drivers tend power based control to be more natural.
power | The desired power output of the swerve module. |
angle | The desired angle of the swerve module. |
Sets the desired state of the swerve module.
state | The desired state of the module. |
void rmb::SwerveModule::setState | ( | const units::meters_per_second_t & | velocity, |
const frc::Rotation2d & | angle ) |
Sets the desired state of the swerve module.
velocity | The desired speed of the swerve module. |
angle | The desired angle of the swerve module. |