-
Notifications
You must be signed in to change notification settings - Fork 3
/
Copy pathconstants.py
154 lines (118 loc) · 4.94 KB
/
constants.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
# Copyright (c) FIRST and other WPILib contributors.
# Open Source Software; you can modify and/or share it under the terms of
# the WPILib BSD license file in the root directory of this project.
"""
The constants module is a convenience place for teams to hold robot-wide
numerical or boolean constants. Don't use this for any other purpose!
"""
import math
from wpimath import units
from wpimath.geometry import Translation2d
from wpimath.kinematics import SwerveDrive4Kinematics
from wpimath.trajectory import TrapezoidProfileRadians
# from rev import CANSparkMax
from rev import SparkMax, SparkBaseConfig
class NeoMotorConstants:
kFreeSpeedRpm = 5676
class DriveConstants:
# Driving Parameters - Note that these are not the maximum capable speeds of
# the robot, rather the allowed maximum speeds
kMaxSpeedMetersPerSecond = 7
kMaxAngularSpeed = math.tau # radians per second
kDirectionSlewRate = 1.2 # radians per second
kMagnitudeSlewRate = 1.8 # percent per second (1 = 100%)
kRotationalSlewRate = 2.0 # percent per second (1 = 100%)
# Chassis configuration
kTrackWidth = units.inchesToMeters(26.5)
# Distance between centers of right and left wheels on robot
kWheelBase = units.inchesToMeters(26.5)
# Distance between front and back wheels on robot
kModulePositions = [
Translation2d(kWheelBase / 2, kTrackWidth / 2),
Translation2d(kWheelBase / 2, -kTrackWidth / 2),
Translation2d(-kWheelBase / 2, kTrackWidth / 2),
Translation2d(-kWheelBase / 2, -kTrackWidth / 2),
]
kDriveKinematics = SwerveDrive4Kinematics(*kModulePositions)
# Angular offsets of the modules relative to the chassis in radians
kFrontLeftChassisAngularOffset = math.radians(-120) #(-60 - 45)*(math.pi/180)
kFrontRightChassisAngularOffset = math.radians(-25)
kBackLeftChassisAngularOffset = math.radians(-205)
kBackRightChassisAngularOffset = math.radians(70)
# SPARK MAX CAN IDs
kFrontLeftDrivingCanId = 32
kRearLeftDrivingCanId = 1
kFrontRightDrivingCanId = 3
kRearRightDrivingCanId = 21
kFrontLeftTurningCanId = 13
kRearLeftTurningCanId = 11
kFrontRightTurningCanId = 12
kRearRightTurningCanId = 14
kGyroReversed = True
class ModuleConstants:
# The MAXSwerve module can be configured with one of three pinion gears: 12T, 13T, or 14T.
# This changes the drive speed of the module (a pinion gear with more teeth will result in a
# robot that drives faster).
kDrivingMotorPinionTeeth = 14
# Invert the turning encoder, since the output shaft rotates in the opposite direction of
# the steering motor in the MAXSwerve Module.
kTurningEncoderInverted = True
# Calculations required for driving motor conversion factors and feed forward
kDrivingMotorFreeSpeedRps = NeoMotorConstants.kFreeSpeedRpm / 60
kWheelDiameterMeters = 0.0762
kWheelCircumferenceMeters = kWheelDiameterMeters * math.pi
# 45 teeth on the wheel's bevel gear, 22 teeth on the first-stage spur gear, 15 teeth on the bevel pinion
kDrivingMotorReduction = (45.0 * 22) / (kDrivingMotorPinionTeeth * 15)
kDriveWheelFreeSpeedRps = (
kDrivingMotorFreeSpeedRps * kWheelCircumferenceMeters
) / kDrivingMotorReduction
kDrivingEncoderPositionFactor = (
kWheelDiameterMeters * math.pi
) / kDrivingMotorReduction # meters
kDrivingEncoderVelocityFactor = (
(kWheelDiameterMeters * math.pi) / kDrivingMotorReduction
) / 60.0 # meters per second
kTurningEncoderPositionFactor = math.tau # radian
kTurningEncoderVelocityFactor = math.tau / 60.0 # radians per second
kTurningEncoderPositionPIDMinInput = 0 # radian
kTurningEncoderPositionPIDMaxInput = kTurningEncoderPositionFactor # radian
kDrivingP = 0.04
kDrivingI = 0
kDrivingD = 0
kDrivingFF = 1 / kDriveWheelFreeSpeedRps
kDrivingMinOutput = -1
kDrivingMaxOutput = 1
kTurningP = 1
kTurningI = 0
kTurningD = 0
kTurningFF = 0
kTurningMinOutput = -1
kTurningMaxOutput = 1
kDrivingMotorIdleMode = SparkBaseConfig.IdleMode.kBrake
kTurningMotorIdleMode = SparkBaseConfig.IdleMode.kBrake
kDrivingMotorCurrentLimit = 50 # amp
kTurningMotorCurrentLimit = 20 # amp
class OIConstants:
kDriverControllerPort = 1
kDriveDeadband = 0.2
class AutoConstants:
kMaxSpeedMetersPerSecond = 10
kMaxAccelerationMetersPerSecondSquared = 10
kMaxAngularSpeedRadiansPerSecond = math.pi
kMaxAngularSpeedRadiansPerSecondSquared = math.pi
kPXController = 1
kPYController = 1
kPThetaController = 1
# Constraint for the motion profiled robot angle controller
kThetaControllerConstraints = TrapezoidProfileRadians.Constraints(
kMaxAngularSpeedRadiansPerSecond, kMaxAngularSpeedRadiansPerSecondSquared
)
class LEDConstants:
kLEDPort = 0
kLEDBuffer = 64
kSilverHue = 0
kSilverSat = 0
kSilverVal = 10
kBlueHue = 90
kBlueSat = 220
kBlueVal = 30