Skip to content

Commit

Permalink
Fixed Drivetrain
Browse files Browse the repository at this point in the history
  • Loading branch information
Fruggg committed Mar 15, 2024
1 parent 0bb9870 commit b069f2f
Show file tree
Hide file tree
Showing 2 changed files with 11 additions and 8 deletions.
3 changes: 2 additions & 1 deletion src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,8 @@ public class Robot extends TimedRobot {
@Override
public void robotInit() {
m_robotContainer = new RobotContainer();
SignalLogger.setPath("/media/sda1/");
//DO NOT LEAVE THIS UNCOMMENTED DURING COMPETITION
// SignalLogger.setPath("/media/sda1/");
// SignalLogger.start();
CameraServer.startAutomaticCapture();
// Creates the CvSink and connects it to the UsbCamera
Expand Down
16 changes: 9 additions & 7 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -77,9 +77,9 @@ public class RobotContainer {
};

private final SwerveRequest.FieldCentric drive = new SwerveRequest.FieldCentric()
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // I want field-centric
// driving in open loop
.withDeadband(MaxSpeed * 0.1).withRotationalDeadband(MaxAngularRate * 0.1) // Add a 10% deadband
.withDriveRequestType(DriveRequestType.OpenLoopVoltage); // I want field-centric
// driving in open loop
private final SwerveRequest.SwerveDriveBrake brake = new SwerveRequest.SwerveDriveBrake();
private final SwerveRequest.PointWheelsAt point = new SwerveRequest.PointWheelsAt();
private final Telemetry logger = new Telemetry(MaxSpeed);
Expand Down Expand Up @@ -137,11 +137,13 @@ private void configureBindings() {
.withRotationalRate(-m_driverController.getRightX() * MaxAngularRate) // Drive counterclockwise with
// negative X (left)
;
drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
drivetrain.setDefaultCommand( // Drivetrain will execute this command periodically
// Drive forward with negative Y (forward)

drivetrain.applyRequest(() -> driveRequest));

drivetrain.applyRequest(() -> drive.withVelocityX(-m_driverController.getLeftY() * MaxSpeed)
.withVelocityY(-m_driverController.getLeftX() * MaxSpeed) // Drive left with negative X (left)
.withRotationalRate(-m_driverController.getRightX() * MaxAngularRate) // Drive counterclockwise with
// negative X (left)
));
// m_driverController.a().whileTrue(drivetrain.applyRequest(() -> brake));
/*
* m_driverController.b().whileTrue(drivetrain
Expand Down

0 comments on commit b069f2f

Please sign in to comment.