Skip to content
Merged
35 changes: 17 additions & 18 deletions ArmBot/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
# the WPILib BSD license file in the root directory of this project.
#

import wpilib
import wpilib.drive
from wpilib import PWMSparkMax, Encoder
from wpilib.drive import DifferentialDrive
import commands2

import constants
Expand All @@ -16,30 +16,29 @@ class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

# The motors on the left side of the drive
self.left_motors = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor1Port),
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor2Port),
)
# The motors on the left side of the drive.
self.left1 = PWMSparkMax(constants.DriveConstants.kLeftMotor1Port)
self.left2 = PWMSparkMax(constants.DriveConstants.kLeftMotor2Port)

# The motors on the right side of the drive
self.right_motors = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor1Port),
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor2Port),
)
# The motors on the right side of the drive.
self.right1 = PWMSparkMax(constants.DriveConstants.kRightMotor1Port)
self.right2 = PWMSparkMax(constants.DriveConstants.kRightMotor2Port)

self.left1.addFollower(self.left2)
self.right1.addFollower(self.right2)

# The robot's drive
self.drive = wpilib.drive.DifferentialDrive(self.left_motors, self.right_motors)
self.drive = DifferentialDrive(self.left1, self.right1)

# The left-side drive encoder
self.left_encoder = wpilib.Encoder(
self.left_encoder = Encoder(
constants.DriveConstants.kLeftEncoderPorts[0],
constants.DriveConstants.kLeftEncoderPorts[1],
constants.DriveConstants.kLeftEncoderReversed,
)

# The right-side drive encoder
self.right_encoder = wpilib.Encoder(
self.right_encoder = Encoder(
constants.DriveConstants.kRightEncoderPorts[0],
constants.DriveConstants.kRightEncoderPorts[1],
constants.DriveConstants.kRightEncoderReversed,
Expand All @@ -56,7 +55,7 @@ def __init__(self) -> None:
# 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.right_motors.setInverted(True)
self.right1.setInverted(True)

def arcadeDrive(self, fwd: float, rot: float) -> None:
"""Drives the robot using arcade controls.
Expand All @@ -80,14 +79,14 @@ def getAverageEncoderDistance(self) -> float:
self.left_encoder.getDistance() + self.right_encoder.getDistance()
) / 2.0

def getLeftEncoder(self) -> wpilib.Encoder:
def getLeftEncoder(self) -> Encoder:
"""Gets the left drive encoder.

:returns: the left drive encoder
"""
return self.left_encoder

def getRightEncoder(self) -> wpilib.Encoder:
def getRightEncoder(self) -> Encoder:
"""Gets the right drive encoder.

:returns: the right drive encoder
Expand Down
39 changes: 20 additions & 19 deletions ArmBotOffboard/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,42 +4,43 @@
# the WPILib BSD license file in the root directory of this project.
#

import typing

import commands2
import commands2.cmd
from wpilib import PWMSparkMax, Encoder
from wpilib.drive import DifferentialDrive

import constants
import wpilib
import wpilib.drive
import typing


class DriveSubsystem(commands2.Subsystem):
def __init__(self) -> None:
super().__init__()

# The motors on the left side of the drive.
self.left = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.kLeftMotor1Port),
wpilib.PWMSparkMax(constants.kLeftMotor2Port),
)
self.left1 = PWMSparkMax(constants.kLeftMotor1Port)
self.left2 = PWMSparkMax(constants.kLeftMotor2Port)

# The motors on the right side of the drive.
self.right = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.kRightMotor1Port),
wpilib.PWMSparkMax(constants.kRightMotor2Port),
)
self.right1 = PWMSparkMax(constants.kRightMotor1Port)
self.right2 = PWMSparkMax(constants.kRightMotor2Port)

self.left1.addFollower(self.left2)
self.right1.addFollower(self.right2)

# The robot's drive
self.drive = wpilib.drive.DifferentialDrive(self.left, self.right)
self.drive = DifferentialDrive(self.left1, self.right1)

# The left-side drive encoder
self.left_encoder = wpilib.Encoder(
self.left_encoder = Encoder(
constants.kLeftEncoderPorts[0],
constants.kLeftEncoderPorts[1],
constants.kLeftEncoderReversed,
)

# The right-side drive encoder
self.right_encoder = wpilib.Encoder(
self.right_encoder = Encoder(
constants.kRightEncoderPorts[0],
constants.kRightEncoderPorts[1],
constants.kRightEncoderReversed,
Expand All @@ -52,7 +53,7 @@ def __init__(self) -> None:
# 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.right.setInverted(True)
self.right1.setInverted(True)

def arcadeDriveCommand(
self, fwd: typing.Callable[[], float], rot: typing.Callable[[], float]
Expand All @@ -71,8 +72,8 @@ def arcadeDriveCommand(

def resetEncoders(self) -> None:
"""Resets the drive encoders to currently read a position of 0."""
self.left.reset()
self.right.reset()
self.left_encoder.reset()
self.right_encoder.reset()

def getAverageEncoderDistance(self) -> float:
"""Gets the average distance of the two encoders.
Expand All @@ -82,15 +83,15 @@ def getAverageEncoderDistance(self) -> float:
"""
return (self.left_encoder.getDistance() + self.right_encoder.getDistance()) / 2

def getLeftEncoder(self) -> wpilib.Encoder:
def getLeftEncoder(self) -> Encoder:
"""Gets the left drive encoder.

Returns:
The left drive encoder.
"""
return self.left_encoder

def getRightEncoder(self) -> wpilib.Encoder:
def getRightEncoder(self) -> Encoder:
"""Gets the right drive encoder.

Returns:
Expand Down
30 changes: 16 additions & 14 deletions DifferentialDriveBot/drivetrain.py
Original file line number Diff line number Diff line change
Expand Up @@ -23,17 +23,23 @@ class Drivetrain:
ENCODER_RESOLUTION = 4096 # counts per revolution

def __init__(self):
leftLeader = wpilib.PWMSparkMax(1)
leftFollower = wpilib.PWMSparkMax(2)
rightLeader = wpilib.PWMSparkMax(3)
rightFollower = wpilib.PWMSparkMax(4)
self.leftLeader = wpilib.PWMSparkMax(1)
self.leftFollower = wpilib.PWMSparkMax(2)
self.rightLeader = wpilib.PWMSparkMax(3)
self.rightFollower = wpilib.PWMSparkMax(4)

# Make sure both motors for each side are in the same group
self.leftLeader.addFollower(self.leftFollower)
self.rightLeader.addFollower(self.rightFollower)

# 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.rightLeader.setInverted(True)

self.leftEncoder = wpilib.Encoder(0, 1)
self.rightEncoder = wpilib.Encoder(2, 3)

self.leftGroup = wpilib.MotorControllerGroup(leftLeader, leftFollower)
self.rightGroup = wpilib.MotorControllerGroup(rightLeader, rightFollower)

self.gyro = wpilib.AnalogGyro(0)

self.leftPIDController = wpimath.controller.PIDController(1.0, 0.0, 0.0)
Expand All @@ -48,11 +54,6 @@ def __init__(self):

self.gyro.reset()

# 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.rightGroup.setInverted(True)

# Set the distance per pulse for the drive encoders. We can simply use the
# distance traveled for one rotation of the wheel divided by the encoder
# resolution.
Expand Down Expand Up @@ -84,8 +85,9 @@ def setSpeeds(self, speeds: wpimath.kinematics.DifferentialDriveWheelSpeeds):
self.rightEncoder.getRate(), speeds.right
)

self.leftGroup.setVoltage(leftOutput + leftFeedforward)
self.rightGroup.setVoltage(rightOutput + rightFeedforward)
# Controls the left and right sides of the robot using the calculated outputs
self.leftLeader.setVoltage(leftOutput + leftFeedforward)
self.rightLeader.setVoltage(rightOutput + rightFeedforward)

def drive(self, xSpeed, rot):
"""Drives the robot with the given linear velocity and angular velocity."""
Expand Down
31 changes: 15 additions & 16 deletions FrisbeeBot/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
# the WPILib BSD license file in the root directory of this project.
#

import wpilib
import wpilib.drive
from wpilib import PWMSparkMax, Encoder
from wpilib.drive import DifferentialDrive
import commands2

import constants
Expand All @@ -17,29 +17,28 @@ def __init__(self) -> None:
super().__init__()

# The motors on the left side of the drive.
self.leftMotors = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor1Port),
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor2Port),
)
self.left1 = PWMSparkMax(constants.DriveConstants.kLeftMotor1Port)
self.left2 = PWMSparkMax(constants.DriveConstants.kLeftMotor2Port)

# The motors on the right side of the drive.
self.rightMotors = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor1Port),
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor2Port),
)
self.right1 = PWMSparkMax(constants.DriveConstants.kRightMotor1Port)
self.right2 = PWMSparkMax(constants.DriveConstants.kRightMotor2Port)

self.left1.addFollower(self.left2)
self.right1.addFollower(self.right2)

# The robot's drive
self.drive = wpilib.drive.DifferentialDrive(self.leftMotors, self.rightMotors)
self.drive = DifferentialDrive(self.left1, self.right1)

# The left-side drive encoder
self.leftEncoder = wpilib.Encoder(
self.leftEncoder = Encoder(
constants.DriveConstants.kLeftEncoderPorts[0],
constants.DriveConstants.kLeftEncoderPorts[1],
constants.DriveConstants.kLeftEncoderReversed,
)

# The right-side drive encoder
self.rightEncoder = wpilib.Encoder(
self.rightEncoder = Encoder(
constants.DriveConstants.kRightEncoderPorts[0],
constants.DriveConstants.kRightEncoderPorts[1],
constants.DriveConstants.kRightEncoderReversed,
Expand All @@ -48,7 +47,7 @@ def __init__(self) -> None:
# 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.rightMotors.setInverted(True)
self.right1.setInverted(True)

# Sets the distance per pulse for the encoders
self.leftEncoder.setDistancePerPulse(
Expand Down Expand Up @@ -80,15 +79,15 @@ def getAverageEncoderDistance(self):
"""
return (self.leftEncoder.getDistance() + self.rightEncoder.getDistance()) / 2.0

def getLeftEncoder(self) -> wpilib.Encoder:
def getLeftEncoder(self) -> Encoder:
"""
Gets the left drive encoder.

:returns: the left drive encoder
"""
return self.leftEncoder

def getRightEncoder(self) -> wpilib.Encoder:
def getRightEncoder(self) -> Encoder:
"""
Gets the right drive encoder.

Expand Down
33 changes: 16 additions & 17 deletions GyroDriveCommands/subsystems/drivesubsystem.py
Original file line number Diff line number Diff line change
Expand Up @@ -4,8 +4,8 @@
# the WPILib BSD license file in the root directory of this project.
#

import wpilib
import wpilib.drive
from wpilib import PWMSparkMax, Encoder, ADXRS450_Gyro
from wpilib.drive import DifferentialDrive
import commands2
import math

Expand All @@ -18,29 +18,28 @@ def __init__(self) -> None:
super().__init__()

# The motors on the left side of the drive.
self.leftMotors = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor1Port),
wpilib.PWMSparkMax(constants.DriveConstants.kLeftMotor2Port),
)
self.left1 = PWMSparkMax(constants.DriveConstants.kLeftMotor1Port)
self.left2 = PWMSparkMax(constants.DriveConstants.kLeftMotor2Port)

# The motors on the right side of the drive.
self.rightMotors = wpilib.MotorControllerGroup(
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor1Port),
wpilib.PWMSparkMax(constants.DriveConstants.kRightMotor2Port),
)
self.right1 = PWMSparkMax(constants.DriveConstants.kRightMotor1Port)
self.right2 = PWMSparkMax(constants.DriveConstants.kRightMotor2Port)

self.left1.addFollower(self.left2)
self.right1.addFollower(self.right2)

# The robot's drive
self.drive = wpilib.drive.DifferentialDrive(self.leftMotors, self.rightMotors)
self.drive = DifferentialDrive(self.left1, self.right1)

# The left-side drive encoder
self.leftEncoder = wpilib.Encoder(
self.leftEncoder = Encoder(
constants.DriveConstants.kLeftEncoderPorts[0],
constants.DriveConstants.kLeftEncoderPorts[1],
constants.DriveConstants.kLeftEncoderReversed,
)

# The right-side drive encoder
self.rightEncoder = wpilib.Encoder(
self.rightEncoder = Encoder(
constants.DriveConstants.kRightEncoderPorts[0],
constants.DriveConstants.kRightEncoderPorts[1],
constants.DriveConstants.kRightEncoderReversed,
Expand All @@ -49,7 +48,7 @@ def __init__(self) -> None:
# 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.rightMotors.setInverted(True)
self.right1.setInverted(True)

# Sets the distance per pulse for the encoders
self.leftEncoder.setDistancePerPulse(
Expand All @@ -59,7 +58,7 @@ def __init__(self) -> None:
constants.DriveConstants.kEncoderDistancePerPulse
)

self.gyro = wpilib.ADXRS450_Gyro()
self.gyro = ADXRS450_Gyro()

def arcadeDrive(self, fwd: float, rot: float):
"""
Expand All @@ -83,15 +82,15 @@ def getAverageEncoderDistance(self):
"""
return (self.leftEncoder.getDistance() + self.rightEncoder.getDistance()) / 2.0

def getLeftEncoder(self) -> wpilib.Encoder:
def getLeftEncoder(self) -> Encoder:
"""
Gets the left drive encoder.

:returns: the left drive encoder
"""
return self.leftEncoder

def getRightEncoder(self) -> wpilib.Encoder:
def getRightEncoder(self) -> Encoder:
"""
Gets the right drive encoder.

Expand Down
Loading