Autoformatted
This commit is contained in:
parent
901aa58894
commit
3b1efebba8
@ -35,7 +35,6 @@ public class OI {
|
||||
joystickButtons[0][0].whileHeld(new SpinRollers(1));
|
||||
joystickButtons[0][1].whileHeld(new SetShooterState(true));
|
||||
// joystickButtons[0][2].whileHeld(new PIDDrive(400));
|
||||
|
||||
joystickButtons[1][0].whileHeld(new MoveArm(0.5));
|
||||
joystickButtons[1][1].whileHeld(new MoveArm(-0.5));
|
||||
joystickButtons[1][2].whileHeld(new SetArmPosition(RobotMap.mainArmPresetCollect));
|
||||
|
@ -15,11 +15,11 @@ public class Robot extends IterativeRobot {
|
||||
oi = new OI();
|
||||
chooser = new SendableChooser();
|
||||
SmartDashboard.putData("Auto mode", chooser);
|
||||
SmartDashboard.putData("MainArm",CommandBase.mainArm.getPIDController());
|
||||
SmartDashboard.putData("LeftEncoderController",CommandBase.driveBase.getLeftController());
|
||||
SmartDashboard.putBoolean("CompressorEnabled",true);
|
||||
SmartDashboard.putData("MainArm", CommandBase.mainArm.getPIDController());
|
||||
SmartDashboard.putData("LeftEncoderController", CommandBase.driveBase.getLeftController());
|
||||
SmartDashboard.putBoolean("CompressorEnabled", true);
|
||||
//Automatically determine if rolling in or rolling out
|
||||
SmartDashboard.putBoolean("SmartRollers",true);
|
||||
SmartDashboard.putBoolean("SmartRollers", true);
|
||||
}
|
||||
public void disabledInit() {
|
||||
}
|
||||
@ -44,9 +44,9 @@ public class Robot extends IterativeRobot {
|
||||
}
|
||||
public void teleopPeriodic() {
|
||||
Scheduler.getInstance().run();
|
||||
SmartDashboard.putNumber("ArmAngleRaw",CommandBase.mainArm.getRaw());
|
||||
SmartDashboard.putNumber("ArmAngleDegrees",CommandBase.mainArm.getDegrees());
|
||||
SmartDashboard.putNumber("tmpRotations",CommandBase.driveBase.getLeftRotations());
|
||||
SmartDashboard.putNumber("ArmAngleRaw", CommandBase.mainArm.getRaw());
|
||||
SmartDashboard.putNumber("ArmAngleDegrees", CommandBase.mainArm.getDegrees());
|
||||
SmartDashboard.putNumber("tmpRotations", CommandBase.driveBase.getLeftRotations());
|
||||
CommandBase.pneumatics.setCompressorEnabled(SmartDashboard.getBoolean("CompressorEnabled"));
|
||||
System.out.println(CommandBase.mainArm.getDegrees());
|
||||
}
|
||||
|
@ -8,7 +8,7 @@ public class MoveArm extends CommandBase {
|
||||
double speed;
|
||||
public MoveArm(double s) {
|
||||
requires(mainArm);
|
||||
speed=s;
|
||||
speed = s;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
|
@ -8,7 +8,7 @@ public class PIDDrive extends CommandBase {
|
||||
double count;
|
||||
public PIDDrive(double c) {
|
||||
requires(driveBase);
|
||||
count=c;
|
||||
count = c;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
|
@ -9,7 +9,7 @@ public class SetArmPosition extends CommandBase {
|
||||
double pos;
|
||||
public SetArmPosition(double p) {
|
||||
requires(mainArm);
|
||||
pos=p;
|
||||
pos = p;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
@ -17,9 +17,9 @@ public class SetArmPosition extends CommandBase {
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
protected void execute() {
|
||||
//Move the arm stop
|
||||
if(pos==RobotMap.mainArmPresetCollect){
|
||||
if (pos == RobotMap.mainArmPresetCollect) {
|
||||
pneumatics.setArmStopState(true);
|
||||
}else if((pos!=RobotMap.mainArmPresetCollect)&&(mainArm.getDegrees()>2)){
|
||||
} else if ((pos != RobotMap.mainArmPresetCollect) && (mainArm.getDegrees() > 2)) {
|
||||
pneumatics.setArmStopState(false);
|
||||
}
|
||||
mainArm.enable();
|
||||
|
@ -7,7 +7,7 @@ import org.usfirst.frc.team2059.robot.Robot;
|
||||
public class SetArmStopState extends CommandBase {
|
||||
boolean state;
|
||||
public SetArmStopState(boolean s) {
|
||||
state=s;
|
||||
state = s;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
|
@ -7,7 +7,7 @@ import org.usfirst.frc.team2059.robot.Robot;
|
||||
public class SetShooterState extends CommandBase {
|
||||
boolean state;
|
||||
public SetShooterState(boolean s) {
|
||||
state=s;
|
||||
state = s;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
|
@ -8,7 +8,7 @@ import org.usfirst.frc.team2059.robot.RobotMap;
|
||||
public class ShootAtSpeed extends CommandBase {
|
||||
double speed;
|
||||
public ShootAtSpeed(double s) {
|
||||
speed=s;
|
||||
speed = s;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
|
@ -8,16 +8,16 @@ import org.usfirst.frc.team2059.robot.Robot;
|
||||
public class SpinRollers extends CommandBase {
|
||||
double speed;
|
||||
public SpinRollers(double s) {
|
||||
speed=s;
|
||||
speed = s;
|
||||
}
|
||||
// Called just before this Command runs the first time
|
||||
protected void initialize() {
|
||||
}
|
||||
// Called repeatedly when this Command is scheduled to run
|
||||
protected void execute() {
|
||||
if(SmartDashboard.getBoolean("SmartRollers") && mainArm.getDegrees()<5){
|
||||
if (SmartDashboard.getBoolean("SmartRollers") && mainArm.getDegrees() < 5) {
|
||||
shooter.shootAtSpeed(-.5);
|
||||
}else{
|
||||
} else {
|
||||
shooter.shootAtSpeed(speed);
|
||||
}
|
||||
}
|
||||
|
@ -11,10 +11,8 @@ public class DriveBase extends Subsystem {
|
||||
CANTalon leftMotorTwo = new CANTalon(RobotMap.driveLeftMotorTwo);
|
||||
CANTalon rightMotorOne = new CANTalon(RobotMap.driveRightMotorOne);
|
||||
CANTalon rightMotorTwo = new CANTalon(RobotMap.driveRightMotorTwo);
|
||||
Encoder leftEncoder = new Encoder(RobotMap.driveLeftEncoderA,RobotMap.driveLeftEncoderB,false,Encoder.EncodingType.k2X);
|
||||
|
||||
PIDController leftEncoderController = new PIDController(0.02,0.002,0.017,leftEncoder,new MotorsPIDOutput());
|
||||
|
||||
Encoder leftEncoder = new Encoder(RobotMap.driveLeftEncoderA, RobotMap.driveLeftEncoderB, false, Encoder.EncodingType.k2X);
|
||||
PIDController leftEncoderController = new PIDController(0.02, 0.002, 0.017, leftEncoder, new MotorsPIDOutput());
|
||||
public void initDefaultCommand() {
|
||||
setDefaultCommand(new Drive());
|
||||
}
|
||||
@ -24,21 +22,20 @@ public class DriveBase extends Subsystem {
|
||||
rightMotorOne.set(y + (x + z));
|
||||
rightMotorTwo.set(y + (x + z));
|
||||
}
|
||||
public void pidDrive(double setpoint){
|
||||
public void pidDrive(double setpoint) {
|
||||
leftEncoder.reset();
|
||||
leftEncoderController.enable();
|
||||
leftEncoderController.setSetpoint(setpoint);
|
||||
}
|
||||
public PIDController getLeftController(){
|
||||
public PIDController getLeftController() {
|
||||
return leftEncoderController;
|
||||
}
|
||||
public double getLeftRotations(){
|
||||
public double getLeftRotations() {
|
||||
return leftEncoder.get();
|
||||
}
|
||||
|
||||
public class MotorsPIDOutput implements PIDOutput{
|
||||
public class MotorsPIDOutput implements PIDOutput {
|
||||
@Override
|
||||
public void pidWrite(double output){
|
||||
public void pidWrite(double output) {
|
||||
leftMotorOne.pidWrite(output);
|
||||
leftMotorTwo.pidWrite(output);
|
||||
rightMotorOne.pidWrite(-output);
|
||||
|
@ -8,36 +8,36 @@ public class MainArm extends PIDSubsystem {
|
||||
CANTalon armMotorLeft = new CANTalon(RobotMap.armLeftMotor);
|
||||
CANTalon armMotorRight = new CANTalon(RobotMap.armRightMotor);
|
||||
AnalogInput pot = new AnalogInput(RobotMap.armPot);
|
||||
public MainArm(){
|
||||
super("MainArm",0.06,0.0,0.002);
|
||||
public MainArm() {
|
||||
super("MainArm", 0.06, 0.0, 0.002);
|
||||
getPIDController().setContinuous(false);
|
||||
setSetpoint(RobotMap.mainArmPresetTraverse);
|
||||
enable();
|
||||
}
|
||||
public void initDefaultCommand() {
|
||||
}
|
||||
public void moveArm(double speed){
|
||||
public void moveArm(double speed) {
|
||||
armMotorLeft.set(-speed);
|
||||
armMotorRight.set(speed);
|
||||
}
|
||||
protected double returnPIDInput(){
|
||||
protected double returnPIDInput() {
|
||||
return getDegrees();
|
||||
}
|
||||
protected void usePIDOutput(double output){
|
||||
protected void usePIDOutput(double output) {
|
||||
armMotorLeft.set(-output);
|
||||
armMotorRight.set(output);
|
||||
}
|
||||
public double getRaw(){
|
||||
public double getRaw() {
|
||||
return pot.getAverageVoltage();
|
||||
}
|
||||
public double getDegrees(){
|
||||
public double getDegrees() {
|
||||
return potToDegrees(getRaw());
|
||||
}
|
||||
private double potToDegrees(double pot){
|
||||
private double potToDegrees(double pot) {
|
||||
double min = RobotMap.zeroDegrees;
|
||||
double max = RobotMap.ninetyDegrees;
|
||||
System.out.println((pot-min)/(Math.abs(min-max)/90));
|
||||
return (pot-min)/(Math.abs(min-max)/90);
|
||||
System.out.println((pot - min) / (Math.abs(min - max) / 90));
|
||||
return (pot - min) / (Math.abs(min - max) / 90);
|
||||
}
|
||||
}
|
||||
// vim: sw=2:ts=2:sts=2
|
||||
|
@ -11,32 +11,32 @@ public class Pneumatics extends Subsystem {
|
||||
boolean shooterState, armStopState;
|
||||
public void initDefaultCommand() {
|
||||
}
|
||||
public void setCompressorEnabled(boolean state){
|
||||
public void setCompressorEnabled(boolean state) {
|
||||
compressor.setClosedLoopControl(state);
|
||||
}
|
||||
public void setShooterState(boolean state){
|
||||
if(state){
|
||||
public void setShooterState(boolean state) {
|
||||
if (state) {
|
||||
shooterSolenoid.set(DoubleSolenoid.Value.kForward);
|
||||
}else{
|
||||
} else {
|
||||
shooterSolenoid.set(DoubleSolenoid.Value.kReverse);
|
||||
}
|
||||
shooterState=state;
|
||||
shooterState = state;
|
||||
}
|
||||
public void setArmStopState(boolean state){
|
||||
if(state){
|
||||
public void setArmStopState(boolean state) {
|
||||
if (state) {
|
||||
armStopSolenoid.set(DoubleSolenoid.Value.kForward);
|
||||
}else{
|
||||
} else {
|
||||
armStopSolenoid.set(DoubleSolenoid.Value.kReverse);
|
||||
}
|
||||
armStopState=state;
|
||||
armStopState = state;
|
||||
}
|
||||
public boolean getShooterState(){
|
||||
public boolean getShooterState() {
|
||||
return shooterState;
|
||||
}
|
||||
public boolean getArmStopState(){
|
||||
public boolean getArmStopState() {
|
||||
return armStopState;
|
||||
}
|
||||
public boolean getCompressorEnabled(){
|
||||
public boolean getCompressorEnabled() {
|
||||
return compressor.enabled();
|
||||
}
|
||||
}
|
||||
|
@ -7,7 +7,7 @@ public class Shooter extends Subsystem {
|
||||
CANTalon shooterMotorRight = new CANTalon(RobotMap.shooterRightMotor);
|
||||
public void initDefaultCommand() {
|
||||
}
|
||||
public void shootAtSpeed(double speed){
|
||||
public void shootAtSpeed(double speed) {
|
||||
shooterMotorRight.set(speed);
|
||||
shooterMotorLeft.set(speed);
|
||||
}
|
||||
|
Loading…
x
Reference in New Issue
Block a user