From 92d35d19f865ebc61ebcfa6e23cd8a34373ea810 Mon Sep 17 00:00:00 2001 From: EdwardFaucher Date: Sat, 10 Dec 2022 14:53:29 -0500 Subject: [PATCH] hncfcb --- src/main/java/frc/robot/Constants.java | 4 ++-- src/main/java/frc/robot/RobotContainer.java | 2 +- src/main/java/frc/robot/subsystems/BasePilotable.java | 2 +- 3 files changed, 4 insertions(+), 4 deletions(-) diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 339de33..b451b19 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -17,8 +17,8 @@ package frc.robot; public final class Constants { public static final int MoteurAvantGauche = (3); public static final int MoteurAvantDroit = (4); - public static final int MoteurArriereGauche = (1); - public static final int MoteurArriereDroit = (2); + public static final int MoteurArriereGauche = (2); + public static final int MoteurArriereDroit = (1); public static final int PistonPousserR = 0; public static final int PistonPousserF = 1; diff --git a/src/main/java/frc/robot/RobotContainer.java b/src/main/java/frc/robot/RobotContainer.java index 307a8df..b442829 100644 --- a/src/main/java/frc/robot/RobotContainer.java +++ b/src/main/java/frc/robot/RobotContainer.java @@ -55,7 +55,7 @@ public class RobotContainer { basePilotable.setDefaultCommand( new RunCommand( - ()-> basePilotable.drive(manette.getLeftY(), manette.getLeftX(), manette.getLeftTriggerAxis()-manette.getRightTriggerAxis()), basePilotable) + ()-> basePilotable.drive(-manette.getLeftY(), manette.getLeftX(), -manette.getLeftTriggerAxis()+manette.getRightTriggerAxis()), basePilotable) ); } diff --git a/src/main/java/frc/robot/subsystems/BasePilotable.java b/src/main/java/frc/robot/subsystems/BasePilotable.java index 2994d77..2ff3688 100644 --- a/src/main/java/frc/robot/subsystems/BasePilotable.java +++ b/src/main/java/frc/robot/subsystems/BasePilotable.java @@ -31,7 +31,7 @@ public double getangle() { return gyroscope.getAngle(); } public void drive(double y, double x, double rot){ - mecanum.driveCartesian(y, rot, -x, 0); + mecanum.driveCartesian(y, x, rot, 0); } public void resetgyro(){ try { gyroscope.reset(); } catch( Exception e) {DriverStation.reportError("bye bye", true); }