diff options
author | kartofen <mladenovnasko0@gmail.com> | 2024-02-13 19:52:59 +0200 |
---|---|---|
committer | kartofen <mladenovnasko0@gmail.com> | 2024-02-13 19:52:59 +0200 |
commit | 22d859552d0728ad0c553382ddd3cbbd140423b1 (patch) | |
tree | 5d1e7161900f88420b7f48b7acc1442b9f799be5 /src/main/java/frc/robot/Constants.java | |
parent | 7b58370a6d4174f2e007264c58bebe7868e7fdc3 (diff) |
tested
Diffstat (limited to 'src/main/java/frc/robot/Constants.java')
-rw-r--r-- | src/main/java/frc/robot/Constants.java | 17 |
1 files changed, 9 insertions, 8 deletions
diff --git a/src/main/java/frc/robot/Constants.java b/src/main/java/frc/robot/Constants.java index 41c9689..6d471db 100644 --- a/src/main/java/frc/robot/Constants.java +++ b/src/main/java/frc/robot/Constants.java @@ -4,28 +4,29 @@ import com.revrobotics.CANSparkMax; import com.revrobotics.CANSparkLowLevel.MotorType; import edu.wpi.first.wpilibj.Encoder; +import edu.wpi.first.wpilibj.GenericHID; import edu.wpi.first.wpilibj.I2C; import edu.wpi.first.wpilibj.I2C.Port; import frc.robot.util.IMUGyro; public class Constants { - public static final int PortDriverController = 0; + public static final GenericHID controller = new GenericHID(1); - public static final double DriveMaxSpeed = 20; // m/s + public static final double DriveMaxSpeed = 5; // m/s public static final double DriveMaxAngular = Math.PI; // rad/s? - public static final double WheelRadius = 0; // in meters - public static final double TrackWidth = 0; // in meters + public static final double WheelRadius = 0.0254; // in meters + public static final double TrackWidth = 0.74; // in meters public static final double EncoderResolution = 4096; public static final IMUGyro gyro = new IMUGyro(new I2C(Port.kOnboard, 0x68)); - public static final CANSparkMax motorL_leader = new CANSparkMax(40, MotorType.kBrushed); - public static final CANSparkMax motorL_follower = new CANSparkMax(41, MotorType.kBrushed); - public static final CANSparkMax motorR_leader = new CANSparkMax(42, MotorType.kBrushed); - public static final CANSparkMax motorR_follower = new CANSparkMax(43, MotorType.kBrushed); + public static final CANSparkMax motorL_leader = new CANSparkMax(11, MotorType.kBrushed); + public static final CANSparkMax motorL_follower = new CANSparkMax(12, MotorType.kBrushed); + public static final CANSparkMax motorR_leader = new CANSparkMax(13, MotorType.kBrushed); + public static final CANSparkMax motorR_follower = new CANSparkMax(14, MotorType.kBrushed); public static final Encoder encoderL = new Encoder(0, 1); public static final Encoder encoderR = new Encoder(2, 3); |