changed values to prepare for competition

This commit is contained in:
Adam Long 2016-09-24 12:11:16 +00:00
parent 6055b2a879
commit a396a7200b
11 changed files with 23 additions and 21 deletions

View File

@ -35,11 +35,14 @@ public class OI {
// Print log when button 1 pressed // Print log when button 1 pressed
//joystickButtons[0][0].whenPressed(new LogEncoder()); //joystickButtons[0][0].whenPressed(new LogEncoder());
joystickButtons[0][0].whileHeld(new SetShooterState(true)); joystickButtons[0][0].whileHeld(new SetShooterState(true));
joystickButtons[0][3].whileHeld(new SpinRollers(1)); joystickButtons[0][2].whileHeld(new SpinRollers(-0.5,false));
joystickButtons[0][3].whileHeld(new SpinRollers(1,false));
joystickButtons[0][6].whileHeld(new SpinRollers(1,true));
// joystickButtons[0][2].whileHeld(new PIDDrive(400)); // joystickButtons[0][2].whileHeld(new PIDDrive(400));
joystickButtons[1][0].whileHeld(new MoveArm(1)); joystickButtons[1][0].whileHeld(new MoveArm(1));
joystickButtons[1][1].whileHeld(new MoveArm(-1)); joystickButtons[1][1].whileHeld(new MoveArm(-1));
joystickButtons[1][2].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCollect)); //joystickButtons[1][2].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCollect));
joystickButtons[1][2].whileHeld(new ResetLower(-1));
joystickButtons[1][3].whileHeld(new SetArmPosition(RobotMap.mainArmPresetTraverse)); joystickButtons[1][3].whileHeld(new SetArmPosition(RobotMap.mainArmPresetTraverse));
joystickButtons[1][4].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCloseShot)); joystickButtons[1][4].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCloseShot));
joystickButtons[1][5].whileHeld(new SetArmPosition(RobotMap.mainArmPresetFarShot)); joystickButtons[1][5].whileHeld(new SetArmPosition(RobotMap.mainArmPresetFarShot));

View File

@ -2,6 +2,7 @@ package org.usfirst.frc.team2059.robot;
import org.usfirst.frc.team2059.robot.commands.CommandBase; import org.usfirst.frc.team2059.robot.commands.CommandBase;
import org.usfirst.frc.team2059.robot.commands.autonomous.*; import org.usfirst.frc.team2059.robot.commands.autonomous.*;
import edu.wpi.first.wpilibj.IterativeRobot; import edu.wpi.first.wpilibj.IterativeRobot;
import edu.wpi.first.wpilibj.CameraServer;
import edu.wpi.first.wpilibj.command.Command; import edu.wpi.first.wpilibj.command.Command;
import edu.wpi.first.wpilibj.command.Scheduler; import edu.wpi.first.wpilibj.command.Scheduler;
import edu.wpi.first.wpilibj.livewindow.LiveWindow; import edu.wpi.first.wpilibj.livewindow.LiveWindow;
@ -11,18 +12,22 @@ public class Robot extends IterativeRobot {
public static OI oi; public static OI oi;
Command autonomousCommand; Command autonomousCommand;
SendableChooser chooser; SendableChooser chooser;
CameraServer cameraServer;
public void robotInit() { public void robotInit() {
CommandBase.init(); CommandBase.init();
oi = new OI(); oi = new OI();
chooser = new SendableChooser(); chooser = new SendableChooser();
chooser.addDefault("Time based drive", new RoutineDriveTime()); cameraServer = CameraServer.getInstance();
cameraServer.setQuality(50);
cameraServer.startAutomaticCapture("cam0");
chooser.addDefault("Time based low bar", new RoutineDriveTime());
chooser.addObject("Time based defense", new RoutineDefenseTime()); chooser.addObject("Time based defense", new RoutineDefenseTime());
SmartDashboard.putData("Auto mode", chooser); SmartDashboard.putData("Auto mode", chooser);
SmartDashboard.putData("MainArm", CommandBase.mainArm.getPIDController()); SmartDashboard.putData("MainArm", CommandBase.mainArm.getPIDController());
SmartDashboard.putData("LeftEncoderController", CommandBase.driveBase.getLeftController()); SmartDashboard.putData("LeftEncoderController", CommandBase.driveBase.getLeftController());
SmartDashboard.putBoolean("CompressorEnabled", true); SmartDashboard.putBoolean("CompressorEnabled", true);
//Automatically determine if rolling in or rolling out //Automatically determine if rolling in or rolling out
SmartDashboard.putBoolean("SmartRollers", true); SmartDashboard.putBoolean("SmartRollers", false);
//Use the limit swithces on the shooter //Use the limit swithces on the shooter
SmartDashboard.putBoolean("UseLimitSwitches", true); SmartDashboard.putBoolean("UseLimitSwitches", true);
} }

View File

@ -28,7 +28,7 @@ public class RobotMap {
public static int armStopSolenoidTwo = 5; public static int armStopSolenoidTwo = 5;
//Misc //Misc
public static int mainArmPresetCollect = -5; public static int mainArmPresetCollect = -5;
public static int mainArmPresetTraverse = 11; public static int mainArmPresetTraverse = 10;
public static int mainArmPresetCloseShot = 90; public static int mainArmPresetCloseShot = 90;
public static int mainArmPresetFarShot = 70; public static int mainArmPresetFarShot = 70;
} }

View File

@ -11,7 +11,7 @@ public class AutoDriveTime extends CommandBase {
protected void initialize() { protected void initialize() {
} }
protected void execute() { protected void execute() {
driveBase.driveArcade(0, -power, 0, 0); driveBase.driveArcade(0, -power, 0, 1);
} }
protected void end() { protected void end() {
driveBase.stopDriving(); driveBase.stopDriving();

View File

@ -4,11 +4,8 @@ import edu.wpi.first.wpilibj.command.CommandGroup;
import org.usfirst.frc.team2059.robot.Robot; import org.usfirst.frc.team2059.robot.Robot;
public class RoutineDefenseTime extends CommandGroup { public class RoutineDefenseTime extends CommandGroup {
public RoutineDefenseTime() { public RoutineDefenseTime() {
addSequential(new AutoSetArmStopState(true));
addSequential(new AutoResetLower(-1));
addSequential(new AutoSetArmPosition(15));
addSequential(new AutoSetArmStopState(false)); addSequential(new AutoSetArmStopState(false));
addSequential(new AutoSetArmPosition(11)); addSequential(new AutoSetArmPosition(10));
// addSequential(new AutoDriveTime(2,.5)); addSequential(new AutoDriveTime(2, .5));
} }
} }

View File

@ -4,8 +4,8 @@ import edu.wpi.first.wpilibj.command.CommandGroup;
import org.usfirst.frc.team2059.robot.Robot; import org.usfirst.frc.team2059.robot.Robot;
public class RoutineDriveTime extends CommandGroup { public class RoutineDriveTime extends CommandGroup {
public RoutineDriveTime() { public RoutineDriveTime() {
addSequential(new AutoResetLower(-1));
addSequential(new AutoSetArmStopState(true)); addSequential(new AutoSetArmStopState(true));
addSequential(new AutoResetLower(-1));
addSequential(new AutoDriveTime(2, .5)); addSequential(new AutoDriveTime(2, .5));
} }
} }

View File

@ -17,7 +17,7 @@ public class Drive extends CommandBase {
double x = Robot.oi.getJoysticks()[0].getRawAxis(0); double x = Robot.oi.getJoysticks()[0].getRawAxis(0);
double y = Robot.oi.getJoysticks()[0].getRawAxis(1); double y = Robot.oi.getJoysticks()[0].getRawAxis(1);
double z = Robot.oi.getJoysticks()[0].getRawAxis(2); double z = Robot.oi.getJoysticks()[0].getRawAxis(2);
if (Robot.oi.getJoysticks()[0].getRawButton(2)) { if (Robot.oi.getJoysticks()[0].getRawButton(2) || Robot.oi.getJoysticks()[0].getRawButton(11)) {
sensitivity = 1; sensitivity = 1;
} else { } else {
sensitivity = 0.5; sensitivity = 0.5;

View File

@ -15,7 +15,6 @@ public class ResetLower extends CommandBase {
} }
// Called repeatedly when this Command is scheduled to run // Called repeatedly when this Command is scheduled to run
protected void execute() { protected void execute() {
System.out.println("test");
mainArm.disable(); mainArm.disable();
mainArm.resetLower(speed); mainArm.resetLower(speed);
} }

View File

@ -17,11 +17,6 @@ public class SetArmPosition extends CommandBase {
// Called repeatedly when this Command is scheduled to run // Called repeatedly when this Command is scheduled to run
protected void execute() { protected void execute() {
//Move the arm stop //Move the arm stop
if (pos == RobotMap.mainArmPresetCollect) {
pneumatics.setArmStopState(true);
} else if ((pos != RobotMap.mainArmPresetCollect) && (mainArm.getDegrees() > 2)) {
pneumatics.setArmStopState(false);
}
mainArm.enable(); mainArm.enable();
mainArm.setSetpoint(pos); mainArm.setSetpoint(pos);
} }

View File

@ -7,15 +7,17 @@ import org.usfirst.frc.team2059.robot.Robot;
*/ */
public class SpinRollers extends CommandBase { public class SpinRollers extends CommandBase {
double speed; double speed;
public SpinRollers(double s) { boolean smartrollers;
public SpinRollers(double s, boolean sr) {
speed = s; speed = s;
smartrollers = sr;
} }
// Called just before this Command runs the first time // Called just before this Command runs the first time
protected void initialize() { protected void initialize() {
} }
// Called repeatedly when this Command is scheduled to run // Called repeatedly when this Command is scheduled to run
protected void execute() { protected void execute() {
if (SmartDashboard.getBoolean("SmartRollers") && mainArm.getDegrees() < 5) { if (smartrollers && (mainArm.getDegrees() < 5 || mainArm.getBottomPressed())) {
shooter.shootAtSpeed(-.5); shooter.shootAtSpeed(-.5);
} else { } else {
shooter.shootAtSpeed(speed); shooter.shootAtSpeed(speed);

View File

@ -17,6 +17,7 @@ public class MainArm extends PIDSubsystem {
public MainArm() { public MainArm() {
super("MainArm", 0.3, 0.0, 0.4); super("MainArm", 0.3, 0.0, 0.4);
getPIDController().setContinuous(false); getPIDController().setContinuous(false);
setSetpoint(70);
enable(); enable();
} }
public void initDefaultCommand() { public void initDefaultCommand() {