constants

Robot constants package.

Sub-modules: robot_constants - Physical constants for the overall robot chassis swerve_constants - Swerve drivetrain constants and module name identifiers

All names are re-exported here so existing imports continue to work: from constants import SwerveDriveConsts # unchanged from constants import SwerveModuleName # new

 1"""
 2Robot constants package.
 3
 4Sub-modules:
 5  robot_constants   - Physical constants for the overall robot chassis
 6  swerve_constants  - Swerve drivetrain constants and module name identifiers
 7
 8All names are re-exported here so existing imports continue to work:
 9  from constants import SwerveDriveConsts        # unchanged
10  from constants import SwerveModuleName         # new
11"""
12
13from .robot_constants import RobotConstants
14from .swerve_constants import (
15    SwerveModuleName,
16    SwerveDriveConsts,
17    SwerveModuleMk4iConsts,
18    SwerveModuleMk4iL1Consts,
19    SwerveModuleMk4iL2Consts,
20    CaptainPlanetConsts,
21)
22
23__all__ = [
24    "RobotConstants",
25    "SwerveModuleName",
26    "SwerveDriveConsts",
27    "SwerveModuleMk4iConsts",
28    "SwerveModuleMk4iL1Consts",
29    "SwerveModuleMk4iL2Consts",
30    "CaptainPlanetConsts",
31]
class RobotConstants:
 7class RobotConstants:
 8    massKG: float = 63.9565
 9    # MOI: Moment of inertia, kg*m^2
10    MOI: float = 5.94175290870316
massKG: float = 63.9565
MOI: float = 5.94175290870316
class SwerveModuleName(enum.StrEnum):
14class SwerveModuleName(StrEnum):
15    """Canonical string identifiers for each swerve module position.
16
17    Values are the string names used in NetworkTables, SmartDashboard keys,
18    and subsystem registration (e.g. "frontLeft").
19    """
20    FRONT_LEFT = "frontLeft"
21    FRONT_RIGHT = "frontRight"
22    BACK_LEFT = "backLeft"
23    BACK_RIGHT = "backRight"

Canonical string identifiers for each swerve module position.

Values are the string names used in NetworkTables, SmartDashboard keys, and subsystem registration (e.g. "frontLeft").

FRONT_LEFT = <SwerveModuleName.FRONT_LEFT: 'frontLeft'>
FRONT_RIGHT = <SwerveModuleName.FRONT_RIGHT: 'frontRight'>
BACK_LEFT = <SwerveModuleName.BACK_LEFT: 'backLeft'>
BACK_RIGHT = <SwerveModuleName.BACK_RIGHT: 'backRight'>
class SwerveDriveConsts(constants.RobotConstants):
31class SwerveDriveConsts(RobotConstants):
32    # where the wheel is compared to the center of the robot in meters
33    moduleFrontLeftX: float = 0.264
34    moduleFrontLeftY: float = 0.287
35    moduleFrontRightX: float = 0.264
36    moduleFrontRightY: float = -0.287
37    moduleBackLeftX: float = -0.264
38    moduleBackLeftY: float = 0.287
39    moduleBackRightX: float = -0.264
40    moduleBackRightY: float = -0.287
41
42    # inverts if the module or gyro does not rotate counterclockwise positive
43    invertGyro: bool = False
44    moduleFrontLeftInvertDrive: bool = True
45    moduleFrontRightInvertDrive: bool = True
46    moduleBackLeftInvertDrive: bool = True
47    moduleBackRightInvertDrive: bool = True
48
49    moduleFrontLeftInvertSteer: bool = True
50    moduleFrontRightInvertSteer: bool = True
51    moduleBackLeftInvertSteer: bool = True
52    moduleBackRightInvertSteer: bool = True
53
54    maxTranslationMPS: float = 4.6
55    maxAngularDPS: float = math.degrees(
56        maxTranslationMPS / math.hypot(moduleFrontLeftY, moduleFrontLeftX)
57    )
moduleFrontLeftX: float = 0.264
moduleFrontLeftY: float = 0.287
moduleFrontRightX: float = 0.264
moduleFrontRightY: float = -0.287
moduleBackLeftX: float = -0.264
moduleBackLeftY: float = 0.287
moduleBackRightX: float = -0.264
moduleBackRightY: float = -0.287
invertGyro: bool = False
moduleFrontLeftInvertDrive: bool = True
moduleFrontRightInvertDrive: bool = True
moduleBackLeftInvertDrive: bool = True
moduleBackRightInvertDrive: bool = True
moduleFrontLeftInvertSteer: bool = True
moduleFrontRightInvertSteer: bool = True
moduleBackLeftInvertSteer: bool = True
moduleBackRightInvertSteer: bool = True
maxTranslationMPS: float = 4.6
maxAngularDPS: float = 675.8741415151436
class SwerveModuleMk4iConsts(constants.SwerveDriveConsts):
60class SwerveModuleMk4iConsts(SwerveDriveConsts):
61    """
62    https://github.com/SwerveDriveSpecialties/swerve-lib/blob/develop/src/main/java/com/swervedrivespecialties/swervelib/ctre/Falcon500DriveControllerFactoryBuilder.java
63    """
64
65    kNominalVoltage: float = 12.0
66    # current limits use amps
67    kDriveCurrentLimit: int = 40
68    kSteerCurrentLimit: int = 20
69    # ramp rate: how fast the bot can go from 0% to 100%, measured in seconds
70    kRampRate: float = 0.25
71    kTicksPerRotation: int = 1
72    kCanStatusFrameHz: int = 10
73    quadratureMeasurementRateMs: int = 10
74    quadratureAverageDepth: int = 2
75    numDriveMotors: int = 1
76    motorType: str = "NEO"  # should be an option in wpimath.system.plant.DCMotor
kNominalVoltage: float = 12.0
kDriveCurrentLimit: int = 40
kSteerCurrentLimit: int = 20
kRampRate: float = 0.25
kTicksPerRotation: int = 1
kCanStatusFrameHz: int = 10
quadratureMeasurementRateMs: int = 10
quadratureAverageDepth: int = 2
numDriveMotors: int = 1
motorType: str = 'NEO'
class SwerveModuleMk4iL1Consts(constants.SwerveModuleMk4iConsts):
79class SwerveModuleMk4iL1Consts(SwerveModuleMk4iConsts):
80    """
81    https://docs.yagsl.com/configuring-yagsl/standard-conversion-factors
82    """
83
84    wheelDiameter: float = 0.10033  # in meters
85    driveGearRatio: float = 8.14
86    steerGearRatio: float = 150 / 7
87
88    # position: meters per rotation
89    # velocity: meters per second
90    drivePositionConversionFactor: float = (math.pi * wheelDiameter) / (
91        driveGearRatio * SwerveModuleMk4iConsts.kTicksPerRotation
92    )
93    driveVelocityConversionFactor: float = drivePositionConversionFactor / 60.0
94    steerPositionConversionFactor: float = 360 / (
95        steerGearRatio * SwerveModuleMk4iConsts.kTicksPerRotation
96    )
97    steerVelocityConversionFactor: float = steerPositionConversionFactor / 60.0
98
99    moduleType: str = "Mk4i_L1"
wheelDiameter: float = 0.10033
driveGearRatio: float = 8.14
steerGearRatio: float = 21.428571428571427
drivePositionConversionFactor: float = 0.03872186620818967
driveVelocityConversionFactor: float = 0.0006453644368031611
steerPositionConversionFactor: float = 16.8
steerVelocityConversionFactor: float = 0.28
moduleType: str = 'Mk4i_L1'
class SwerveModuleMk4iL2Consts(constants.SwerveModuleMk4iConsts):
102class SwerveModuleMk4iL2Consts(SwerveModuleMk4iConsts):
103    """
104    https://docs.yagsl.com/configuring-yagsl/standard-conversion-factors
105    """
106
107    wheelDiameter: float = 0.10033  # in meters
108    # COf: coefficient, force/force (no units)
109    wheelCOF: float = 1.0130211
110    driveGearRatio: float = 6.75
111    steerGearRatio: float = 150 / 7
112
113    # position: meters per rotation
114    # velocity: meters per second
115    drivePositionConversionFactor: float = (wheelCOF * (math.pi * wheelDiameter)) / (
116        driveGearRatio * SwerveModuleMk4iConsts.kTicksPerRotation
117    )
118    driveVelocityConversionFactor: float = drivePositionConversionFactor / 60.0
119    steerPositionConversionFactor: float = 360 / (
120        steerGearRatio * SwerveModuleMk4iConsts.kTicksPerRotation
121    )
122    steerVelocityConversionFactor: float = steerPositionConversionFactor / 60.0
123
124    moduleType: str = "Mk4i_L2"
wheelDiameter: float = 0.10033
wheelCOF: float = 1.0130211
driveGearRatio: float = 6.75
steerGearRatio: float = 21.428571428571427
drivePositionConversionFactor: float = 0.04730373177069974
driveVelocityConversionFactor: float = 0.0007883955295116624
steerPositionConversionFactor: float = 16.8
steerVelocityConversionFactor: float = 0.28
moduleType: str = 'Mk4i_L2'
class CaptainPlanetConsts:
141class CaptainPlanetConsts:
142    kIntakeMotorCanId = 11
143    kRollerMotorCanId = 56
144    kMotorInverted = False
145    kCurrentLimitAmps = 30
146    # kBreakBeam = 2
147    # kFrontBreakBeam = 2
148    # kBackBreakBeam = 0
149    # kHallEffectSensor = 6
150    kDefaultSpeed = 0.15
151    kOperatorDampener = 0.15
152    class BreakBeamActionOptions(Enum):
153        DONOTHING = 1
154        TOFRONT = 2
155        TOBACK = 3
kIntakeMotorCanId = 11
kRollerMotorCanId = 56
kMotorInverted = False
kCurrentLimitAmps = 30
kDefaultSpeed = 0.15
kOperatorDampener = 0.15
class CaptainPlanetConsts.BreakBeamActionOptions(enum.Enum):
152    class BreakBeamActionOptions(Enum):
153        DONOTHING = 1
154        TOFRONT = 2
155        TOBACK = 3
DONOTHING = <BreakBeamActionOptions.DONOTHING: 1>
TOFRONT = <BreakBeamActionOptions.TOFRONT: 2>
TOBACK = <BreakBeamActionOptions.TOBACK: 3>