TR-mbed 1.0
Loading...
Searching...
No Matches
Public Types | Public Member Functions | Static Public Member Functions | Public Attributes | List of all members
ChassisSubsystem Class Reference

#include <ChassisSubsystem.h>

Public Types

enum  BrakeMode { BRAKE , COAST }
 
enum  MotorLocation { LEFT_FRONT , RIGHT_FRONT , LEFT_BACK , RIGHT_BACK }
 
enum  SPEED_UNIT { RAD_PER_SECOND , RPM , METER_PER_SECOND }
 
enum  DRIVE_MODE { YAW_ORIENTED , REVERSE_YAW_ORIENTED , ROBOT_ORIENTED }
 

Public Member Functions

 ChassisSubsystem (short lfId, short rfId, short lbId, short rbId, BNO055 &imu, double radius)
 
WheelSpeeds getWheelSpeeds () const
 
float setWheelSpeeds (WheelSpeeds wheelSpeeds)
 
WheelSpeeds normalizeWheelSpeeds (WheelSpeeds wheelSpeeds) const
 
void setWheelPower (WheelSpeeds wheelPower)
 
ChassisSpeeds getChassisSpeeds () const
 
float setChassisSpeeds (ChassisSpeeds desiredChassisSpeeds_, DRIVE_MODE mode=ROBOT_ORIENTED)
 
ChassisSpeeds rotateChassisSpeed (ChassisSpeeds speeds, double yawCurrent)
 
DJIMotorgetMotor (MotorLocation location)
 
void setMotorSpeedPID (MotorLocation location, float kP, float kI, float kD)
 
void setSpeedIntegralCap (MotorLocation location, double cap)
 
void setSpeedFeedforward (MotorLocation location, double FF)
 
void setSpeedFF_Ks (double Ks)
 
BrakeMode getBrakeMode ()
 
void setBrakeMode (BrakeMode brakeMode)
 
void initializeImu ()
 
void periodic ()
 
int getHeadingDegrees () const
 
Pose2D getPose ()
 
double getMotorSpeed (MotorLocation location, SPEED_UNIT unit)
 
void setOmniKinematicsLimits (double max_Vel, double max_vOmega)
 
void readImu ()
 
void setYawReference (DJIMotor *motor, double initial_offset_ticks)
 
WheelSpeeds chassisSpeedsToWheelSpeeds (ChassisSpeeds chassisSpeeds)
 
ChassisSpeeds wheelSpeedsToChassisSpeeds (WheelSpeeds wheelSpeeds)
 
char * MatrixtoString (Eigen::MatrixXd mat)
 

Static Public Member Functions

static float limitAcceleration (float desiredRPM, float previousRPM, int power)
 
static float p_theory (int LeftFrontPower, int RightFrontPower, int LeftBackPower, int RightBackPower, int LeftFrontRpm, int RightFrontRpm, int LeftBackRpm, int RightBackRpm)
 
static float Bisection (int LeftFrontPower, int RightFrontPower, int LeftBackPower, int RightBackPower, int LeftFrontRpm, int RightFrontRpm, int LeftBackRpm, int RightBackRpm, float chassisPowerLimit)
 
static double radiansToDegrees (double radians)
 
static double degreesToRadians (double degrees)
 
static double radiansToTicks (double radians)
 
static double ticksToRadians (double ticks)
 

Public Attributes

float previousRPM [4] = {0, 0, 0, 0}
 
float power_limit
 
ChassisSpeeds desiredChassisSpeeds
 
WheelSpeeds desiredWheelSpeeds
 
OmniKinematicsLimits m_OmniKinematicsLimits
 
ChassisSpeeds m_chassisSpeeds
 
WheelSpeeds m_wheelSpeeds
 
int PEAK_POWER_ALL
 
int PEAK_POWER_SINGLE
 
PID pid_LF
 
PID pid_RF
 
PID pid_LB
 
PID pid_RB
 
uint32_t lastPIDTime = 0
 
double prevVel
 
double yawPhase
 
int testData [300][4]
 
int testDataIndex = 0
 

Detailed Description

The ChassisSubsystem class is a wrapper for the DJIMotor class that allows for easy control of the chassis.

The ChassisSubsystem class also contains methods for controlling the chassis with the IMU. The IMU is used to control the chassis in a field-relative manner, and to control the chassis with an offset angle.

Member Enumeration Documentation

◆ BrakeMode

The BrakeMode enum is used to set the brake mode of the chassis.

Enumerator
BRAKE 
COAST 

◆ DRIVE_MODE

Enumerator
YAW_ORIENTED 
REVERSE_YAW_ORIENTED 
ROBOT_ORIENTED 

◆ MotorLocation

Enumerator
LEFT_FRONT 
RIGHT_FRONT 
LEFT_BACK 
RIGHT_BACK 

◆ SPEED_UNIT

Enumerator
RAD_PER_SECOND 
RPM 
METER_PER_SECOND 

Constructor & Destructor Documentation

◆ ChassisSubsystem()

ChassisSubsystem::ChassisSubsystem ( short  lfId,
short  rfId,
short  lbId,
short  rbId,
BNO055 imu,
double  radius 
)

The Chassis constructor. This constructor takes in the CAN IDs of the four motors on the chassis.

Parameters
lfIdLeft front motor CAN ID
rfIdRight front motor CAN ID
lbIdLeft back motor CAN ID
rbIdRight back motor CAN ID
radiusradius in meters

Member Function Documentation

◆ Bisection()

float ChassisSubsystem::Bisection ( int  LeftFrontPower,
int  RightFrontPower,
int  LeftBackPower,
int  RightBackPower,
int  LeftFrontRpm,
int  RightFrontRpm,
int  LeftBackRpm,
int  RightBackRpm,
float  chassisPowerLimit 
)
static

◆ chassisSpeedsToWheelSpeeds()

WheelSpeeds ChassisSubsystem::chassisSpeedsToWheelSpeeds ( ChassisSpeeds  chassisSpeeds)

◆ degreesToRadians()

double ChassisSubsystem::degreesToRadians ( double  degrees)
static

Helper method to convert an angle from radians to degrees

Parameters
degreesAn angle measurement in degrees
Returns
The angle converted to radians

◆ getBrakeMode()

ChassisSubsystem::BrakeMode ChassisSubsystem::getBrakeMode ( )

A helper method to find the brake mode of the chassis.

Returns
An enum representing the brake mode of the chassis

◆ getChassisSpeeds()

ChassisSpeeds ChassisSubsystem::getChassisSpeeds ( ) const

Gets the chassis's current ChassisSpeeds from odometry (only velocity state)

Returns
The chassis's current ChassisSpeeds

◆ getHeadingDegrees()

int ChassisSubsystem::getHeadingDegrees ( ) const

Gets the IMU's current angle reading in degrees

Returns
The IMU's current angle reading in degrees

◆ getMotor()

DJIMotor & ChassisSubsystem::getMotor ( MotorLocation  location)

A helper method to find a DJIMotor object from an index.

Parameters
locationThe MotorLocation of the motor (LF, RF, LB, RB)
Returns
a DJIMotor object

◆ getMotorSpeed()

double ChassisSubsystem::getMotorSpeed ( MotorLocation  location,
SPEED_UNIT  unit = RPM 
)

gets motor speed based on location and speed unit

Returns
motor speed in selected unit
Parameters
locationlocation of the motor
unitunit of speed

◆ getPose()

Pose2D ChassisSubsystem::getPose ( )

Gets the chassis's current 2D position (TO BE DONE)

Returns
The chassis's current 2D position

◆ getWheelSpeeds()

WheelSpeeds ChassisSubsystem::getWheelSpeeds ( ) const

Gets the chassis's current WheelSpeeds

Returns
The chassis's current WheelSpeeds

◆ initializeImu()

void ChassisSubsystem::initializeImu ( )

A helper method to initialize the IMU.

◆ limitAcceleration()

float ChassisSubsystem::limitAcceleration ( float  desiredRPM,
float  previousRPM,
int  power 
)
static

◆ MatrixtoString()

char * ChassisSubsystem::MatrixtoString ( Eigen::MatrixXd  mat)

◆ normalizeWheelSpeeds()

WheelSpeeds ChassisSubsystem::normalizeWheelSpeeds ( WheelSpeeds  wheelSpeeds) const

The normalizeWheelSpeeds method normalizes each motor with respect to m_OmniKinematicsLimits.max_Vel

Parameters
wheelSpeedsThe speeds in m/s to drive each motor at

◆ p_theory()

float ChassisSubsystem::p_theory ( int  LeftFrontPower,
int  RightFrontPower,
int  LeftBackPower,
int  RightBackPower,
int  LeftFrontRpm,
int  RightFrontRpm,
int  LeftBackRpm,
int  RightBackRpm 
)
static

◆ periodic()

void ChassisSubsystem::periodic ( )

A method that should be run every main loop to update the Chassis's estimated position

◆ radiansToDegrees()

double ChassisSubsystem::radiansToDegrees ( double  radians)
static

Helper method to convert an angle from degrees to radians

Parameters
radiansAn angle measurement in radians
Returns
The angle converted to degree

◆ radiansToTicks()

double ChassisSubsystem::radiansToTicks ( double  radians)
static

◆ readImu()

void ChassisSubsystem::readImu ( )

A helper method to read/update the IMU.

◆ rotateChassisSpeed()

ChassisSpeeds ChassisSubsystem::rotateChassisSpeed ( ChassisSpeeds  speeds,
double  yawCurrent 
)

The rotateChassisSpeed method

Parameters
speedsThe relative speeds (vX, vY, and vOmega) in m/s
yawCurrentThe CCW-positive angle in degrees

There's no setChassisPower because it doesn't make sense. Power (is not PWM voltage) saturates your motor speeds, and it's not related to motor speed.

◆ setBrakeMode()

void ChassisSubsystem::setBrakeMode ( BrakeMode  brakeMode)

A helper method to set the brake mode of the chassis.

Parameters
brakeModeAn enum representing the brake mode of the chassis

◆ setChassisSpeeds()

float ChassisSubsystem::setChassisSpeeds ( ChassisSpeeds  desiredChassisSpeeds_,
DRIVE_MODE  mode = ROBOT_ORIENTED 
)

The setChassisSpeeds method is used to drive the chassis in a chassis relative manner.

Parameters
desiredChassisSpeedsThe robot-relative speeds (vX, vY, and vOmega) in m/s

◆ setMotorSpeedPID()

void ChassisSubsystem::setMotorSpeedPID ( MotorLocation  location,
float  kP,
float  kI,
float  kD 
)

Sets the P, I, and D control parameters

Parameters
locationThe MotorLocation of the motor (LF, RF, LB, RB)
kPThe new P (proportional) parameter
kIThe new I (integral) parameter
kDThe new D (derivative) parameter

◆ setOmniKinematicsLimits()

void ChassisSubsystem::setOmniKinematicsLimits ( double  max_Vel,
double  max_vOmega 
)

sets chassis speeds limits

Parameters
max_Velmaximum linear velocity of chassis
max_vOmegamaximum angular velocity of chassis

◆ setSpeedFeedforward()

void ChassisSubsystem::setSpeedFeedforward ( MotorLocation  location,
double  FF 
)

Sets the Feedforward for the SpeedPID

Parameters
locationThe MotorLocation of the motor (LF, RF, LB, RB)
FFThe arbitrary Feedforward value ranges from [-1, 1]

◆ setSpeedFF_Ks()

void ChassisSubsystem::setSpeedFF_Ks ( double  Ks)

Sets the Friction Feedforward compensation for the SpeedPID

Parameters
KsThe arbitrary Friction Feedforward Gain in [-1, 1]

◆ setSpeedIntegralCap()

void ChassisSubsystem::setSpeedIntegralCap ( MotorLocation  location,
double  cap 
)

Sets the IntegralCap for the SpeedPID

Parameters
locationThe MotorLocation of the motor (LF, RF, LB, RB)
capThe maximum integral that can be achieved, above which the integral will be capped

◆ setWheelPower()

void ChassisSubsystem::setWheelPower ( WheelSpeeds  wheelPower)

The driveMotors method drives each motor at a specific speed

Parameters
wheelPowerThe speeds in [-1, 1] to drive each motor at

◆ setWheelSpeeds()

float ChassisSubsystem::setWheelSpeeds ( WheelSpeeds  wheelSpeeds)

The setWheelSpeeds method drives each motor at a specific speed

Parameters
wheelSpeedsThe speeds in RPM to drive each motor at

◆ setYawReference()

void ChassisSubsystem::setYawReference ( DJIMotor motor,
double  initial_offset_ticks 
)

Yaw motor is a motor that controls the Turret yawPhase is an initial offset of your Yaw Motor Angle (basically which direction you want your Heading to be w.r.t Yaw Motor)

Parameters
motoryour Yaw Motor reference as in &{motor_name}
initial_offset_ticksinitial offset of your Yaw Motor Angle in ticks (try pass it as double)

◆ ticksToRadians()

double ChassisSubsystem::ticksToRadians ( double  ticks)
static

◆ wheelSpeedsToChassisSpeeds()

ChassisSpeeds ChassisSubsystem::wheelSpeedsToChassisSpeeds ( WheelSpeeds  wheelSpeeds)

Member Data Documentation

◆ desiredChassisSpeeds

ChassisSpeeds ChassisSubsystem::desiredChassisSpeeds

◆ desiredWheelSpeeds

WheelSpeeds ChassisSubsystem::desiredWheelSpeeds

◆ lastPIDTime

uint32_t ChassisSubsystem::lastPIDTime = 0

◆ m_chassisSpeeds

ChassisSpeeds ChassisSubsystem::m_chassisSpeeds

◆ m_OmniKinematicsLimits

OmniKinematicsLimits ChassisSubsystem::m_OmniKinematicsLimits

◆ m_wheelSpeeds

WheelSpeeds ChassisSubsystem::m_wheelSpeeds

◆ PEAK_POWER_ALL

int ChassisSubsystem::PEAK_POWER_ALL

◆ PEAK_POWER_SINGLE

int ChassisSubsystem::PEAK_POWER_SINGLE

◆ pid_LB

PID ChassisSubsystem::pid_LB

◆ pid_LF

PID ChassisSubsystem::pid_LF

◆ pid_RB

PID ChassisSubsystem::pid_RB

◆ pid_RF

PID ChassisSubsystem::pid_RF

◆ power_limit

float ChassisSubsystem::power_limit

◆ previousRPM

float ChassisSubsystem::previousRPM[4] = {0, 0, 0, 0}

◆ prevVel

double ChassisSubsystem::prevVel

◆ testData

int ChassisSubsystem::testData[300][4]

◆ testDataIndex

int ChassisSubsystem::testDataIndex = 0

◆ yawPhase

double ChassisSubsystem::yawPhase

yawPhase is an initial offset of your Yaw Motor Angle (basically which direction you want your Heading to be w.r.t Yaw Motor)


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