Skip to content
Merged
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
6 changes: 6 additions & 0 deletions .wpilib/wpilib_preferences.json
Original file line number Diff line number Diff line change
@@ -0,0 +1,6 @@
{
"currentLanguage": "none",
"enableCppIntellisense": false,
"projectYear": "none",
"teamNumber": 199
}
6 changes: 3 additions & 3 deletions Robot2019/src/main/java/frc/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down
7 changes: 4 additions & 3 deletions Robot2019/src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);
}
Expand Down
13 changes: 5 additions & 8 deletions Robot2019/src/main/java/frc/robot/commands/TeleopDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -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);
Expand Down Expand Up @@ -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);
Expand Down
16 changes: 12 additions & 4 deletions Robot2019/src/main/java/frc/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -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;
Expand Down Expand Up @@ -51,6 +56,7 @@ public Drivetrain(WPI_TalonSRX leftMaster, WPI_VictorSPX leftSlave1, WPI_VictorS
rightEnc.setDistancePerPulse(pulseFraction * Math.PI * wheelDiameter);

this.gyro = gyro;

}

@Override
Expand All @@ -61,23 +67,25 @@ 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() {
leftMotor.stopMotor();
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();
Expand Down