Skip to content

Commit

Permalink
Arizona North Day 3: Teleop and switch autonomous are fully functional
Browse files Browse the repository at this point in the history
Following our elimination from competitive play at the regional,
software was allowed some much needed one on one time with the
competition bot on a practice field. All of the Telop bugs have been
ironed out per our testing, and our switch autonomous is fully
functional. GnarlyController and MotionProfileCommand have been debugged
and tuned to very precisely follow a trajectory and scale autonomous is
almost ready for testing.
  • Loading branch information
AvidhBavkar committed Mar 12, 2018
1 parent bd6faf2 commit 639a4c3
Show file tree
Hide file tree
Showing 11 changed files with 440 additions and 353 deletions.
106 changes: 53 additions & 53 deletions src/com/team3925/utils/SendablePIDTuner.java → SendablePIDTuner.java
Original file line number Diff line number Diff line change
@@ -1,54 +1,54 @@
package com.team3925.utils;

import edu.wpi.first.wpilibj.Sendable;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class SendablePIDTuner implements Sendable {

String name = "PIDTuner";
String subsystem;
PIDTunable pid_values;

public SendablePIDTuner(Subsystem subsystem, PIDTunable pid_values) {
this.subsystem = subsystem.getName() + "Tuner";
this.pid_values = pid_values;
}

@Override
public String getName() {
return name;
}

@Override
public void setName(String name) {
this.name = name;

}

@Override
public String getSubsystem() {
return subsystem;
}

@Override
public void setSubsystem(String subsystem) {
this.subsystem = subsystem;
}

@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("PIDController");
builder.addDoubleProperty("p", pid_values::getkP, pid_values::setkP);
builder.addDoubleProperty("i", pid_values::getkI, pid_values::setkI);
builder.addDoubleProperty("d", pid_values::getkD, pid_values::setkD);
builder.addDoubleProperty("f", pid_values::getkF, pid_values::setkF);
}

public void updateDashboard() {
// TODO: should this be name or subsystem? The subsystem will allow us to
// differentiate it.
SmartDashboard.putData(subsystem, this);
}
package com.team3925.utils;

import edu.wpi.first.wpilibj.Sendable;
import edu.wpi.first.wpilibj.command.Subsystem;
import edu.wpi.first.wpilibj.smartdashboard.SendableBuilder;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;

public class SendablePIDTuner implements Sendable {

String name = "PIDTuner";
String subsystem;
PIDTunable pid_values;

public SendablePIDTuner(Subsystem subsystem, PIDTunable pid_values) {
this.subsystem = subsystem.getName() + "Tuner";
this.pid_values = pid_values;
}

@Override
public String getName() {
return name;
}

@Override
public void setName(String name) {
this.name = name;

}

@Override
public String getSubsystem() {
return subsystem;
}

@Override
public void setSubsystem(String subsystem) {
this.subsystem = subsystem;
}

@Override
public void initSendable(SendableBuilder builder) {
builder.setSmartDashboardType("PIDController");
builder.addDoubleProperty("p", pid_values::getkP, pid_values::setkP);
builder.addDoubleProperty("i", pid_values::getkI, pid_values::setkI);
builder.addDoubleProperty("d", pid_values::getkD, pid_values::setkD);
builder.addDoubleProperty("f", pid_values::getkF, pid_values::setkF);
}

public void updateDashboard() {
// TODO: should this be name or subsystem? The subsystem will allow us to
// differentiate it.
SmartDashboard.putData(subsystem, this);
}
}
41 changes: 19 additions & 22 deletions src/com/team3925/frc2018/Logger.java
Original file line number Diff line number Diff line change
@@ -1,22 +1,19 @@
package com.team3925.frc2018;

import com.team3925.frc2018.subsystems.Drivetrain;
import com.team3925.utils.SendablePIDTuner;

public class Logger {
SendablePIDTuner drivetrainTuner;

private static Logger instance;
public static Logger getInstance() {
if (instance == null)
instance = new Logger();
return instance;
}

private Logger() {
drivetrainTuner = new SendablePIDTuner(Drivetrain.getInstance(), Drivetrain.getInstance());
}
public void update() {
drivetrainTuner.updateDashboard();
}
}
package com.team3925.frc2018;

public class Logger {
// SendablePIDTuner drivetrainTuner;

private static Logger instance;
public static Logger getInstance() {
if (instance == null)
instance = new Logger();
return instance;
}

private Logger() {
// drivetrainTuner = new SendablePIDTuner(Drivetrain.getInstance(), Drivetrain.getInstance());
}
public void update() {
// drivetrainTuner.updateDashboard();
}
}
10 changes: 8 additions & 2 deletions src/com/team3925/frc2018/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -142,15 +142,21 @@ protected void end() {

@Override
protected boolean isFinished() {
return Intake.getInstance().isAtSetpoint();
if(Elevator.state == ElevatorState.BOTTOM) {
return Intake.getInstance().isAtSetpoint();
}else {
return true;
}
}
});
shootCube.whenInactive(new Command() {

@Override
protected void initialize() {
Intake.getInstance().setIntakeRollers(0);
Intake.getInstance().setAngle(85);
if (Elevator.state == ElevatorState.BOTTOM) {
Intake.getInstance().setAngle(85);
}
}
@Override
protected boolean isFinished() {
Expand Down
16 changes: 10 additions & 6 deletions src/com/team3925/frc2018/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,6 +8,7 @@
import com.team3925.frc2018.commands.autos.CenterSwitchAuto;
import com.team3925.frc2018.commands.autos.CenterSwitchAuto.AutoSide;
import com.team3925.frc2018.commands.autos.DriveForwardAuto;
import com.team3925.frc2018.commands.autos.LeftScaleAuto;
import com.team3925.frc2018.subsystems.Drivetrain;
import com.team3925.frc2018.subsystems.Elevator;
import com.team3925.frc2018.subsystems.Intake;
Expand All @@ -31,7 +32,7 @@ public class Robot extends IterativeRobot {
Command zeroIntake;
UsbCamera camera;
SendableChooser<String> autoSelector;
boolean isElevatorZeroed = false;
private static boolean isElevatorZeroed;

@Override
public void robotInit() {
Expand All @@ -45,40 +46,44 @@ public void robotInit() {
camera.setFPS(12);
autoSelector.addDefault("Drive Forward", "DriveForward");
autoSelector.addObject("CenterSwitch", "Center");
autoSelector.addObject("Left Scale", "LeftScale");
SmartDashboard.putData("Auto", autoSelector);
isElevatorZeroed = false;
}

@Override
public void autonomousInit() {
isElevatorZeroed = true;
Intake.getInstance().setIntakeRollers(0.25);
Elevator.getInstance().zero();
Intake.getInstance().zeroLift();
testAuto = new DriveForwardAuto();
System.out.println(DriverStation.getInstance().getGameSpecificMessage().charAt(0));
if (autoSelector.getSelected().equals("DriveForward")) {
testAuto = new DriveForwardAuto();
}else if(autoSelector.getSelected().equals("Center")){
if (DriverStation.getInstance().getGameSpecificMessage().charAt(0) == 'L') {
testAuto = new CenterSwitchAuto(AutoSide.LEFT);
System.out.println("RUNnningLEFt");
}else if(DriverStation.getInstance().getGameSpecificMessage().charAt(0) == 'R') {
testAuto = new CenterSwitchAuto(AutoSide.RIGHT);
}
}
testAuto = new LeftScaleAuto();
testAuto.start();
isElevatorZeroed = true;
}

@Override
public void autonomousPeriodic() {
}

public void teleopInit() {
if (!isElevatorZeroed) {
if (isElevatorZeroed == false) {
Elevator.getInstance().zero();
Intake.getInstance().zeroLift();
System.out.println("ZeroCalled");
}
drive.start();
Intake.getInstance().setIntakeRollers(0.3);
Intake.getInstance().setIntakeRollers(0.25);
// Elevator.getInstance().setPosition(ElevatorState.BOTTOM);
// Intake.getInstance().zeroLift();
}
Expand All @@ -98,6 +103,5 @@ public void robotPeriodic() {

@Override
public void disabledInit() {
isElevatorZeroed = false;
}
}
150 changes: 75 additions & 75 deletions src/com/team3925/frc2018/commands/DriveManual.java
Original file line number Diff line number Diff line change
@@ -1,75 +1,75 @@
package com.team3925.frc2018.commands;

import javax.print.attribute.standard.PrinterResolution;

import com.team3925.frc2018.subsystems.Drivetrain;
import com.team3925.frc2018.subsystems.Elevator;

import edu.wpi.first.wpilibj.command.Command;

public class DriveManual extends Command {

public interface DriveManualInput {
public abstract double getFwd();

public abstract double getLeft();
}

private final boolean doReverseWhenReversing;

private DriveManualInput input;
private double prelimLeft, prelimRight;
private double fwd, turn;
private double scale;
private static final double K_HEIGHT_SUBTRACTION = 0.9;

public DriveManual(DriveManualInput input) {
this.input = input;
doReverseWhenReversing = false;
requires(Drivetrain.getInstance());
}

@Override
protected void initialize() {
Drivetrain.getInstance().setRaw(0, 0);
}

@Override
protected void execute() {
fwd = input.getFwd();
turn = input.getLeft();
if (Math.abs(fwd) < 0.1)
fwd = 0;
if (doReverseWhenReversing && fwd != 0)
turn *= Math.signum(fwd);
prelimLeft = fwd + turn;
prelimRight = fwd - turn;
if (prelimLeft != 0 || prelimRight != 0) {
scale = Math.max(Math.abs(fwd), Math.abs(turn)) / Math.max(Math.abs(prelimLeft), Math.abs(prelimRight));
prelimLeft *= scale;
prelimRight *= scale;
}

Drivetrain.getInstance().setRaw(
prelimLeft * (1 - (Elevator.getInstance().getElevatorHeightPercentage() * K_HEIGHT_SUBTRACTION)),
prelimRight * (1 - (Elevator.getInstance().getElevatorHeightPercentage() * K_HEIGHT_SUBTRACTION))
);
}


@Override
protected boolean isFinished() {
return false;
}

@Override
protected void end() {
Drivetrain.getInstance().setRaw(0, 0);
}

@Override
protected void interrupted() {
Drivetrain.getInstance().setRaw(0, 0);
}

}
package com.team3925.frc2018.commands;

import javax.print.attribute.standard.PrinterResolution;

import com.team3925.frc2018.subsystems.Drivetrain;
import com.team3925.frc2018.subsystems.Elevator;

import edu.wpi.first.wpilibj.command.Command;

public class DriveManual extends Command {

public interface DriveManualInput {
public abstract double getFwd();

public abstract double getLeft();
}

private final boolean doReverseWhenReversing;

private DriveManualInput input;
private double prelimLeft, prelimRight;
private double fwd, turn;
private double scale;
private static final double K_HEIGHT_SUBTRACTION = 0.8;

public DriveManual(DriveManualInput input) {
this.input = input;
doReverseWhenReversing = false;
requires(Drivetrain.getInstance());
}

@Override
protected void initialize() {
Drivetrain.getInstance().setRaw(0, 0);
}

@Override
protected void execute() {
fwd = input.getFwd();
turn = input.getLeft();
if (Math.abs(fwd) < 0.1)
fwd = 0;
if (doReverseWhenReversing && fwd != 0)
turn *= Math.signum(fwd);
prelimLeft = fwd + turn;
prelimRight = fwd - turn;
if (prelimLeft != 0 || prelimRight != 0) {
scale = Math.max(Math.abs(fwd), Math.abs(turn)) / Math.max(Math.abs(prelimLeft), Math.abs(prelimRight));
prelimLeft *= scale;
prelimRight *= scale;
}

Drivetrain.getInstance().setRaw(
prelimLeft * (1 - (Elevator.getInstance().getElevatorHeightPercentage() * K_HEIGHT_SUBTRACTION)),
prelimRight * (1 - (Elevator.getInstance().getElevatorHeightPercentage() * K_HEIGHT_SUBTRACTION))
);
}


@Override
protected boolean isFinished() {
return false;
}

@Override
protected void end() {
Drivetrain.getInstance().setRaw(0, 0);
}

@Override
protected void interrupted() {
Drivetrain.getInstance().setRaw(0, 0);
}

}
Loading

0 comments on commit 639a4c3

Please sign in to comment.