diff --git a/.wpilib/wpilib_preferences.json b/.wpilib/wpilib_preferences.json new file mode 100644 index 0000000..f0ee648 --- /dev/null +++ b/.wpilib/wpilib_preferences.json @@ -0,0 +1,6 @@ +{ + "currentLanguage": "none", + "enableCppIntellisense": false, + "projectYear": "none", + "teamNumber": 199 +} \ No newline at end of file diff --git a/Robot2019/src/main/java/frc/robot/OI.java b/Robot2019/src/main/java/frc/robot/OI.java index f3b4c5b..913c1a5 100644 --- a/Robot2019/src/main/java/frc/robot/OI.java +++ b/Robot2019/src/main/java/frc/robot/OI.java @@ -43,12 +43,12 @@ public class OI { rightSlowBtn = new JoystickButton(rightJoy, 1); rightSlowBtn.whileHeld(new SlowDrive(SlowDrive.Side.RIGHT)); - toggleHatchBtn = new JoystickButton(manipulator, 0); // TODO: set ports to correct values + toggleHatchBtn = new JoystickButton(manipulator, 1); // TODO: set ports to correct values toggleHatchBtn.whenPressed(new ToggleHatch(hp)); - cargoIntakeBtn = new JoystickButton(manipulator, 1); // TODO: set ports to correct values + cargoIntakeBtn = new JoystickButton(manipulator, 2); // TODO: set ports to correct values cargoIntakeBtn.whenPressed(new IntakeCargo(cargo)); - cargoEjectBtn = new JoystickButton(manipulator, 2); // TODO: set ports to correct values + cargoEjectBtn = new JoystickButton(manipulator, 3); // TODO: set ports to correct values cargoEjectBtn.whenPressed(new EjectCargo(cargo)); toggleCameraBtn = new JoystickButton(leftJoy, 2); diff --git a/Robot2019/src/main/java/frc/robot/Robot.java b/Robot2019/src/main/java/frc/robot/Robot.java index 5250f18..e7c6f62 100644 --- a/Robot2019/src/main/java/frc/robot/Robot.java +++ b/Robot2019/src/main/java/frc/robot/Robot.java @@ -29,14 +29,15 @@ public class Robot extends TimedRobot { @Override public void robotInit() { - dt = new Drivetrain(RobotMap.leftMaster, RobotMap.leftSlave1, RobotMap.leftSlave2, RobotMap.rightMaster, - RobotMap.rightSlave1, RobotMap.rightSlave2, oi.leftJoy, oi.rightJoy, RobotMap.leftEnc, RobotMap.rightEnc, - RobotMap.gyro); hp = new HatchPanel(RobotMap.hatchPistons); cargo = new Cargo(RobotMap.cargoRoller, RobotMap.pdp); oi = new OI(cargo, hp, RobotMap.driveCamera, RobotMap.hatchCamera, RobotMap.cameraServer); + dt = new Drivetrain(RobotMap.leftMaster, RobotMap.leftSlave1, RobotMap.leftSlave2, RobotMap.rightMaster, + RobotMap.rightSlave1, RobotMap.rightSlave2, oi.leftJoy, oi.rightJoy, RobotMap.leftEnc, RobotMap.rightEnc, + RobotMap.gyro); + chooser.setDefaultOption("Default Auto", new TeleopDrive(dt)); SmartDashboard.putData("Auto Mode", chooser); } diff --git a/Robot2019/src/main/java/frc/robot/commands/TeleopDrive.java b/Robot2019/src/main/java/frc/robot/commands/TeleopDrive.java index 5f80349..f342795 100644 --- a/Robot2019/src/main/java/frc/robot/commands/TeleopDrive.java +++ b/Robot2019/src/main/java/frc/robot/commands/TeleopDrive.java @@ -35,9 +35,11 @@ protected void execute() { } private void arcadeDrive() { - double speed = dt.leftJoy.getY(); + double speed = -dt.leftJoy.getY(); double rot = dt.rightJoy.getX(); + //System.out.println("Speed: " + speed + ", Rotation: " + rot); + if (SmartDashboard.getBoolean("Square Joysticks", true)) { speed = Math.copySign(speed * speed, speed); rot = Math.copySign(rot * rot, rot); @@ -74,17 +76,12 @@ private void arcadeDrive() { } } - if (SmartDashboard.getBoolean("Square Joysticks", true)) { - left = Math.signum(left * left); - right = Math.signum(right * right); - } - dt.drive(left, right); } private void tankDrive() { - double left = dt.leftJoy.getY(); - double right = dt.rightJoy.getY(); + double left = -dt.leftJoy.getY(); + double right = -dt.rightJoy.getY(); if (SmartDashboard.getBoolean("Square Joysticks", true)) { left = Math.copySign(left * left, left); diff --git a/Robot2019/src/main/java/frc/robot/subsystems/Drivetrain.java b/Robot2019/src/main/java/frc/robot/subsystems/Drivetrain.java index 8b796aa..6464445 100644 --- a/Robot2019/src/main/java/frc/robot/subsystems/Drivetrain.java +++ b/Robot2019/src/main/java/frc/robot/subsystems/Drivetrain.java @@ -15,9 +15,14 @@ import edu.wpi.first.wpilibj.Joystick; import edu.wpi.first.wpilibj.SpeedController; import edu.wpi.first.wpilibj.command.Subsystem; +import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard; import frc.robot.commands.TeleopDrive; public class Drivetrain extends Subsystem { + public enum Side { + LEFT, RIGHT + } + private SpeedController leftMotor, rightMotor; private Encoder leftEnc, rightEnc; public Joystick leftJoy, rightJoy; @@ -51,6 +56,7 @@ public Drivetrain(WPI_TalonSRX leftMaster, WPI_VictorSPX leftSlave1, WPI_VictorS rightEnc.setDistancePerPulse(pulseFraction * Math.PI * wheelDiameter); this.gyro = gyro; + } @Override @@ -61,6 +67,8 @@ public void initDefaultCommand() { public void drive(double left, double right) { leftMotor.set(left); rightMotor.set(right); + SmartDashboard.putNumber("Encoder Distance Left:", leftEnc.getDistance()); + SmartDashboard.putNumber("Encoder Distance Right:", rightEnc.getDistance()); } public void stop() { @@ -68,16 +76,16 @@ public void stop() { rightMotor.stopMotor(); } - public double getEncDist(String type) { - if (type.equals("left")) { + public double getEncDist(Side type) { + if (type == Side.LEFT) { return leftEnc.getDistance(); } else { return rightEnc.getDistance(); } } - public double getEncRate(String type) { - if (type.equals("left")) { + public double getEncRate(Side type) { + if (type == Side.LEFT) { return leftEnc.getRate(); } else { return rightEnc.getRate();