Skip to content

Commit

Permalink
modified the units for ff and construct with velocity
Browse files Browse the repository at this point in the history
  • Loading branch information
outsidermm committed Jan 9, 2024
1 parent ed7db50 commit 481a093
Showing 1 changed file with 5 additions and 5 deletions.
10 changes: 5 additions & 5 deletions components/chassis.py
Original file line number Diff line number Diff line change
Expand Up @@ -198,12 +198,12 @@ def set(self, desired_state: SwerveModuleState):
# rescale the speed target based on how close we are to being correctly aligned
target_speed = self.state.speed * math.cos(target_displacement) ** 2
speed_volt = self.drive_ff.calculate(target_speed)
drive_request = phoenix6.controls.VelocityVoltage(0)
self.drive.set_control(
drive_request.with_velocity(
target_speed / self.WHEEL_CIRCUMFERENCE
).with_feed_forward(speed_volt / self.MAX_DRIVE_VOLTS)

# original position change/100ms, new m/s -> rot/s
drive_request = phoenix6.controls.VelocityVoltage(
target_speed / self.WHEEL_CIRCUMFERENCE
)
self.drive.set_control(drive_request.with_feed_forward(speed_volt))

#
def sync_steer_encoders(self) -> None:
Expand Down

0 comments on commit 481a093

Please sign in to comment.