Skip to content
Open
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
7 changes: 4 additions & 3 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,9 @@

import static edu.wpi.first.units.Units.MetersPerSecond;

import edu.wpi.first.util.sendable.Sendable;
import edu.wpi.first.util.sendable.SendableBuilder;
import edu.wpi.first.wpilibj.drive.RobotDriveBase;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.Subsystem;
Expand All @@ -29,12 +32,10 @@ public RobotContainer() {
setUpDriverButtonBindings();
setUpOperatorButtonBindings();
}



private void setUpDefaultCommands() {
drivetrain.setDefaultCommand(
drivetrain.tankDrive(() -> commandxboxcontroller.getRightY(), () -> commandxboxcontroller.getLeftY())
drivetrain.arcadeDrive(() -> commandxboxcontroller.getLeftY(), () -> commandxboxcontroller.getRightX())
);


Expand Down
14 changes: 12 additions & 2 deletions src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@

import edu.wpi.first.units.measure.Distance;
import edu.wpi.first.units.measure.LinearVelocity;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants.MotorIdConstants;
Expand All @@ -37,6 +38,8 @@ public class Drivetrain extends SubsystemBase {

private final double MAX_SPEED_METERS_PER_SECOND = 4.0;

private final DifferentialDrive drive;

public Drivetrain() {
SparkMaxConfig rightFrontConfig = new SparkMaxConfig();
SparkMaxConfig leftFrontConfig = new SparkMaxConfig();
Expand Down Expand Up @@ -102,6 +105,7 @@ public Drivetrain() {
motorRightClosedLoopController = rightFrontMotorController.getClosedLoopController();
motorLeftClosedLoopController = leftFrontMotorController.getClosedLoopController();

drive = new DifferentialDrive(leftFrontMotorController, rightFrontMotorController);
}

public void setRightSpeed(LinearVelocity speed) {
Expand All @@ -113,8 +117,14 @@ public void setLeftSpeed(LinearVelocity speed) {
}
public Command tankDrive(DoubleSupplier rightSpeed, DoubleSupplier leftSpeed) {
return this.run(()->{
setLeftSpeed((MetersPerSecond.of(leftSpeed.getAsDouble() * MAX_SPEED_METERS_PER_SECOND)));
setRightSpeed((MetersPerSecond.of(rightSpeed.getAsDouble() * MAX_SPEED_METERS_PER_SECOND)));
setLeftSpeed((MetersPerSecond.of(leftSpeed.getAsDouble() * MAX_SPEED_METERS_PER_SECOND)));
setRightSpeed((MetersPerSecond.of(rightSpeed.getAsDouble() * MAX_SPEED_METERS_PER_SECOND)));
} );
}

public Command arcadeDrive(DoubleSupplier xSpeed, DoubleSupplier zRotation) {
return this.run(()->{
drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble());
} );
}
}
Expand Down