-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathdrivesubsystem.py
215 lines (175 loc) · 9.5 KB
/
drivesubsystem.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
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
import math
import wpilib
import wpimath.geometry
import wpimath.kinematics
import wpimath.filter
import wpimath.units
import ntcore
import navx
import swervemodule
import constants
import swerveutils
from commands2 import Command
# import networklogger
class DriveSubsystem:
"""
Represents a swerve drive style drivetrain.
"""
def __init__(self) -> None:
self.kDriveKinematics = wpimath.kinematics.SwerveDrive4Kinematics(
wpimath.geometry.Translation2d(constants.kWheelBase / 2, constants.kTrackWidth / 2),
wpimath.geometry.Translation2d(constants.kWheelBase / 2, -constants.kTrackWidth / 2),
wpimath.geometry.Translation2d(-constants.kWheelBase / 2, constants.kTrackWidth / 2),
wpimath.geometry.Translation2d(-constants.kWheelBase / 2, -constants.kTrackWidth / 2),
)
self.front_left = swervemodule.SwerveModule(
constants.kFrontLeftDrivingCanId,
constants.kFrontLeftTurningCanId,
constants.kFrontLeftChassisAngularOffset,
constants.kFrontLeftAbsoluteEncoderOffset
)
self.rear_left = swervemodule.SwerveModule(
constants.kRearLeftDrivingCanId,
constants.kRearLeftTurningCanId,
constants.kRearLeftChassisAngularOffset,
constants.kRearLeftAbsoluteEncoderOffset
)
self.front_right = swervemodule.SwerveModule(
constants.kFrontRightDrivingCanId,
constants.kFrontRightTurningCanId,
constants.kFrontRightChassisAngularOffset,
constants.kFrontRightAbsoluteEncoderOffset
)
self.rear_right = swervemodule.SwerveModule(
constants.kRearRightDrivingCanId,
constants.kRearRightTurningCanId,
constants.kRearRightChassisAngularOffset,
constants.kRearRightAbsoluteEncoderOffset
)
# the gyro sensor
self.gyro = navx.AHRS(navx.AHRS.NavXComType.kMXP_SPI)
# Slew rate filter variables for controlling the lateral acceleration
self.current_rotation = 0.0
self.current_translation_dir = 0.0
self.current_translation_mag = 0.0
self.mag_limiter = wpimath.filter.SlewRateLimiter(constants.kMagnitudeSlewRate / 1)
self.rot_limiter = wpimath.filter.SlewRateLimiter(constants.kRotationalSlewRate / 1)
self.prev_time = ntcore._now() * pow(1, -6) # secodns
# Odometry class for tracking robot pose
# 4 defines the number of modules
self.odometry = wpimath.kinematics.SwerveDrive4Odometry(
self.kDriveKinematics,
# wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(self.gyro.getAngle())),
self.gyro.getRotation2d(),
(self.front_left.get_position(), self.front_right.get_position(), self.rear_left.get_position(), self.rear_right.get_position()),
wpimath.geometry.Pose2d()
)
self.reset_encoders()
# logger object for sending data to smart dashboard
# self.logger = networklogger.NetworkLogger()
def periodic(self):
self.odometry.update(
# wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(self.gyro.getAngle())),
self.gyro.getRotation2d(),
(self.front_left.get_position(), self.front_right.get_position(), self.rear_left.get_position(), self.rear_right.get_position()),
)
#self.logger.log_gyro(self.gyro.getAngle())
def drive(
self,
x_speed: float,
y_speed: float,
rot: float,
field_relative: bool,
rate_limit: bool,
) -> None:
"""
Method to drive the robot using joystick info.
:param x_speed: Speed of the robot in the x direction (forward).
:param y_speed: Speed of the robot in the y direction (sideways).
:param rot: Angular rate of the robot.
:param field_relative: Whether the provided x and y speeds are relative to the field.
:param rate_limit: Whether to enable rate limiting for smoother control
:param periodSeconds: Time
"""
x_speed_commanded = None
y_speed_commanded = None
if rate_limit:
# Convert XY to polar for rate limiting
input_translation_dir = math.atan2(y_speed, x_speed)
input_translation_mag = math.sqrt(pow(x_speed, 2) + pow(y_speed, 2))
# Calculate the direction slew rate based on an estimate of lateral acceleration
direction_slew_rate = None
if self.current_translation_mag != 0.0:
direction_slew_rate = abs(constants.kDirectionSlewRate / self.current_translation_mag)
else:
direction_slew_rate = 500.0 # some high number that means the slew rate is effectively instantaneous
current_time = ntcore._now() * pow(1, -6)
elapsed_time = current_time - self.prev_time
angleDif = swerveutils.angleDifference(input_translation_dir, self.current_translation_dir)
if angleDif < 0.45 * math.pi:
self.current_translation_dir = swerveutils.stepTowardsCircular(self.current_translation_dir, input_translation_dir, direction_slew_rate * elapsed_time)
self.current_translation_mag = self.mag_limiter.calculate(input_translation_mag)
elif angleDif > 0.85 * math.pi:
if self.current_translation_mag > 1e-4:
self.current_translation_mag = self.mag_limiter.calculate(0.0)
else:
self.current_translation_dir = swerveutils.wrapAngle(self.current_translation_dir + math.pi)
self.current_translation_mag = self.mag_limiter.calculate(input_translation_mag)
else:
self.current_translation_dir = swerveutils.stepTowardsCircular(self.current_translation_dir, input_translation_dir, direction_slew_rate * elapsed_time)
self.current_translation_mag = self.mag_limiter.calculate(0.0)
self.prev_time = current_time
x_speed_commanded = self.current_translation_mag * math.cos(self.current_translation_dir)
y_speed_commanded = self.current_translation_mag * math.sin(self.current_translation_dir)
self.current_rotation = self.rot_limiter.calculate(rot)
else:
x_speed_commanded = x_speed
y_speed_commanded = y_speed
self.current_rotation = rot
# Convert the commanded speeds into correct units for the drivetrain
x_speedDelivered = x_speed_commanded * constants.kMaxSpeed
y_speedDelivered = y_speed_commanded * constants.kMaxSpeed
rotDelivered = self.current_rotation * constants.kMaxAngularSpeed
(fl, fr, bl, br) = self.kDriveKinematics.toSwerveModuleStates(
wpimath.kinematics.ChassisSpeeds.fromFieldRelativeSpeeds(
x_speedDelivered, y_speedDelivered, rotDelivered, self.gyro.getRotation2d()#wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(self.gyro.getAngle()))
) if field_relative
else wpimath.kinematics.ChassisSpeeds(x_speedDelivered, y_speedDelivered, rotDelivered)
)
# Set the swerve modules to desired states
self.front_left.set_desired_state(fl)
self.front_right.set_desired_state(fr)
self.rear_left.set_desired_state(bl)
self.rear_right.set_desired_state(br)
def setX(self) -> None:
self.front_left.set_desired_state(wpimath.kinematics.SwerveModuleState(0, wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(45))))
self.front_right.set_desired_state(wpimath.kinematics.SwerveModuleState(0, wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(-45))))
self.rear_left.set_desired_state(wpimath.kinematics.SwerveModuleState(0, wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(-45))))
self.rear_right.set_desired_state(wpimath.kinematics.SwerveModuleState(0, wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(45))))
def setModuleStates(self, desiredStates: tuple[wpimath.kinematics.SwerveModuleState]) -> None:
self.kDriveKinematics.desaturateWheelSpeeds(desiredStates, constants.kMaxSpeed)
self.front_left.set_desired_state(desiredStates[0])
self.front_right.set_desired_state(desiredStates[1])
self.rear_left.set_desired_state(desiredStates[2])
self.rear_right.set_desired_state(desiredStates[3])
def reset_encoders(self) -> None:
self.front_left.reset_encoders()
self.rear_left.reset_encoders()
self.front_right.reset_encoders()
self.rear_right.reset_encoders()
# Returns the robot's heading in degrees from -180 to 180
def getHeading(self) -> float:
return self.gyro.getRotation2d().degrees()
# return wpimath.geometry.Rotation2d(wpimath.units.degreesToRadians(self.gyro.getAngle())).degrees()
# Zeroes the heading of the robot
def zeroHeading(self) -> None:
self.gyro.reset()
# Returns the turn rate of the robot in degrees per second
def getTurnRate(self) -> float:
return -self.gyro.getRate()
# returns the currently-estimated pose
def getPose(self) -> wpimath.geometry.Pose2d:
return self.odometry.getPose()
# Resets the odometry to the specified pose
def resetOdometry(self, pose: wpimath.geometry.Pose2d):
self.odometry.resetPosition(self.getHeading(), (self.front_left.get_position(), self.front_right.get_position(), self.rear_left.get_position(), self.rear_right.get_position()), pose)