mirror of
https://github.com/wpilibsuite/allwpilib
synced 2026-06-19 00:41:43 +00:00
164 lines
6.6 KiB
Python
164 lines
6.6 KiB
Python
#
|
|
# 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.
|
|
#
|
|
|
|
import math
|
|
|
|
import wpilib
|
|
import wpimath
|
|
import wpimath.units
|
|
|
|
from exampleglobalmeasurementsensor import ExampleGlobalMeasurementSensor
|
|
|
|
|
|
class Drivetrain:
|
|
"""Represents a mecanum drive style drivetrain."""
|
|
|
|
kMaxSpeed = 3.0 # 3 meters per second
|
|
kMaxAngularSpeed = math.pi # 1/2 rotation per second
|
|
|
|
def __init__(self) -> None:
|
|
self.frontLeftMotor = wpilib.PWMSparkMax(1)
|
|
self.frontRightMotor = wpilib.PWMSparkMax(2)
|
|
self.backLeftMotor = wpilib.PWMSparkMax(3)
|
|
self.backRightMotor = wpilib.PWMSparkMax(4)
|
|
|
|
self.frontLeftEncoder = wpilib.Encoder(0, 1)
|
|
self.frontRightEncoder = wpilib.Encoder(2, 3)
|
|
self.backLeftEncoder = wpilib.Encoder(4, 5)
|
|
self.backRightEncoder = wpilib.Encoder(6, 7)
|
|
|
|
self.frontLeftLocation = wpimath.Translation2d(0.381, 0.381)
|
|
self.frontRightLocation = wpimath.Translation2d(0.381, -0.381)
|
|
self.backLeftLocation = wpimath.Translation2d(-0.381, 0.381)
|
|
self.backRightLocation = wpimath.Translation2d(-0.381, -0.381)
|
|
|
|
self.frontLeftPIDController = wpimath.PIDController(1, 0, 0)
|
|
self.frontRightPIDController = wpimath.PIDController(1, 0, 0)
|
|
self.backLeftPIDController = wpimath.PIDController(1, 0, 0)
|
|
self.backRightPIDController = wpimath.PIDController(1, 0, 0)
|
|
|
|
self.imu = wpilib.OnboardIMU(wpilib.OnboardIMU.MountOrientation.kFlat)
|
|
|
|
self.kinematics = wpimath.MecanumDriveKinematics(
|
|
self.frontLeftLocation,
|
|
self.frontRightLocation,
|
|
self.backLeftLocation,
|
|
self.backRightLocation,
|
|
)
|
|
|
|
# Here we use MecanumDrivePoseEstimator so that we can fuse odometry readings. The numbers
|
|
# used below are robot specific, and should be tuned.
|
|
self.poseEstimator = wpimath.MecanumDrivePoseEstimator(
|
|
self.kinematics,
|
|
self.imu.getRotation2d(),
|
|
self.getCurrentDistances(),
|
|
wpimath.Pose2d(),
|
|
(0.05, 0.05, wpimath.units.degreesToRadians(5)),
|
|
(0.5, 0.5, wpimath.units.degreesToRadians(30)),
|
|
)
|
|
|
|
# Gains are for example purposes only - must be determined for your own robot!
|
|
self.feedforward = wpimath.SimpleMotorFeedforwardMeters(1, 3)
|
|
|
|
self.imu.resetYaw()
|
|
|
|
# We need to invert one side of the drivetrain so that positive voltages
|
|
# result in both sides moving forward. Depending on how your robot's
|
|
# gearbox is constructed, you might have to invert the left side instead.
|
|
self.frontRightMotor.setInverted(True)
|
|
self.backRightMotor.setInverted(True)
|
|
|
|
def getCurrentState(self) -> wpimath.MecanumDriveWheelSpeeds:
|
|
"""Returns the current state of the drivetrain.
|
|
|
|
:returns: The current state of the drivetrain.
|
|
"""
|
|
return wpimath.MecanumDriveWheelSpeeds(
|
|
self.frontLeftEncoder.getRate(),
|
|
self.frontRightEncoder.getRate(),
|
|
self.backLeftEncoder.getRate(),
|
|
self.backRightEncoder.getRate(),
|
|
)
|
|
|
|
def getCurrentDistances(self) -> wpimath.MecanumDriveWheelPositions:
|
|
"""Returns the current distances measured by the drivetrain.
|
|
|
|
:returns: The current distances measured by the drivetrain.
|
|
"""
|
|
positions = wpimath.MecanumDriveWheelPositions()
|
|
positions.frontLeft = self.frontLeftEncoder.getDistance()
|
|
positions.frontRight = self.frontRightEncoder.getDistance()
|
|
positions.rearLeft = self.backLeftEncoder.getDistance()
|
|
positions.rearRight = self.backRightEncoder.getDistance()
|
|
return positions
|
|
|
|
def setSpeeds(self, speeds: wpimath.MecanumDriveWheelSpeeds) -> None:
|
|
"""Set the desired speeds for each wheel.
|
|
|
|
:param speeds: The desired wheel speeds.
|
|
"""
|
|
frontLeftFeedforward = self.feedforward.calculate(speeds.frontLeft)
|
|
frontRightFeedforward = self.feedforward.calculate(speeds.frontRight)
|
|
backLeftFeedforward = self.feedforward.calculate(speeds.rearLeft)
|
|
backRightFeedforward = self.feedforward.calculate(speeds.rearRight)
|
|
|
|
frontLeftOutput = self.frontLeftPIDController.calculate(
|
|
self.frontLeftEncoder.getRate(), speeds.frontLeft
|
|
)
|
|
frontRightOutput = self.frontRightPIDController.calculate(
|
|
self.frontRightEncoder.getRate(), speeds.frontRight
|
|
)
|
|
backLeftOutput = self.backLeftPIDController.calculate(
|
|
self.backLeftEncoder.getRate(), speeds.rearLeft
|
|
)
|
|
backRightOutput = self.backRightPIDController.calculate(
|
|
self.backRightEncoder.getRate(), speeds.rearRight
|
|
)
|
|
|
|
self.frontLeftMotor.setVoltage(frontLeftOutput + frontLeftFeedforward)
|
|
self.frontRightMotor.setVoltage(frontRightOutput + frontRightFeedforward)
|
|
self.backLeftMotor.setVoltage(backLeftOutput + backLeftFeedforward)
|
|
self.backRightMotor.setVoltage(backRightOutput + backRightFeedforward)
|
|
|
|
def drive(
|
|
self,
|
|
xSpeed: float,
|
|
ySpeed: float,
|
|
rot: float,
|
|
fieldRelative: bool,
|
|
period: float,
|
|
) -> None:
|
|
"""Method to drive the robot using joystick info.
|
|
|
|
:param xSpeed: Speed of the robot in the x direction (forward).
|
|
:param ySpeed: Speed of the robot in the y direction (sideways).
|
|
:param rot: Angular rate of the robot.
|
|
:param fieldRelative: Whether the provided x and y speeds are relative to the field.
|
|
"""
|
|
chassisSpeeds = wpimath.ChassisSpeeds(xSpeed, ySpeed, rot)
|
|
if fieldRelative:
|
|
chassisSpeeds = chassisSpeeds.toRobotRelative(
|
|
self.poseEstimator.getEstimatedPosition().rotation()
|
|
)
|
|
self.setSpeeds(
|
|
self.kinematics.toWheelSpeeds(chassisSpeeds.discretize(period)).desaturate(
|
|
self.kMaxSpeed
|
|
)
|
|
)
|
|
|
|
def updateOdometry(self) -> None:
|
|
"""Updates the field relative position of the robot."""
|
|
self.poseEstimator.update(self.imu.getRotation2d(), self.getCurrentDistances())
|
|
|
|
# Also apply vision measurements. We use 0.3 seconds in the past as an example -- on
|
|
# a real robot, this must be calculated based either on latency or timestamps.
|
|
self.poseEstimator.addVisionMeasurement(
|
|
ExampleGlobalMeasurementSensor.getEstimatedGlobalPose(
|
|
self.poseEstimator.getEstimatedPosition()
|
|
),
|
|
wpilib.Timer.getTimestamp() - 0.3,
|
|
)
|