librmb 1.0
Rambunction 4330 Utility Library
Loading...
Searching...
No Matches
rmb::SwerveModule Class Reference

#include <rmb/drive/SwerveModule.h>

Inheritance diagram for rmb::SwerveModule:

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 ()
 

Detailed Description

Class managing the motion of a swerve module

Constructor & Destructor Documentation

◆ SwerveModule()

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.

Parameters
angularControllerController of the angle of module.
angularControllerController of the velocioty of module.
moduleTranslationthe position of teh modlue reletive to the center of the robot for kinematics.

Member Function Documentation

◆ getModuleTranslation()

const frc::Translation2d & rmb::SwerveModule::getModuleTranslation ( ) const

Returns the position fo the module reletive to the center of the robot for kinematics.

◆ getPosition()

frc::SwerveModulePosition rmb::SwerveModule::getPosition ( ) const

Returns the current position of the module useful for more accurate odometry.

◆ getState()

frc::SwerveModuleState rmb::SwerveModule::getState ( ) const

Returns the current state of the module.

◆ getTargetState()

frc::SwerveModuleState rmb::SwerveModule::getTargetState ( ) const
Returns
The target state of the module. This is useful for debugging.

◆ setPower() [1/2]

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.

Parameters
powerThe desired power output of the swerve module.

◆ setPower() [2/2]

void rmb::SwerveModule::setPower ( double power,
const frc::Rotation2d & angle )

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.

Parameters
powerThe desired power output of the swerve module.
angleThe desired angle of the swerve module.

◆ setState() [1/2]

void rmb::SwerveModule::setState ( const frc::SwerveModuleState & state)

Sets the desired state of the swerve module.

Parameters
stateThe desired state of the module.

◆ setState() [2/2]

void rmb::SwerveModule::setState ( const units::meters_per_second_t & velocity,
const frc::Rotation2d & angle )

Sets the desired state of the swerve module.

Parameters
velocityThe desired speed of the swerve module.
angleThe desired angle of the swerve module.

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