Skip to content

Commit

Permalink
Merge pull request #2 from FIRST-Team-2557-The-SOTABots/dev
Browse files Browse the repository at this point in the history
Final 2020 Code
  • Loading branch information
charlesdnguyen03 authored Feb 25, 2021
2 parents 4a0ce9d + 55266d2 commit aa525d6
Show file tree
Hide file tree
Showing 34 changed files with 957 additions and 392 deletions.
41 changes: 21 additions & 20 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -3,40 +3,41 @@
import edu.wpi.first.wpilibj.kinematics.DifferentialDriveKinematics;
import edu.wpi.first.wpilibj.trajectory.TrapezoidProfile;

/**
* The Constants class provides a convenient place for teams to hold robot-wide numerical or boolean
* constants. This class should not be used for any other purpose. All constants should be
* declared globally (i.e. public static). Do not put anything functional in this class.
*
* <p>It is advised to statically import this class (or one of its inner classes) wherever the
* constants are needed, to reduce verbosity.
*/
public final class Constants {
public static final double hoodFromTrench = 600;
public static final double hoodTriangle = 800;
public static final double hoodAutoLine = 767;
public static final double turretFromTrench = 6;
public static final double turretClose = 0;
public static final double ticksPerRevolutionLow = 19;
public static final double hoodFromTrench = 930;
public static final double hoodTriangle = 550;
public static final double hoodAutoLine = 1075;
public static final double turretFromTrench = -6;
public static final double turretLine = -7;
public static final double turretTriangle = 0;
public static final double ticksPerRevolutionLow = 18.6;
public static final double ticksPerRevolutionHigh = 6.4;
public static final double ratioGearLow = 18.86;
public static final double ratioGearHigh = 6.45;
public static final double wheelCircumferenceMeters = 6*Math.PI*0.0254;
//HoodTriangle: 590
//HoodLine: 1117
//HoodTrench:

//is that guys name Howard??
// idk
//Seth's granpa


public static final class DriveConstants {
// public static boolean reverse = true;
public static boolean reverse = false;

public static final double kTrackWidth = 0.584;
// public static final double kTrackWidth = 0.5;
public static final double kTrackWidth = 0.584/1.5;
// public static final double kTrackWidth = 0.0000001;
public static final DifferentialDriveKinematics kDriveKinematics = new DifferentialDriveKinematics(kTrackWidth);

public static final double ksVoltsLow = 0.147;
public static final double ksVoltsLow = 0.174;
// public static final double kvVoltSecondsPerMeterLow = 1.88; //estimate
public static final double kvVoltSecondsPerMeterLow = 4.47; //characterize
public static final double kaVoltSecondsSquaredPerMeterLow = 0.552; //0.1225
public static final double kvVoltSecondsPerMeterLow = 4.74; //characterize
public static final double kaVoltSecondsSquaredPerMeterLow = 0.6;

public static final double kPDriveVelLow = 16.3;
public static final double kPDriveVelLow = 3;

public static final double ksVoltsHigh = 0.122;
public static final double kvVoltSecondsPerMeterHigh = 0.64; //estimate
Expand Down
196 changes: 94 additions & 102 deletions src/main/java/frc/robot/Robot.java

Large diffs are not rendered by default.

18 changes: 12 additions & 6 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -15,12 +15,14 @@
import frc.robot.commands.FlywheelCommand;
import frc.robot.commands.HoodCommand;
import frc.robot.commands.IntakeCommand;
import frc.robot.commands.PIDTurret;
import frc.robot.commands.PositionControlCommand;
import frc.robot.commands.RotationControlCommand;
import frc.robot.commands.TurretCommand;
import frc.robot.commands.climb.ClimbCommand;
import frc.robot.commands.climb.ClimbSequence1;
import frc.robot.commands.climb.ClimbSequence2;
import frc.robot.commands.climb.ClimbSequence3;
import frc.robot.commands.climb.LockClimb;
import frc.robot.commands.climb.UnlockClimb;
import frc.robot.subsystems.CPMSub;
import frc.robot.subsystems.ClimbSub;
import frc.robot.subsystems.DriveSub;
Expand All @@ -30,7 +32,6 @@
import frc.robot.subsystems.LidarSub;
import frc.robot.subsystems.TurretSub;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.JoystickButton;

public class RobotContainer {
Expand All @@ -52,7 +53,7 @@ public class RobotContainer {
public static WPI_TalonSRX intake3 = new WPI_TalonSRX(6);

public static WPI_TalonSRX winch1 = new WPI_TalonSRX(7);
public static WPI_TalonSRX lift = new WPI_TalonSRX(8);
// public static WPI_TalonSRX lift = new WPI_TalonSRX(8);
public static WPI_TalonSRX winch2 = new WPI_TalonSRX(9);
//lift to -14000 for 12in\]]

Expand All @@ -64,7 +65,7 @@ public class RobotContainer {
// winchShift:kReverse=pull,kForward=freespin
// intakePistons:kReverse=in,kForward=out
// dSl:kReverse=low,kForward=high
public static Compressor compressor = new Compressor(0);
public static Compressor compressor = new Compressor(1);
public static DoubleSolenoid dsL = new DoubleSolenoid(0, 0, 1);
public static DoubleSolenoid intakePistons = new DoubleSolenoid(0, 2, 3);
public static DoubleSolenoid winchShift = new DoubleSolenoid(0, 4, 5);
Expand Down Expand Up @@ -133,23 +134,28 @@ public RobotContainer() {
hoodSub.setDefaultCommand(new HoodCommand());
flywheelSub.setDefaultCommand(new FlywheelCommand());
climbSub.setDefaultCommand(new ClimbCommand());
turretSub.setDefaultCommand(new TurretCommand());

configureButtonBindings();

//lift.setDefaultCommand(new RunCommand( () -> lift.lift(manipulator.getRawAxis(5)) , lift));

// flywheelSub.setDefaultCommand(new RunCommand( () -> flywheelSub.spinFlywheel(driver.getRawAxis(1)), flywheelSub));
// hoodSub.setDefaultCommand(new RunCommand( () -> hoodSub.angleHood(driver.getRawAxis(5)), hoodSub));
// turretSub.setDefaultCommand(new RunCommand( () -> turretSub.rotate(driver.getRawAxis(0)), flywheelSub));

}

private void configureButtonBindings() {

// ma.whileHeld(new PIDTurret());

my.whileHeld(new PositionControlCommand());
mx.whileHeld(new RotationControlCommand());

da.whileHeld(new ClimbSequence1());
db.whileHeld(new ClimbSequence2());
db.whenReleased(new LockClimb());
dstart.whileHeld(new ClimbSequence3());

}

Expand Down
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/commands/AimCommand.java
Original file line number Diff line number Diff line change
Expand Up @@ -14,11 +14,11 @@ public AimCommand(double hoodPos) {
new ParallelCommandGroup(
new PIDTurret(),
new PIDHood(hoodPos),
new PIDFlywheel(16000)
new PIDFlywheel(16500)
),
new ParallelCommandGroup(
new RunCommand( () -> RobotContainer.intakeSub.runConveyorBelt(IntakeSub.conveyorMotorSpeed), RobotContainer.intakeSub),
new RunCommand( () -> RobotContainer.intakeSub.runStarWheelAndCPM(IntakeSub.starWheelAndCPMSpeed), RobotContainer.intakeSub),
new RunCommand( () -> RobotContainer.intakeSub.runTurretFeeder(IntakeSub.conveyorMotorSpeed), RobotContainer.intakeSub),
new RunCommand( () -> RobotContainer.intakeSub.runConveyorAndCPM(IntakeSub.starWheelAndCPMSpeed), RobotContainer.intakeSub),
new PIDFlywheel()
)

Expand Down
53 changes: 53 additions & 0 deletions src/main/java/frc/robot/commands/AutoIntakeIntake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,53 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 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.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.RobotContainer;
import frc.robot.subsystems.IntakeSub;

public class AutoIntakeIntake extends CommandBase {

public AutoIntakeIntake() {
addRequirements(RobotContainer.intakeSub);
// Use addRequirements() here to declare subsystem dependencies.
}

// Called when the command is initially scheduled.
@Override
public void initialize() {
System.out.println("Intake intake Command init");
SmartDashboard.putBoolean("Exist", true);
SmartDashboard.putBoolean("Not Exist", false);
SmartDashboard.putBoolean("Exist Execute", false);
}

// Called every time the scheduler runs while the command is scheduled.
@Override
public void execute() {
SmartDashboard.putBoolean("Exist Execute", true);
System.out.println("Intake intake Command exe");
RobotContainer.intakeSub.intakeOut();
RobotContainer.intakeSub.runIntake(IntakeSub.intakeSpeed);
}

// Called once the command ends or is interrupted.
@Override
public void end(boolean interrupted) {
RobotContainer.intakeSub.runIntake(0);
SmartDashboard.putBoolean("Not Exist", true);
}

// Returns true when the command should end.
@Override
public boolean isFinished() {
return false;
}
}
93 changes: 93 additions & 0 deletions src/main/java/frc/robot/commands/AutoShootIntake.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,93 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj.DriverStation;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.CommandBase;
import edu.wpi.first.wpilibj2.command.RunCommand;
import frc.robot.RobotContainer;
import frc.robot.subsystems.FlywheelSub;
import frc.robot.subsystems.IntakeSub;

public class AutoShootIntake extends CommandBase {

boolean runConveyor = false;
boolean finalBall = false;
int numBall = 0;
boolean shoot;
boolean intaking;
boolean startTimer = false;
double tim = 0;
Timer t = new Timer();
public static boolean finished = false;

public AutoShootIntake(boolean intaking) {
addRequirements(RobotContainer.intakeSub, RobotContainer.flywheelSub);
this.intaking = intaking;
}

@Override
public void initialize() {
t.reset();
shoot = false;
countBalls = 0;
finished = false;
RobotContainer.intakeSub.intakeIn();
}

@Override
public void execute() {
System.out.println("Intaking: " + intaking);
if(!intaking){
RobotContainer.flywheelSub.spinFlywheels(1);
if(RobotContainer.flywheelSub.getFlywheelSpeed() > 16000) {//16000
shoot = true;
if(!startTimer){
t.start();
startTimer = true;
tim = DriverStation.getInstance().getMatchTime();
}
}

if(shoot){
RobotContainer.intakeSub.runConveyorAndCPM(IntakeSub.starWheelAndCPMSpeed);
RobotContainer.intakeSub.runTurretFeeder(IntakeSub.conveyorMotorSpeed);
}
}else{
RobotContainer.intakeSub.intakeOut();
RobotContainer.intakeSub.runIntake(IntakeSub.intakeSpeed);
}
if(t.get() != 0){
System.out.println("Timer is: " + t.get());
}

}

@Override
public void end(boolean interrupted) {
RobotContainer.intakeSub.runConveyorAndCPM(0);
RobotContainer.intakeSub.runTurretFeeder(0);
RobotContainer.intakeSub.intakeOut();
finished = true;
}

@Override
public boolean isFinished() {
return countBalls()>=3 || t.get()>5 || DriverStation.getInstance().getMatchTime()-tim > 5;
}

int countBalls = 0;
boolean prevTrue = false;
public int countBalls(){
if(!prevTrue && RobotContainer.touchThree.get()){
countBalls++;
}

if(!RobotContainer.touchThree.get()) prevTrue = false;
else prevTrue = true;

System.out.println("counting: " + countBalls);
System.out.println("prevTrue: " + prevTrue);
return countBalls;
}
}
7 changes: 0 additions & 7 deletions src/main/java/frc/robot/commands/CPMCommand.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,3 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 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.wpilibj2.command.CommandBase;
Expand Down
32 changes: 26 additions & 6 deletions src/main/java/frc/robot/commands/DriveCommand.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,14 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj.DoubleSolenoid.Value;
import edu.wpi.first.wpilibj2.command.CommandBase;
import frc.robot.Robot;
import frc.robot.RobotContainer;

public class DriveCommand extends CommandBase {

boolean autoShift = true;

public DriveCommand() {
addRequirements(RobotContainer.driveSub);
}
Expand All @@ -16,14 +20,30 @@ public void initialize() {
@Override
public void execute() {

// RobotContainer.driveSub.drive(RobotContainer.driver.getRawAxis(1), 0.6 * RobotContainer.driver.getRawAxis(4));
RobotContainer.driveSub.teleDrive();

// if (RobotContainer.driveSub.getCurrentGear() == 1 && Math.abs(RobotContainer.driveSub.getRotationSpeed(RobotContainer.driveSub.getCurrentGear())) > DriveSub.limitRotSpdGear1) {
// RobotContainer.driveSub.shift();
// } else if (RobotContainer.driveSub.getCurrentGear() == 2 && Math.abs(RobotContainer.driveSub.getRotationSpeed(RobotContainer.driveSub.getCurrentGear())) < DriveSub.limitRotSpdGear1) {
// RobotContainer.driveSub.shift();
// }
if(RobotContainer.driver.getPOV() == 180){
autoShift = false;
}
if(RobotContainer.driver.getPOV() == 0){
autoShift = true;
}
if(!Robot.auto){
if(autoShift){
if (RobotContainer.dsL.get() == Value.kReverse && Math.abs(RobotContainer.driveSub.getWheelVelocity())>2.1){ //1.8
RobotContainer.dsL.set(Value.kForward);
} else if (RobotContainer.dsL.get() == Value.kForward && Math.abs(RobotContainer.driveSub.getWheelVelocity()) < 0.8) { //1.2
RobotContainer.dsL.set(Value.kReverse);
}
}else{
if(RobotContainer.driver.getPOV() == 90){
RobotContainer.dsL.set(Value.kForward);
}else if(RobotContainer.driver.getPOV() == 270){
RobotContainer.dsL.set(Value.kReverse);
}
}
}

}

@Override
Expand Down
7 changes: 0 additions & 7 deletions src/main/java/frc/robot/commands/FlywheelCommand.java
Original file line number Diff line number Diff line change
@@ -1,10 +1,3 @@
/*----------------------------------------------------------------------------*/
/* Copyright (c) 2019 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.wpilibj2.command.CommandBase;
Expand Down
Loading

0 comments on commit aa525d6

Please sign in to comment.