Skip to content

Commit

Permalink
Add 2018-compatible code, no issues except cv
Browse files Browse the repository at this point in the history
  • Loading branch information
blai00 committed Jan 22, 2018
1 parent 57abdca commit a95df43
Show file tree
Hide file tree
Showing 10 changed files with 66 additions and 50 deletions.
2 changes: 1 addition & 1 deletion src/edu/stuy/robot/commands/RotateDegreesGyroCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -22,7 +22,7 @@ public RotateDegreesGyroCommand(double angle) {
}

protected void setDesiredAngle() {
desiredAngle = notSet ? SmartDashboard.getNumber("gyro-rotate-degs") : _angle;
desiredAngle = notSet ? SmartDashboard.getNumber("gyro-rotate-degs", 0) : _angle;
}

protected void onEnd() {}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ public class DriveOverMoatCommand extends DriveForwardCommand {
private static final double SPEED = 0.9;

public DriveOverMoatCommand() {
super(SmartDashboard.getNumber("Moat"), MAX_TIME_IN_SECONDS, SPEED);
super(SmartDashboard.getNumber("Moat", 0), MAX_TIME_IN_SECONDS, SPEED);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ public class DriveOverRampartsCommand extends DriveForwardCommand {
private static final double SPEED = 1.0;

public DriveOverRampartsCommand() {
super(SmartDashboard.getNumber("Ramparts"), MAX_TIME_IN_SECONDS, SPEED);
super(SmartDashboard.getNumber("Ramparts", 0), MAX_TIME_IN_SECONDS, SPEED);
}

@Override
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -9,7 +9,7 @@ public class DriveOverRoughTerrainCommand extends DriveForwardCommand {
private static final double SPEED = 1.0;

public DriveOverRoughTerrainCommand() {
super(SmartDashboard.getNumber("Rough"), MAX_TIME_IN_SECONDS, SPEED);
super(SmartDashboard.getNumber("Rough", 0), MAX_TIME_IN_SECONDS, SPEED);
}

@Override
Expand Down
9 changes: 6 additions & 3 deletions src/edu/stuy/robot/subsystems/Acquirer.java
Original file line number Diff line number Diff line change
@@ -1,22 +1,25 @@
package edu.stuy.robot.subsystems;

import static edu.stuy.robot.RobotMap.ACQUIRER_MOTOR_CHANNEL;

import com.ctre.CANTalon;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

import edu.stuy.robot.commands.AcquirerStopCommand;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.command.Subsystem;

/**
*
*/
public class Acquirer extends Subsystem {

private CANTalon acquirerMotor;
private WPI_TalonSRX acquirerMotor;

// Put methods for controlling this subsystem
// here. Call these from Commands.

public Acquirer() {
acquirerMotor = new CANTalon(ACQUIRER_MOTOR_CHANNEL);
acquirerMotor = new WPI_TalonSRX(ACQUIRER_MOTOR_CHANNEL);
}

public void initDefaultCommand() {
Expand Down
53 changes: 28 additions & 25 deletions src/edu/stuy/robot/subsystems/Drivetrain.java
Original file line number Diff line number Diff line change
Expand Up @@ -12,16 +12,19 @@
import static edu.stuy.robot.RobotMap.RIGHT_ENCODER_CHANNEL_A;
import static edu.stuy.robot.RobotMap.RIGHT_ENCODER_CHANNEL_B;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

import edu.stuy.robot.commands.DrivetrainTankDriveCommand;
import edu.stuy.util.TankDriveOutput;
import edu.wpi.first.wpilibj.ADXRS450_Gyro;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.Encoder;
import edu.wpi.first.wpilibj.PIDController;
import edu.wpi.first.wpilibj.PIDSourceType;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.Solenoid;
import edu.wpi.first.wpilibj.SpeedControllerGroup;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

/**
Expand All @@ -30,16 +33,17 @@
public class Drivetrain extends Subsystem {
private Encoder rightEncoder;
private Encoder leftEncoder;
private CANTalon leftFrontMotor;
private CANTalon rightFrontMotor;
private CANTalon leftRearMotor;
private CANTalon rightRearMotor;
private RobotDrive robotDrive;
private WPI_TalonSRX leftFrontMotor;
private WPI_TalonSRX rightFrontMotor;
private WPI_TalonSRX leftRearMotor;
private WPI_TalonSRX rightRearMotor;
private DifferentialDrive differentialDrive;
private ADXRS450_Gyro gyro;
private TankDriveOutput out;
private Solenoid gearShift;
private double[] currents;

private SpeedControllerGroup leftSpeedController;
private SpeedControllerGroup rightSpeedController;
public final PIDController pid;

public boolean gearUp; // Stores the state of the gear shift
Expand All @@ -53,16 +57,15 @@ public class Drivetrain extends Subsystem {
public Drivetrain() {
gearShift = new Solenoid(GEAR_SHIFT_CHANNEL);
currents = new double[10];
leftFrontMotor = new CANTalon(FRONT_LEFT_MOTOR_CHANNEL);
rightFrontMotor = new CANTalon(FRONT_RIGHT_MOTOR_CHANNEL);
leftRearMotor = new CANTalon(REAR_LEFT_MOTOR_CHANNEL);
rightRearMotor = new CANTalon(REAR_RIGHT_MOTOR_CHANNEL);
leftFrontMotor = new WPI_TalonSRX(FRONT_LEFT_MOTOR_CHANNEL);
rightFrontMotor = new WPI_TalonSRX(FRONT_RIGHT_MOTOR_CHANNEL);
leftRearMotor = new WPI_TalonSRX(REAR_LEFT_MOTOR_CHANNEL);
rightRearMotor = new WPI_TalonSRX(REAR_RIGHT_MOTOR_CHANNEL);
leftFrontMotor.setInverted(true);
rightFrontMotor.setInverted(true);
leftRearMotor.setInverted(true);
rightRearMotor.setInverted(true);
robotDrive = new RobotDrive(leftFrontMotor, leftRearMotor,
rightFrontMotor, rightRearMotor);
differentialDrive = new DifferentialDrive(leftSpeedController, rightSpeedController);

rightEncoder = new Encoder(RIGHT_ENCODER_CHANNEL_A,
RIGHT_ENCODER_CHANNEL_B);
Expand All @@ -74,11 +77,11 @@ public Drivetrain() {
autoGearShiftingState = true;

// Setup PIDController for auto-rotation and aiming
out = new TankDriveOutput(robotDrive);
out = new TankDriveOutput(differentialDrive);
gyro = new ADXRS450_Gyro();
pid = new PIDController(SmartDashboard.getNumber("Gyro P"),
SmartDashboard.getNumber("Gyro I"),
SmartDashboard.getNumber("Gyro D"), gyro, out);
pid = new PIDController(SmartDashboard.getNumber("Gyro P", 0),
SmartDashboard.getNumber("Gyro I", 0),
SmartDashboard.getNumber("Gyro D", 0), gyro, out);
pid.setInputRange(0, 360);
pid.setContinuous(); // Tell `pid' that 0deg = 360deg
pid.setAbsoluteTolerance(MAX_DEGREES_OFF_AUTO_AIMING);
Expand All @@ -97,7 +100,7 @@ public void initDefaultCommand() {
}

public void tankDrive(double left, double right) {
robotDrive.tankDrive(left, right);
differentialDrive.tankDrive(left, right);
}

public double getGyroAngle() {
Expand Down Expand Up @@ -138,7 +141,7 @@ public void resetEncoders() {
}

public void stop() {
robotDrive.tankDrive(0.0, 0.0);
differentialDrive.tankDrive(0.0, 0.0);
}

/**
Expand All @@ -157,7 +160,7 @@ public void autoGearShift() {
sum += currents[i];
}
gearUp = sum / currents.length > SmartDashboard
.getNumber("Gear Shifting Threshold");
.getNumber("Gear Shifting Threshold", 0);
gearShift.set(gearUp);
gearCounter = 0;
} else {
Expand Down Expand Up @@ -199,10 +202,10 @@ public double getAverageCurrent() {
}

public void setDrivetrainBrakeMode(boolean on) {
leftFrontMotor.enableBrakeMode(on);
leftRearMotor.enableBrakeMode(on);
rightFrontMotor.enableBrakeMode(on);
rightRearMotor.enableBrakeMode(on);
leftFrontMotor.setNeutralMode(NeutralMode.Brake);
leftRearMotor.setNeutralMode(NeutralMode.Brake);
rightFrontMotor.setNeutralMode(NeutralMode.Brake);
rightRearMotor.setNeutralMode(NeutralMode.Brake);
}

public void resetGyro() {
Expand Down
15 changes: 9 additions & 6 deletions src/edu/stuy/robot/subsystems/DropDown.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,9 +3,12 @@
import static edu.stuy.robot.RobotMap.ACQUIRER_POTENTIOMETER_CHANNEL;
import static edu.stuy.robot.RobotMap.DROPDOWN_MOTOR_CHANNEL;
import static edu.stuy.robot.RobotMap.DROP_DOWN_DEADBAND;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

import edu.stuy.robot.commands.DropDownDefaultCommand;
import edu.wpi.first.wpilibj.AnalogPotentiometer;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.interfaces.Potentiometer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
Expand All @@ -15,15 +18,15 @@
*/
public class DropDown extends Subsystem {

private CANTalon dropDownMotor;
private WPI_TalonSRX dropDownMotor;
private Potentiometer potentiometer;
public double currentAngle;

// Put methods for controlling this subsystem
// here. Call these from Commands.

public DropDown() {
dropDownMotor = new CANTalon(DROPDOWN_MOTOR_CHANNEL);
dropDownMotor = new WPI_TalonSRX(DROPDOWN_MOTOR_CHANNEL);
dropDownMotor.setInverted(true);
potentiometer = new AnalogPotentiometer(ACQUIRER_POTENTIOMETER_CHANNEL, 300, 0);
currentAngle = getAngle();
Expand Down Expand Up @@ -54,8 +57,8 @@ public double getVoltage() {

public double getAngle() {
double x = getVoltage();
double initialVoltage = SmartDashboard.getNumber("Initial Voltage");
double finalVoltage = SmartDashboard.getNumber("Final Voltage");
double initialVoltage = SmartDashboard.getNumber("Initial Voltage", 0);
double finalVoltage = SmartDashboard.getNumber("Final Voltage", 0);
double conversionFactor = 90.0 / (finalVoltage - initialVoltage);
return (x - initialVoltage) * conversionFactor;
}
Expand All @@ -68,7 +71,7 @@ public void lowerAcquirerToDrivingPosition() {
}

public void setDropDownBreakMode(boolean breakMode) {
dropDownMotor.enableBrakeMode(breakMode);
dropDownMotor.setNeutralMode(NeutralMode.Brake);
}

/**
Expand Down
11 changes: 7 additions & 4 deletions src/edu/stuy/robot/subsystems/Hopper.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,10 +4,13 @@
import static edu.stuy.robot.RobotMap.HOPPER_SENSOR_CHANNEL;
import static edu.stuy.robot.RobotMap.HOPPER_SENSOR_THRESHOLD;

import com.ctre.CANTalon;
import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

import edu.stuy.robot.Robot;
import edu.stuy.robot.commands.HopperStopCommand;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.command.Subsystem;

/**
Expand All @@ -16,11 +19,11 @@
public class Hopper extends Subsystem {
// Put methods for controlling this subsystem
// here. Call these from Commands.
private CANTalon hopperMotor;
private WPI_TalonSRX hopperMotor;
private AnalogInput distanceSensor;

public Hopper() {
hopperMotor = new CANTalon(HOPPER_MOTOR_CHANNEL);
hopperMotor = new WPI_TalonSRX(HOPPER_MOTOR_CHANNEL);
hopperMotor.setInverted(true);
distanceSensor = new AnalogInput(HOPPER_SENSOR_CHANNEL);
}
Expand All @@ -43,7 +46,7 @@ public void stop() {
}

public void setHopperBrakeMode(boolean on) {
hopperMotor.enableBrakeMode(on);
hopperMotor.setNeutralMode(NeutralMode.Brake);
}

public double getDistance() {
Expand Down
13 changes: 8 additions & 5 deletions src/edu/stuy/robot/subsystems/Shooter.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,10 @@

import static edu.stuy.robot.RobotMap.SHOOTER_ENCODER_MAXSPEED;
import static edu.stuy.robot.RobotMap.SHOOTER_MOTOR_CHANNEL;
import edu.wpi.first.wpilibj.CANTalon;

import com.ctre.phoenix.motorcontrol.NeutralMode;
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;

import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.command.Subsystem;

Expand All @@ -15,12 +18,12 @@
*/
public class Shooter extends Subsystem {

private CANTalon shooterMotor;
private WPI_TalonSRX shooterMotor;

public double currentSpeed;

public Shooter() {
shooterMotor = new CANTalon(SHOOTER_MOTOR_CHANNEL);
shooterMotor = new WPI_TalonSRX(SHOOTER_MOTOR_CHANNEL);
currentSpeed = 1.0;
/*
* shooterMotor.setFeedbackDevice(FeedbackDevice.CtreMagEncoder_Relative
Expand Down Expand Up @@ -54,7 +57,7 @@ public void stop() {
* public void setSpeedHigh() { setRPM(SHOOTER_ENCODER_MAXSPEED - 400.0); }
*/
public double getCurrentMotorSpeedInRPM() {
return shooterMotor.getSpeed();
return shooterMotor.getSelectedSensorVelocity(0);
}

// Use the encoders to verify the speed
Expand Down Expand Up @@ -97,7 +100,7 @@ public void setSpeedReliablyVBus(double speed) {
}

public void setShooterBrakeMode(boolean on) {
shooterMotor.enableBrakeMode(on);
shooterMotor.setNeutralMode(NeutralMode.Brake);
}

public void initDefaultCommand() {
Expand Down
7 changes: 4 additions & 3 deletions src/edu/stuy/util/TankDriveOutput.java
Original file line number Diff line number Diff line change
@@ -1,15 +1,16 @@
package edu.stuy.util;

import static edu.stuy.robot.RobotMap.PID_MAX_ROBOT_SPEED;

import edu.wpi.first.wpilibj.PIDOutput;
import edu.wpi.first.wpilibj.RobotDrive;
import edu.wpi.first.wpilibj.drive.DifferentialDrive;

public class TankDriveOutput implements PIDOutput {

private RobotDrive pidDrive;
private DifferentialDrive pidDrive;
private double maxValue;

public TankDriveOutput(RobotDrive drive) {
public TankDriveOutput(DifferentialDrive drive) {
pidDrive = drive;
maxValue = PID_MAX_ROBOT_SPEED;
}
Expand Down

0 comments on commit a95df43

Please sign in to comment.