added top limit switch back

This commit is contained in:
Adam Long 2016-10-02 00:27:55 +00:00
parent b1f2c54ad2
commit 40076e6d48
4 changed files with 34 additions and 10 deletions

View File

@ -12,14 +12,14 @@ public class Robot extends IterativeRobot {
public static OI oi;
Command autonomousCommand;
SendableChooser chooser;
CameraServer cameraServer;
// CameraServer cameraServer;
public void robotInit() {
CommandBase.init();
oi = new OI();
chooser = new SendableChooser();
cameraServer = CameraServer.getInstance();
cameraServer.setQuality(50);
cameraServer.startAutomaticCapture("cam0");
// cameraServer = CameraServer.getInstance();
// cameraServer.setQuality(50);
// cameraServer.startAutomaticCapture("cam0");
chooser.addDefault("Nothing", new RoutineNothing());
chooser.addObject("Time based low bar", new RoutineDriveTime());
chooser.addObject("Time based straight low bar", new RoutineDriveStraightTime());
@ -67,13 +67,13 @@ public class Robot extends IterativeRobot {
SmartDashboard.putNumber("ArmAngleRaw", CommandBase.mainArm.getRaw());
SmartDashboard.putNumber("ArmAngleDegrees", CommandBase.mainArm.getDegrees());
SmartDashboard.putNumber("tmpRotations", CommandBase.driveBase.getLeftRotations());
SmartDashboard.putNumber("centerX",CommandBase.visionHelper.getCenterX());
if (Robot.oi.getJoysticks()[1].getRawButton(3)) {
CommandBase.pneumatics.setArmStopState(true);
} else {
CommandBase.pneumatics.setArmStopState(false);
}
CommandBase.pneumatics.setCompressorEnabled(SmartDashboard.getBoolean("CompressorEnabled"));
System.out.println(CommandBase.mainArm.getDegrees());
}
public void testPeriodic() {
LiveWindow.run();

View File

@ -4,6 +4,7 @@ import org.usfirst.frc.team2059.robot.subsystems.EncoderBase;
import org.usfirst.frc.team2059.robot.subsystems.MainArm;
import org.usfirst.frc.team2059.robot.subsystems.Pneumatics;
import org.usfirst.frc.team2059.robot.subsystems.Shooter;
import org.usfirst.frc.team2059.robot.subsystems.VisionHelper;
import edu.wpi.first.wpilibj.command.Command;
public abstract class CommandBase extends Command {
public static EncoderBase encoderBase;
@ -11,12 +12,14 @@ public abstract class CommandBase extends Command {
public static MainArm mainArm;
public static Pneumatics pneumatics;
public static Shooter shooter;
public static VisionHelper visionHelper;
public static void init() {
encoderBase = new EncoderBase();
driveBase = new DriveBase();
mainArm = new MainArm();
pneumatics = new Pneumatics();
shooter = new Shooter();
visionHelper = new VisionHelper();
}
}
// vim: sw=2:ts=2:sts=2

View File

@ -25,6 +25,7 @@ public class MainArm extends PIDSubsystem {
public void moveArm(double speed) {
// Calibrate the arm, but don't do anything about it
calibrate();
System.out.println(getTopPressed());
armMotorLeft.set(-speed);
armMotorRight.set(speed);
}
@ -79,12 +80,11 @@ public class MainArm extends PIDSubsystem {
System.out.println("Calibrating bottom to: " + getRaw());
min = getRaw();
return true;
} else if (getTopPressed()) {
System.out.println("Calibrating top to: " + getRaw());
max = getRaw();
return true;
}
// } else if (getTopPressed()) {
// System.out.println("Calibrating top to: " + getRaw());
// max = getRaw();
// return true;
// }
return false;
}
}

View File

@ -0,0 +1,21 @@
package org.usfirst.frc.team2059.robot.subsystems;
import edu.wpi.first.wpilibj.command.PIDSubsystem;
import edu.wpi.first.wpilibj.CANTalon;
import edu.wpi.first.wpilibj.AnalogInput;
import edu.wpi.first.wpilibj.DigitalInput;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj.networktables.NetworkTable;
public class VisionHelper {
NetworkTable contoursTable;
public VisionHelper(){
contoursTable=NetworkTable.getTable("GRIP/contours");
}
public double getCenterX(){
try{
return contoursTable.getNumberArray("centerX",new double[0])[0];
}catch(Exception e){
return 0;
}
}
}