|
TR-mbed 1.0
|
#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 } |
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 |
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.
| 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.
| lfId | Left front motor CAN ID |
| rfId | Right front motor CAN ID |
| lbId | Left back motor CAN ID |
| rbId | Right back motor CAN ID |
| radius | radius in meters |
|
static |
| WheelSpeeds ChassisSubsystem::chassisSpeedsToWheelSpeeds | ( | ChassisSpeeds | chassisSpeeds | ) |
|
static |
Helper method to convert an angle from radians to degrees
| degrees | An angle measurement in degrees |
| ChassisSubsystem::BrakeMode ChassisSubsystem::getBrakeMode | ( | ) |
A helper method to find the brake mode of the chassis.
| ChassisSpeeds ChassisSubsystem::getChassisSpeeds | ( | ) | const |
Gets the chassis's current ChassisSpeeds from odometry (only velocity state)
| int ChassisSubsystem::getHeadingDegrees | ( | ) | const |
Gets the IMU's current angle reading in degrees
| DJIMotor & ChassisSubsystem::getMotor | ( | MotorLocation | location | ) |
| double ChassisSubsystem::getMotorSpeed | ( | MotorLocation | location, |
| SPEED_UNIT | unit = RPM |
||
| ) |
gets motor speed based on location and speed unit
| location | location of the motor |
| unit | unit of speed |
| Pose2D ChassisSubsystem::getPose | ( | ) |
Gets the chassis's current 2D position (TO BE DONE)
| WheelSpeeds ChassisSubsystem::getWheelSpeeds | ( | ) | const |
Gets the chassis's current WheelSpeeds
| void ChassisSubsystem::initializeImu | ( | ) |
A helper method to initialize the IMU.
|
static |
| char * ChassisSubsystem::MatrixtoString | ( | Eigen::MatrixXd | mat | ) |
| WheelSpeeds ChassisSubsystem::normalizeWheelSpeeds | ( | WheelSpeeds | wheelSpeeds | ) | const |
The normalizeWheelSpeeds method normalizes each motor with respect to m_OmniKinematicsLimits.max_Vel
| wheelSpeeds | The speeds in m/s to drive each motor at |
|
static |
| void ChassisSubsystem::periodic | ( | ) |
A method that should be run every main loop to update the Chassis's estimated position
|
static |
Helper method to convert an angle from degrees to radians
| radians | An angle measurement in radians |
|
static |
| void ChassisSubsystem::readImu | ( | ) |
A helper method to read/update the IMU.
| ChassisSpeeds ChassisSubsystem::rotateChassisSpeed | ( | ChassisSpeeds | speeds, |
| double | yawCurrent | ||
| ) |
The rotateChassisSpeed method
| speeds | The relative speeds (vX, vY, and vOmega) in m/s |
| yawCurrent | The 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.
| void ChassisSubsystem::setBrakeMode | ( | BrakeMode | brakeMode | ) |
A helper method to set the brake mode of the chassis.
| brakeMode | An enum representing the brake mode of the chassis |
| float ChassisSubsystem::setChassisSpeeds | ( | ChassisSpeeds | desiredChassisSpeeds_, |
| DRIVE_MODE | mode = ROBOT_ORIENTED |
||
| ) |
The setChassisSpeeds method is used to drive the chassis in a chassis relative manner.
| desiredChassisSpeeds | The robot-relative speeds (vX, vY, and vOmega) in m/s |
| void ChassisSubsystem::setMotorSpeedPID | ( | MotorLocation | location, |
| float | kP, | ||
| float | kI, | ||
| float | kD | ||
| ) |
Sets the P, I, and D control parameters
| location | The MotorLocation of the motor (LF, RF, LB, RB) |
| kP | The new P (proportional) parameter |
| kI | The new I (integral) parameter |
| kD | The new D (derivative) parameter |
| void ChassisSubsystem::setOmniKinematicsLimits | ( | double | max_Vel, |
| double | max_vOmega | ||
| ) |
sets chassis speeds limits
| max_Vel | maximum linear velocity of chassis |
| max_vOmega | maximum angular velocity of chassis |
| void ChassisSubsystem::setSpeedFeedforward | ( | MotorLocation | location, |
| double | FF | ||
| ) |
Sets the Feedforward for the SpeedPID
| location | The MotorLocation of the motor (LF, RF, LB, RB) |
| FF | The arbitrary Feedforward value ranges from [-1, 1] |
| void ChassisSubsystem::setSpeedFF_Ks | ( | double | Ks | ) |
Sets the Friction Feedforward compensation for the SpeedPID
| Ks | The arbitrary Friction Feedforward Gain in [-1, 1] |
| void ChassisSubsystem::setSpeedIntegralCap | ( | MotorLocation | location, |
| double | cap | ||
| ) |
Sets the IntegralCap for the SpeedPID
| location | The MotorLocation of the motor (LF, RF, LB, RB) |
| cap | The maximum integral that can be achieved, above which the integral will be capped |
| void ChassisSubsystem::setWheelPower | ( | WheelSpeeds | wheelPower | ) |
The driveMotors method drives each motor at a specific speed
| wheelPower | The speeds in [-1, 1] to drive each motor at |
| float ChassisSubsystem::setWheelSpeeds | ( | WheelSpeeds | wheelSpeeds | ) |
The setWheelSpeeds method drives each motor at a specific speed
| wheelSpeeds | The speeds in RPM to drive each motor at |
| 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)
| motor | your Yaw Motor reference as in &{motor_name} |
| initial_offset_ticks | initial offset of your Yaw Motor Angle in ticks (try pass it as double) |
|
static |
| ChassisSpeeds ChassisSubsystem::wheelSpeedsToChassisSpeeds | ( | WheelSpeeds | wheelSpeeds | ) |
| ChassisSpeeds ChassisSubsystem::desiredChassisSpeeds |
| WheelSpeeds ChassisSubsystem::desiredWheelSpeeds |
| uint32_t ChassisSubsystem::lastPIDTime = 0 |
| ChassisSpeeds ChassisSubsystem::m_chassisSpeeds |
| OmniKinematicsLimits ChassisSubsystem::m_OmniKinematicsLimits |
| WheelSpeeds ChassisSubsystem::m_wheelSpeeds |
| int ChassisSubsystem::PEAK_POWER_ALL |
| int ChassisSubsystem::PEAK_POWER_SINGLE |
| PID ChassisSubsystem::pid_LB |
| PID ChassisSubsystem::pid_LF |
| PID ChassisSubsystem::pid_RB |
| PID ChassisSubsystem::pid_RF |
| float ChassisSubsystem::power_limit |
| float ChassisSubsystem::previousRPM[4] = {0, 0, 0, 0} |
| double ChassisSubsystem::prevVel |
| int ChassisSubsystem::testData[300][4] |
| int ChassisSubsystem::testDataIndex = 0 |
| 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)