FRC Paradigm Shift #1259
Documentation for the 2021 Robot
Constants.h File Reference

Go to the source code of this file.

Namespaces

 DriveConstants
 
 ModuleConstants
 
 AutoConstants
 
 OIConstants
 
 VisionConstants
 

Macros

#define DualJoysticks
 Uncomment to set button binds for secondary controller to the primary controller. More...
 

Typedefs

using AutoConstants::radians_per_second_squared_t = compound_unit< radians, inverse< squared< second >>>
 

Variables

constexpr int DriveConstants::kNumSwerveModules = 4
 
constexpr meter_t DriveConstants::kTrackWidth = 23.5_in
 Distance between centers of left and right wheels on robot. More...
 
constexpr meter_t DriveConstants::kWheelBase = 23.5_in
 Distance between centers of front and back wheels on robot. More...
 
constexpr bool DriveConstants::kGyroReversed = false
 
constexpr double DriveConstants::kFrontLeftOffset = 2689.0
 
constexpr double DriveConstants::kFrontRightOffset = 205.0
 
constexpr double DriveConstants::kRearRightOffset = 1858.0
 
constexpr double DriveConstants::kRearLeftOffset = 983.0
 
constexpr double DriveConstants::kPulseWidthToZeroOne = 4096.0
 
constexpr double DriveConstants::kPulseWidthToRadians = 2.0 * wpi::math::pi / kPulseWidthToZeroOne
 
constexpr int ModuleConstants::kEncoderCPR = 2048
 
constexpr int ModuleConstants::kEncoderTicksPerSec = 10
 TalonFX::GetSelectedSensorVelocity() returns ticks/100ms = 10 ticks/sec. More...
 
constexpr double ModuleConstants::kWheelDiameterMeters = .1016
 4" More...
 
constexpr double ModuleConstants::kDriveGearRatio = 8.16
 MK3 swerve modules w/NEOs 12.1 ft/sec w/Falcon 13.6 ft/sec. More...
 
constexpr double ModuleConstants::kTurnMotorRevsPerWheelRev = 12.8
 
constexpr double ModuleConstants::kDriveEncoderMetersPerSec = kEncoderTicksPerSec / static_cast<double>(kEncoderCPR) / kDriveGearRatio * (kWheelDiameterMeters * wpi::math::pi)
 
constexpr double ModuleConstants::kTurnEncoderCPR = 4096.0 / kTurnMotorRevsPerWheelRev
 
constexpr double ModuleConstants::kP_ModuleTurningController = 1.1
 
constexpr double ModuleConstants::kD_ModuleTurningController = 0.03
 
constexpr double ModuleConstants::kPModuleDriveController = 0.001
 
constexpr uint ModuleConstants::kMotorCurrentLimit = 30
 
constexpr auto AutoConstants::kMaxSpeed = meters_per_second_t(3.75)
 
constexpr auto AutoConstants::kMaxAcceleration = meters_per_second_squared_t(4.5)
 
constexpr auto AutoConstants::kMaxAngularSpeed = radians_per_second_t(wpi::math::pi * 6.0)
 
constexpr auto AutoConstants::kMaxAngularAcceleration = unit_t<radians_per_second_squared_t>(wpi::math::pi * 6.0)
 
constexpr double AutoConstants::kPXController = 7.0
 
constexpr double AutoConstants::kDXController = 0.7
 
constexpr double AutoConstants::kPYController = 7.0
 
constexpr double AutoConstants::kDYController = 0.7
 
constexpr double AutoConstants::kPThetaController = 10.0
 
constexpr double AutoConstants::kDThetaController = 0.9
 
constexpr double OIConstants::kDeadzoneX = 0.015
 
constexpr double OIConstants::kDeadzoneY = 0.015
 
constexpr double OIConstants::kDeadzoneXY = 0.08
 
constexpr double OIConstants::kDeadzoneRot = 0.10
 
constexpr double OIConstants::kDeadzoneAbsRot = 0.50
 
constexpr int OIConstants::kPrimaryControllerPort = 0
 
constexpr int OIConstants::kSecondaryControllerPort = 1
 
constexpr double VisionConstants::kMountingAngle = 25.0
 
constexpr double VisionConstants::kMountingHeight = 22
 
constexpr double VisionConstants::kTargetHeight = 81.25
 
constexpr double VisionConstants::kMinTargetDistance = 70
 
constexpr double VisionConstants::kMaxTargetDistance = 380
 
constexpr double VisionConstants::kMinHoneDistance = 130
 
constexpr double VisionConstants::kMaxHoneDistance = 260
 
Teleop Drive Constraints
constexpr auto DriveConstants::kDriveSpeed = meters_per_second_t(3.5)
 
constexpr auto DriveConstants::kDriveAngularSpeed = radians_per_second_t(wpi::math::pi * 2.0)
 
CAN bus IDs

CAN IDs for swerve modules

constexpr int DriveConstants::kCanifierID = 0
 CANifier CAN ID (for absolute encoder PWM inputs) More...
 
constexpr int DriveConstants::kFrontLeftDriveMotorPort = 1
 Front Left Drive CAN ID (TalonFX) More...
 
constexpr int DriveConstants::kFrontLeftTurningMotorPort = 2
 Front Left Turn CAN ID (SparkMAX) More...
 
constexpr int DriveConstants::kFrontRightDriveMotorPort = 3
 Front Right Drive CAN ID (TalonFX) More...
 
constexpr int DriveConstants::kFrontRightTurningMotorPort = 4
 Front Right Turn CAN ID (SparkMAX) More...
 
constexpr int DriveConstants::kRearRightDriveMotorPort = 5
 Rear Right Drive CAN ID (TalonFX) More...
 
constexpr int DriveConstants::kRearRightTurningMotorPort = 6
 Rear Right Turn CAN ID (SparkMAX) More...
 
constexpr int DriveConstants::kRearLeftDriveMotorPort = 7
 Rear Left Drive CAN ID (TalonFX) More...
 
constexpr int DriveConstants::kRearLeftTurningMotorPort = 8
 
Canifier PWM channels

PWM channels for the canifier

constexpr CANifier::PWMChannel DriveConstants::kFrontLeftPWM = CANifier::PWMChannel::PWMChannel0
 
constexpr CANifier::PWMChannel DriveConstants::kFrontRightPWM = CANifier::PWMChannel::PWMChannel2
 
constexpr CANifier::PWMChannel DriveConstants::kRearRightPWM = CANifier::PWMChannel::PWMChannel1
 
constexpr CANifier::PWMChannel DriveConstants::kRearLeftPWM = CANifier::PWMChannel::PWMChannel3
 
Drive wheel reversal (inverting) flags

To keep the swerve module bevel gear facing inwards we need to reverse the right side

constexpr bool DriveConstants::kFrontLeftDriveMotorReversed = true
 
constexpr bool DriveConstants::kRearLeftDriveMotorReversed = true
 
constexpr bool DriveConstants::kFrontRightDriveMotorReversed = false
 
constexpr bool DriveConstants::kRearRightDriveMotorReversed = false
 
Robot RotationDrive PID Controller

Rotation PID Controller for Rotation Drive, converts between radians angle error to radians per second turn

constexpr double DriveConstants::kRotationDriveP = 1
 
constexpr double DriveConstants::kRotationDriveI = 0
 
constexpr double DriveConstants::kRotationDriveIMaxRange = 0
 
constexpr double DriveConstants::kRotationDriveD = 0.025
 
constexpr double DriveConstants::kRotationDriveMaxSpeed = 3.5
 Max speed for control. More...
 
constexpr double DriveConstants::kRotationDriveDirectionLimit = 3
 Speeds higher than value will prevent robot from changing directions for a turn. More...
 
constexpr double DriveConstants::kRotationDriveTolerance = 0.07
 Tolerance for turning. More...
 
Turn PID Controller for Swerve Modules
constexpr bool ModuleConstants::kTurnAdjust = false
 
constexpr double ModuleConstants::kTurnP = 0.75
 
constexpr double ModuleConstants::kTurnI = 0.0
 
constexpr double ModuleConstants::kTurnD = 0.0
 
constexpr double ModuleConstants::kTurnIA = 0.0
 
constexpr double ModuleConstants::kTurnIZ = 0.0
 
Drive PID Controller for Swerve Modules
constexpr bool ModuleConstants::kDriveAdjust = false
 
constexpr double ModuleConstants::kDriveP = 0.1
 
constexpr double ModuleConstants::kDriveI = 0
 
constexpr double ModuleConstants::kDriveD = 0
 
constexpr double ModuleConstants::kDriveFF = 0.047619
 

Macro Definition Documentation

#define DualJoysticks

Uncomment to set button binds for secondary controller to the primary controller.

Definition at line 24 of file Constants.h.