Skip to content

Commit

Permalink
Merge pull request #8 from FRC6334/wip/oob1
Browse files Browse the repository at this point in the history
after first comp
  • Loading branch information
curtisf authored Mar 21, 2019
2 parents 2081103 + 184c898 commit 9f82c9a
Show file tree
Hide file tree
Showing 23 changed files with 886 additions and 111 deletions.
15 changes: 11 additions & 4 deletions src/main/java/frc/robot/OI.java
Original file line number Diff line number Diff line change
Expand Up @@ -11,6 +11,7 @@
import edu.wpi.first.wpilibj.buttons.Button;
import edu.wpi.first.wpilibj.buttons.JoystickButton;
import frc.robot.commands.*;
import frc.robot.commands.Hab3AutoClimb.AutoToHab3;

/**
* This class is the glue that binds the controls on the physical operator
Expand All @@ -28,13 +29,19 @@ public static void init() {

Button moveArmToPos = new JoystickButton(leftDriveStick, 9);
Button moveArmToHighestRocket = new JoystickButton(leftDriveStick, 8);
Button driveClimberForward = new JoystickButton(rightDriveStick, 4);
Button driveClimberBackwards = new JoystickButton(rightDriveStick, 5);
Button navXClimb = new JoystickButton(rightDriveStick, 3);
Button driveFrontClimber = new JoystickButton(rightDriveStick, 8);
Button driveBackClimber = new JoystickButton(rightDriveStick, 9);
Button autoLimelight = new JoystickButton(leftDriveStick, 4);
//Button autoNavxClimb = new JoystickButton(rightDriveStick, 2);

navXClimb.whileHeld(new AutoNavXBalanceClimb());
moveArmToHighestRocket.whileHeld(new MoveToHighRocket());
moveArmToPos.whileHeld(new MoveTo47());
driveClimberForward.whileHeld(new DriveClimberForward());
driveClimberBackwards.whileHeld(new DriveClimberBackwards());
driveFrontClimber.toggleWhenPressed(new DriveFrontClimberX());
driveBackClimber.toggleWhenPressed(new DriveBackClimberX());
autoLimelight.whileHeld(new AutoDriveToTarget());
//autoNavxClimb.toggleWhenPressed(new AutoToHab3());
}

public static Joystick getRightDriveStick() {
Expand Down
5 changes: 5 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -115,6 +115,11 @@ public void teleopInit() {
@Override
public void teleopPeriodic() {
Scheduler.getInstance().run();
SmartDashboard.putNumber("Motor #1 position", CommandBase.climber.getFrontClimbEncoder());
SmartDashboard.putNumber("Motor #1 velocity", CommandBase.climber.getFrontClimbVoltage());
SmartDashboard.putNumber("Motor #2 position", CommandBase.climber.getBackClimbEncoder());
SmartDashboard.putNumber("Motor #2 velocity", CommandBase.climber.getBackClimbVoltage());
SmartDashboard.putNumber("navx roll", CommandBase.climber.getRoll());
}

/**
Expand Down
7 changes: 5 additions & 2 deletions src/main/java/frc/robot/commands/ArcadeDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -21,21 +21,24 @@ public class ArcadeDrive extends CommandBase {

public ArcadeDrive() {
super("ArcadeDrive");
System.out.println("TankDrive command init");
System.out.println("arcade command init");
requires(driveTrain);
}

// Called just before this Command runs the first time
@Override
protected void initialize() {
System.out.println("TankDrive command init 2");
System.out.println("arcadedrive command init 2");
rightStick = OI.getRightDriveStick();
leftStick = OI.getLeftDriveStick();
}

// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
if (leftStick.getRawButtonPressed(1)) {
grabber.toggle();
}
double leftX = Math.abs(leftStick.getX()) < 0.05 ? 0 : leftStick.getX();
double leftY = Math.abs(leftStick.getY()) < 0.05 ? 0 : leftStick.getY(); // Handle deadband
double rightX = Math.abs(rightStick.getX()) < 0.05 ? 0 : rightStick.getX();
Expand Down
17 changes: 10 additions & 7 deletions src/main/java/frc/robot/commands/AutoDriveToTarget.java
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,6 @@ public AutoDriveToTarget() {
super("AutoDrive");
requires(driveTrain);
requires(vision);
requires(climber);

limelight = NetworkTableInstance.getDefault().getTable("limelight");
}
Expand All @@ -30,6 +29,7 @@ public AutoDriveToTarget() {
protected void initialize() {
System.out.println("Init");
xOffset = limelight.getEntry("tx").getDouble(0);
vision.setLedMode(3);
}

// Called repeatedly when this Command is scheduled to run
Expand All @@ -40,18 +40,18 @@ protected void execute() {

if (target == 0) {
System.out.println("No target. Spinning aimlessly until I find something.");
// climber.driveIndividual(0.3, -0.3);
driveTrain.tankDrive(0.15, -0.15);
} else if (target == 1) {
double throttle = 0.07 * limelight.getEntry("tx").getDouble(0);
if (Math.abs(throttle) > 0.5) {
if (Math.abs(throttle) > 0.25) {
int sign = 1;
if (throttle < 0) {
sign = -1;
}
throttle = sign * 0.5;
throttle = sign * 0.25;
}
System.out.println(throttle);
// climber.driveIndividual(-throttle, throttle);
driveTrain.tankDrive(-throttle, throttle);
}
}

Expand All @@ -64,13 +64,16 @@ public boolean isFinished() {
@Override
protected void end() {
System.out.println("end");
// climber.driveIndividual(0, 0);
driveTrain.tankDrive(0, 0);
vision.setLedMode(1);
}

// Called when another command which requires one or more of the same
// subs*ystems is scheduled to run
@Override
protected void interrupted() {
System.out.println("interrupt auto");
System.out.println("interrupt auto limelight target");
driveTrain.tankDrive(0, 0);
vision.setLedMode(1);
}
}
99 changes: 99 additions & 0 deletions src/main/java/frc/robot/commands/AutoNavXBalanceClimb.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,99 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/

package frc.robot.commands;

import edu.wpi.first.wpilibj.Joystick;
import frc.robot.OI;

public class AutoNavXBalanceClimb extends CommandBase {

Joystick rightStick;

public AutoNavXBalanceClimb() {
super("navxautobalance");
// Use requires() here to declare subsystem dependencies
requires(climber);
rightStick = OI.getRightDriveStick();
}

// Called just before this Command runs the first time
@Override
protected void initialize() {
System.out.println("auto balance navx started");
}

// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
balance();
}

public void balance() {
double roll = climber.getRoll();
if (Math.abs(roll) < 2)
roll = 0;
if (roll == 0) {
if (climber.getFrontClimbEncoder() > -65) {
climber.driveFrontClimber(-0.35);
} else climber.driveFrontClimber(0);
if (climber.getBackClimbEncoder() > -65) {
climber.driveBackClimber(-0.35);
} else climber.driveBackClimber(0);
}
;
if (roll > 0 && Math.ceil(climber.getFrontClimbEncoder()) >= -65) {
System.out.println("I'm leaning forwards... adjusting");
if (climber.getFrontClimbEncoder() > -65) {
climber.driveFrontClimber(-0.20);
climber.driveBackClimber(0);
} else {
climber.driveFrontClimber(0);
climber.driveBackClimber(0);
}
} else if (roll < 0) {
System.out.println("I'm leaning backwards... adjusting");
if (climber.getBackClimbEncoder() > -65) {
climber.driveBackClimber(-0.20);
climber.driveFrontClimber(0);
} else {
climber.driveBackClimber(0);
climber.driveFrontClimber(0);
}
}
if (rightStick.getRawButton(4)) {
climber.driveBothClimbAxleWheels(0.50);
}
if (rightStick.getRawButton(5)) {
climber.driveBothClimbAxleWheels(-0.50);
}
}

// Make this return true when this Command no longer needs to run execute()
@Override
public boolean isFinished() {
return Math.ceil(climber.getFrontClimbEncoder()) <= -65 && Math.ceil(climber.getBackClimbEncoder()) <= -65;
}

// Called once after isFinished returns true
@Override
protected void end() {
System.out.println("auto balance is done.");
climber.driveClimbBoth(0);
climber.driveBothClimbAxleWheels(0);
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
@Override
protected void interrupted() {
System.out.println("auto balance interrupt");
climber.driveClimbBoth(0);
climber.driveBackClimber(0);
climber.driveBothClimbAxleWheels(0);
}
}
37 changes: 28 additions & 9 deletions src/main/java/frc/robot/commands/ClimberDrive.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,29 +27,47 @@ public ClimberDrive() {
// Called just before this Command runs the first time
@Override
protected void initialize() {
System.out.println("climberdrive init");
}

// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
if (rightStick.getRawButtonPressed(6))
climber.toggleFront();
if (rightStick.getRawButtonPressed(7))
climber.toggleBack();
// if (rightStick.getRawButtonPressed(10)) climber.togglePiston(10);
if (rightStick.getRawButtonPressed(3))
climber.toggleAll();

if (auxJoystick.getRawButtonPressed(1)) {
grabber.toggle();
System.out.println("Toggle grabber");
}

if (Math.abs(auxJoystick.getY()) <= 0.05) // Arm is disabled, just drives the climb motors here
if (rightStick.getRawButton(4)) {
climber.driveBothClimbAxleWheels(0.50);
} else {
climber.driveBothClimbAxleWheels(0);
}

if (rightStick.getRawButtonPressed(7)) {
System.out.println("reset both climb encoders");
climber.resetBothClimbEncoders();
}

if (rightStick.getRawButtonPressed(6)) {
System.out.println("F: " + climber.getFrontSensorInches() + "\nB: " + climber.getBackSensorInches());
}

if (auxJoystick.getRawButtonPressed(10)) {
climber.resetArm();
}

if (Math.abs(auxJoystick.getY()) <= 0.05)
climber.driveArm(0);
else
climber.driveArm(auxJoystick.getY());

if (Math.abs(rightStick.getY()) <= 0.05) {
climber.driveClimbBoth(0);
} else {
climber.driveClimbBoth(rightStick.getY());
}

SmartDashboard.putNumber("Position", climber.getPosition());
SmartDashboard.putNumber("Velocity", climber.getVelocity());
}
Expand All @@ -69,5 +87,6 @@ protected void end() {
// subsystems is scheduled to run
@Override
protected void interrupted() {
System.out.println("climberdrive interrupt");
}
}
75 changes: 75 additions & 0 deletions src/main/java/frc/robot/commands/DriveBackClimberX.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,75 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2018 FIRST. All Rights Reserved. */
/* Open Source Software - may be modified and shared by FRC teams. The code */
/* must be accompanied by the FIRST BSD license file in the root directory of */
/* the project. */
/*----------------------------------------------------------------------------*/

package frc.robot.commands;

import edu.wpi.first.wpilibj.Joystick;
import frc.robot.OI;
import frc.robot.RobotMap.rightStick;

public class DriveBackClimberX extends CommandBase {

Joystick rightStick, arcadeStick;

public DriveBackClimberX() {
super("drivebackclimberx");
// Use requires() here to declare subsystem dependencies
requires(climber);
requires(driveTrain);
rightStick = OI.getRightDriveStick();
arcadeStick = OI.getLeftDriveStick();
}

// Called just before this Command runs the first time
@Override
protected void initialize() {
System.out.println("back climber drive init");
}

// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
if (rightStick.getRawButton(2)) {
if (climber.getBackClimbEncoder() < 0.5) {
climber.driveBackClimber(0.2);
}
} else {
climber.driveBackClimber(0);
}
if (rightStick.getRawButton(4)) {
climber.driveBothClimbAxleWheels(0.50);
} else {
climber.driveBothClimbAxleWheels(0);
}
if (Math.abs(arcadeStick.getY()) < 0.05) {
driveTrain.arcadeDrive(0, 0);
} else {
driveTrain.arcadeDrive(arcadeStick.getX(), arcadeStick.getY());
}
}

// Make this return true when this Command no longer needs to run execute()
@Override
public boolean isFinished() {
return false;
}

// Called once after isFinished returns true
@Override
protected void end() {
System.out.println("front climber done");
climber.driveBackClimber(0);
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
@Override
protected void interrupted() {
climber.driveBackClimber(0);
System.out.println("back climber drive interrupt");
}
}
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/commands/DriveClimberBackwards.java
Original file line number Diff line number Diff line change
Expand Up @@ -23,7 +23,7 @@ protected void initialize() {
// Called repeatedly when this Command is scheduled to run
@Override
protected void execute() {
climber.driveBack(-0.5);
climber.driveBothClimbAxleWheels(-0.25);
}

// Make this return true when this Command no longer needs to run execute()
Expand All @@ -36,14 +36,14 @@ public boolean isFinished() {
@Override
protected void end() {
System.out.println("done driving the climber backwards");
climber.driveBack(0);
climber.driveBothClimbAxleWheels(0);
}

// Called when another command which requires one or more of the same
// subsystems is scheduled to run
@Override
protected void interrupted() {
System.out.println("climber backwards drive interrupt");
climber.driveBack(0);
climber.driveBothClimbAxleWheels(0);
}
}
Loading

0 comments on commit 9f82c9a

Please sign in to comment.