librmb 1.0
Rambunction 4330 Utility Library
Loading...
Searching...
No Matches
rmb::SwerveModulePower Struct Reference

#include <rmb/drive/SwerveModule.h>

Static Public Member Functions

static SwerveModulePower Optimize (const SwerveModulePower &desiredPower, const frc::Rotation2d &currentAngle)
 

Public Attributes

double power
 
frc::Rotation2d angle
 

Detailed Description

Open loop state of a swerve module.

This is often useful for teleoperated driving since it tends to more natural for a human driver to controll the power of a motor in open loop operation rather than the velocity in a closed loop mode (closed loop operation is, of course, not possible for angle control).

Member Function Documentation

◆ Optimize()

static SwerveModulePower rmb::SwerveModulePower::Optimize ( const SwerveModulePower & desiredPower,
const frc::Rotation2d & currentAngle )
static

Minimize the change in heading the desired power would require by potentially reversing the direction the wheel spins so the furthest a wheel will ever rotate is 90 degrees.

Parameters
desiredPowerThe desired power.
currentAngleThe current module angle.
Returns
Optomized module power.

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