Skip to content

Swervedrive

Constructor

frc::Pose2d initial_pose = frc::Pose2d(0_m, 0_m, 0_rad);
wom::SwerveDrive *swerveDrive = new wom::SwerveDrive(config, initial_pose);

Config

TypeNameDescriptionSee Also
std::stringpathThe path in the networktables
wom::SwerveModule::angle_pid_conf_tanglePIDThe angle PID configSwerveModule
wom::SwerveModule::velocity_pid_conf_tvelocityPIDThe velocity PID configSwerveModule
wpi::array<SwerveModuleConfig, 4>modulesThe modulesSwerveModule
wom::GyrogyroThe gyroGyro
units::kilogram_tmassThe mass of the robot
wpi::array<double, 3>stateStdDevsThe standard deviations of the state
wpi::array<double, 3>visionMeasurementStdDevsThe standard deviations of the vision measurements

Example

wom::SwerveDriveConfig config;

SwerveDriveState

An enum of states for the swervedrive.

NameValueDescription
kZeroing0The drivetrain is zeroing
kIdle1The drivetrain is idle
kVelocity2The drivetrain is driving in velocity mode
kFieldRelativeVelocity3The drivetrain is driving in field relative velocity mode
kPose4The drivetrain is driving in pose mode
kIndividualTuning5The drivetrain is tuning individual modules
kTuning6The drivetrain is tuning
kXWheels7The drivetrain is driving in x wheels mode
kModuleTurn8The drivetrain is turning a module
kFRVelocityRotationLock9The drivetrain is driving in field relative velocity rotation lock mode

Example

wom::SwerveDriveState state = swerveDrive->GetState();
wom::SwerveDriveState newState = wom::SwerveDriveState::kIdle;

FieldRelativeSpeeds

A struct of speeds for the swervedrive.

TypeNameDescriptionSee Also
units::meters_per_second_tvxThe x speed
units::meters_per_second_tvyThe y speed
units::radians_per_second_tomegaThe omega speed

Example

swerveDrive->SetFieldRelativeVelocity(wom::FieldRelativeSpeeds{1_mps, 1_mps, 1_rad_per_s});

Methods

RotateMatchJoystick

Switches the state to handle the robot’s rotation matching that of the joystick.

void RotateMatchJoystick(units::radian_t joystickAngle, wom::FieldRelativeSpeeds speeds)

Usage

swerveDrive->RotateMatchJoystick(1_rad, wom::FieldRelativeSpeeds{1_mps, 1_mps, 1_rad_per_s});

SetIdle

Switches the state to idle.

Usage

swerveDrive->SetIdle();

SetZeroing

Switches the state to zeroing.

Usage

swerveDrive->SetZeroing();

SetVelocity

Switches the state to velocity.

void SetVelocity(frc::ChassisSpeeds speeds)

Usage

swerveDrive->SetVelocity(frc::ChassisSpeeds());

SetFieldRelativeVelocity

Switches the state to field relative velocity.

See Field Relative Speeds.

void SetFieldRelativeVelocity(wom::FieldRelativeSpeeds speeds)

Usage

swerveDrive->SetFieldRelativeVelocity(wom::FieldRelativeSpeeds{1_mps, 1_mps, 1_rad_per_s});

SetPose

Switches the state to pose.

void SetPose(frc::Pose2d pose)

Usage

swerveDrive->SetPose(frc::Pose2d(1_m, 1_m, 1_rad));

IsAtSetPose

Checks if the robot is at the set pose.

Usage

bool isAtSetPose = swerveDrive->IsAtSetPose();

SetIndividualTuning

Switches the state to individual tuning.

void SetIndividualTuning(int mod, units::radian_t angle, units::meters_per_second_t speed)

Usage

swerveDrive->SetIndividualTuning(0, 1_rad, 1_mps);

SetTuning

Switches the state to tuning.

SetTuning(units::radian_t angle, units::meters_per_second_t speed)

Usage

swerveDrive->SetTuning(1_rad, 1_mps);

SetZero

Sets PID setpoints to zero.

Usage

swerveDrive->SetZero();

SetVoltageLimit

Sets the voltage limit.

void SetVoltageLimit(units::volt_t driveVoltageLimit)

Usage

swerveDrive->SetVoltageLimit(12_V);

OnResetMode

Resets the intergral value of the PID controllers.

Usage

swerveDrive->OnResetMode();

SetXWheelState

Switches the state to x wheels.

Usage

swerveDrive->SetXWheelState();

SetIsFieldRelative

Sets whether the drivetrain is field relative.

void SetIsFieldRelative(bool value)

Usage

swerveDrive->SetIsFieldRelative(true);

GetIsFieldRelative

Gets whether the drivetrain is field relative.

Usage

bool isFieldRelative = swerveDrive->GetIsFieldRelative();

SetAccelerationLimit

Sets the acceleration limit.

void SetAccelerationLimit(units::meters_per_second_squared_t limit)

Usage

swerveDrive->SetAccelerationLimit(1_mps_sq);

ResetPose

Resets the pose.

void ResetPose(frc::Pose2d pose)

Usage

swerveDrive->ResetPose(frc::Pose2d());

GetPose

Gets the pose.

Usage

frc::Pose2d pose = swerveDrive->GetPose();

AddVisionMeasurement

Adds a vision measurement.

void AddVisionMeasurement(frc::Pose2d pose, units::second_t timestamp)

Usage

swerveDrive->AddVisionMeasurement(frc::Pose2d(), 1_s);

GetConfig

Gets the config of the drivetrain.

Returns SwerveDriveConfig (see above)

Usage

SwerveDriveConfig config = swerveDrive->GetConfig();

Swerve Modules

Constructor

SwerveModule(std::string path, SwerveModuleConfig config, angle_pid_conf_t anglePID, velocity_pid_conf_t velocityPID)

Example

SwerveModule *swerveModule = new SwerveModule(config);

Config

TypeNameDescriptionSee Also
frc::Translation2dpositionThe position of the module
wom::utils::GearboxdriveMotorThe drive gearboxGearbox
wom::utils::GearboxturnMotorThe turn gearboxGearbox
CANCodercanEncoderThe CANCoder
units::meter_twheelRadiusThe radius of the wheel
Example
SwerveModuleConfig config{
frc::Translation2d(1_m, 1_m),
driveMotor,
turnMotor,
canEncoder,
1_m
};

SwerveModuleState

An enum of states for the swerve module.

NameValueDescription
kZeroing0The module is zeroing
kIdle1The module is idle
kPID2The module is driving in PID mode

Example

SwerveModuleState state = swerveModule->GetState();
SwerveModuleState newState = SwerveModuleState::kIdle;

Methods

SetZero

Sets PID setpoints to zero.

Usage
swerveModule->SetZero();

SetIdle

Switches the state to idle.

Usage
swerveModule->SetIdle();

SetPID

Switches the state to PID and sets the setpoints.

void SetPID(units::radian_t angle, units::meters_per_second_t speed, units::second_t dt)
Usage
swerveModule->SetPID(1_rad, 1_mps, 1_s);

SetVoltageLimit

Sets the voltage limit.

void SetVoltageLimit(units::volt_t driveVoltageLimit)
Usage
swerveModule->SetVoltageLimit(12_V);

SetAccelerationLimit

Sets the acceleration limit.

SetAccelerationLimit(units::meters_per_second_squared_t limit)
Usage
swerveModule->SetAccelerationLimit(1_mps_sq);

GetPosition

Gets the position of the module.

Usage
frc::SwerveModulePosition position = swerveModule->GetPosition();

GetSpeed

Gets the speed of the module.

Usage
frc::SwerveModuleSpeed speed = swerveModule->GetSpeed();

GetDistance

Gets the distance of the module.

Usage
units::meter_t dist = swerveModule->GetDistance();

GetConfig

Gets the config of the module.

Returns SwerveModuleConfig (see above)

Usage
SwerveModuleConfig config = swerveModule->GetConfig();