Skip to content

Commit

Permalink
Merge pull request #11 from Team5430/dev
Browse files Browse the repository at this point in the history
Updating Master Code with Dev Changes
  • Loading branch information
frc5430 committed Mar 8, 2024
2 parents d6956d2 + 078b31d commit 7148336
Show file tree
Hide file tree
Showing 11 changed files with 577 additions and 390 deletions.
37 changes: 26 additions & 11 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
@@ -1,31 +1,46 @@
package frc.robot;

public class Constants {

public static double multiplier = 0;
//multiplier must not be 0
public static double multiplier = .5;

//
public static double gyroPos = 0;
//represents the amount of rotations the motor needs in order to make one full gear rotation
public static double ratio = 10.71;
//represents an increase or decrease in the number that the related software gives.
public static double encoderTicks = 2048;
//represents the total length of the wheel
public static double circumferenceInInches = 6 * Math.PI;
//represents number of inches in a foot
public static double inches = 12;


// ratio of the intake
public static double Iratio = 12/56;
// represents the amount of gear ratio * rotations needed for 1 degree of pivot rotation
public static double degree = 1.0891/90;

public static class CANid {
// Talons CANid
public static int backLeftMotor = 2;
public static int L_hangmotor = 2;
public static int R_hangmotor = 1;
//public static final int shooterMotor = 15;

// Talon CANid's
public static int backLeftMotor = 5;
public static int frontLeftMotor = 4;
public static int backRightMotor = 3;
public static int frontRightMotor = 5;
public static int shooterMotor;
public static int pivotMotor;
public static int intakeMotor;
public static int hang_motor;
public static int frontRightMotor = 6;
public static int shooterMotor = 15;
public static int pivotMotor = 7;
public static int intakeMotor = 8;
public static int transversalMotor = 9;
}

public static class OperatorC {
//Sets the controller in USB order from driver station
public static int CO_Con = 0;
//sets the left stick in USB order from driver station
public static int L_Joy = 1;
//sets the right stick in USB order from driver station
public static int R_Joy = 2;
}
}
4 changes: 4 additions & 0 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -8,14 +8,18 @@
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.CommandScheduler;


public class Robot extends TimedRobot {
private Command m_autonomousCommand;

private RobotContainer m_robotContainer;


@Override
public void robotInit() {
m_robotContainer = new RobotContainer();


}

@Override
Expand Down
105 changes: 70 additions & 35 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,34 +4,33 @@

package frc.robot;

import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
import edu.wpi.first.wpilibj.smartdashboard.SendableChooser;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.Subsystem;
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.autoCenter;
import frc.robot.commands.autoLeft;
import frc.robot.commands.autoRight;
import frc.robot.commands.Autos;
import frc.robot.subsystems.driveTrain;
import frc.robot.subsystems.hangSub;
import frc.robot.subsystems.intakeSub;
import frc.robot.subsystems.shooterSub;

public class RobotContainer {

// subsystems
// subsystems as variables
private driveTrain m_driveTrain = new driveTrain();
private shooterSub m_shooterSub = new shooterSub();
private intakeSub m_intakeSub = new intakeSub();

private hangSub m_HangSub = new hangSub();
private intakeSub m_IntakeSub = new intakeSub();
// private shooterSub m_shooterSub = new shooterSub();

//Joysticks are initialized as CommandJoysticks
public CommandJoystick L_Joy = new CommandJoystick(Constants.OperatorC.L_Joy);
public CommandJoystick R_Joy = new CommandJoystick(Constants.OperatorC.R_Joy);

private CommandJoystick CO_Con = new CommandJoystick(Constants.OperatorC.CO_Con);
// chooser for auton
public SendableChooser<Command> m_chooser = new SendableChooser<>();
private CommandJoystick CO_Con = new CommandJoystick(Constants.OperatorC.CO_Con); //Controller is initalized as CommandJoySticks

public SendableChooser<Command> m_chooser = new SendableChooser<>(); // object|scope for auton choosing

public RobotContainer() {
// default commands
Expand All @@ -41,38 +40,74 @@ public RobotContainer() {
//motor configs
m_driveTrain.motorConfig();

m_intakeSub.motorConfig();
m_IntakeSub.motorConfig();

m_shooterSub.motorConfig();
//m_shooterSub.motorConfig(); - Temporary commented

//drive active input during match
m_driveTrain.setDefaultCommand(
new RunCommand( () -> m_driveTrain.drive(L_Joy.getY(), R_Joy.getY()), m_driveTrain));

// autonmous routines

Command auto_1 = new autoCenter(m_driveTrain, m_shooterSub, m_intakeSub);
Command auto_2 = new autoLeft(m_driveTrain, m_shooterSub, m_intakeSub);
Command auto_3 = new autoRight(m_driveTrain, m_shooterSub, m_intakeSub);


m_driveTrain.setDefaultCommand(
new RunCommand( () -> m_driveTrain.drive(L_Joy.getY(), R_Joy.getY()), m_driveTrain)); //The drivetrain control will be set as defaultCommand
//DefaultCommand will run first then all of the subsystems
// newRunCommand( () -> m_HangSub.)
//new RunCommand( () ->
// shuffleboard options

m_chooser.addOption("Auton 1", auto_1);
m_chooser.addOption("Auton 2", auto_2);
m_chooser.addOption("Auton 3", auto_3);



m_chooser.addOption("Right", Autos.autoRight(m_driveTrain, m_IntakeSub));
m_chooser.setDefaultOption("Left", Autos.autoLeft(m_driveTrain, m_IntakeSub));
m_chooser.addOption("Center", Autos.autoCenter(m_driveTrain, m_IntakeSub));

Shuffleboard.getTab("Auton")
.add("AutonChoice", m_chooser);

}

private void configureBindings() {
private void configureBindings() { //initializes and binds all the buttons to methods inside subsystem class

//Code down here are buttons from joysticks/gamepad intialized and used for subsystems
//word before Trigger is button, word before = is functions act the buttons
//X = 3 Y = 4 L1 = 5 R1 = 6 Back arrow = 7 Forward arrow = 8 Left joystick = 9 Right joystick = 10
Trigger A_Button = CO_Con.button(1);
Trigger B_Button = CO_Con.button(2);
Trigger X_Button = CO_Con.button(3);
Trigger Y_Button = CO_Con.button(4);
Trigger L1_Button = CO_Con.button(5);
Trigger R2_Button = CO_Con.button(6);
Trigger Back_Arrow = CO_Con.button(7);
Trigger Forward_Arrow = CO_Con.button(8);
Trigger LeftJoystick_Button = CO_Con.button(9);
Trigger RightJoystick_Button = CO_Con.button(10);
Trigger UP_DPad = CO_Con.povUp();
Trigger DOWN_DPad = CO_Con.povDown();
Trigger RIGHT_DPad = CO_Con.povRight();

//Code down here are buttons assigned to the specific methods/actions from subsystems
//in "instantCommand( ));" is a methods from subsystem binded to the buttona

UP_DPad.onTrue(new InstantCommand(intakeSub::setShoot)); // (deprecated) Dpad for intake to move up in shoot position to score speaker
DOWN_DPad.onTrue(new InstantCommand(intakeSub::setFloor)); //Dpad down for intake to move in floor position to intake note
RIGHT_DPad.onTrue(new InstantCommand(intakeSub::setFloor)); //Dpad right for intake to move into Amp Position

A_Button.and(B_Button).whileFalse(new InstantCommand(intakeSub::C_stopIntake));
A_Button.onTrue(new InstantCommand(intakeSub:: C_outtake));
B_Button.onTrue(new InstantCommand(intakeSub:: C_intake));
//Junkyards below, but these won't be deleted because we might need them

// trigger first, then the use of it
Trigger R_joyButton = R_Joy.button(3);

R_joyButton.onTrue(new InstantCommand(m_driveTrain::VariableSpeedIncrease, m_driveTrain));
R_joyButton.onFalse(new InstantCommand(m_driveTrain::VariableSpeedDecrease, m_driveTrain));

//Trigger R_joyButton = R_Joy.button(3);
// Trigger B_Button = CO_Con.button(2);
//Trigger Up_L_Joystick = CO_Con.axisGreaterThan(1, 0);
//R_joyButton.onTrue(new InstantCommand(m_driveTrain::VariableSpeedIncrease, m_driveTrain));
//R_joyButton.onFalse(new InstantCommand(m_driveTrain::VariableSpeedDecrease, m_driveTrain));
//A_Button.onTrue(new InstantCommand(intakeSub::C_intake));
// Goes to shooter point after pressing up
//A_Button.onTrue(new InstantCommand(m_HangSub::extendclimbertimer, m_HangSub));
// B_Button.onTrue(new InstantCommand(m_IntakeSub::outtake, m_IntakeSub));
// B_Button.onFalse(new InstantCommand(m_IntakeSub::stopIntake, m_IntakeSub));
A_Button.onTrue(m_HangSub.C_pullinTime(1.8, -0.6));
//B_Button.onTrue(m_HangSub.C_releaseInTime(3, 0.4));
//A_Button.toggleOnTrue(new InstantCommand(m_HangSub::C_Doe, m_HangSub));
// B_Button.onTrue(new InstantCommand(m_HangSub:: C_ExtendClimberTimer));
}

public Command getAutonomousCommand() {
Expand Down
119 changes: 119 additions & 0 deletions src/main/java/frc/robot/commands/Autos.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,119 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.subsystems.driveTrain;
import frc.robot.subsystems.intakeSub;

public class Autos {


/*By March 3, 2024, all shooters command lines are commented due to absence of shooter,
we will not use the shooter by the time of arizona trip
*/

public static Command autoRight(driveTrain drive, intakeSub intake) {
return Commands.sequence(
//shoot.C_ShooterOut(),//gets the shooter ready to shoot
intake.C_intake(),//makes sure the note is correctly in place
new WaitCommand(1),//gives the shooter time to shoot
intake.C_outtake(),//moves the note into the shooter which then flings it out
new WaitCommand(.5),//lets the note fling out
intake.C_stopIntake(),//turns off the intake motor
//shoot.C_ShooterStop(),//turns off the shooter motor
drive.C_driveinInches(-11.046),//moves backwards 11.046 inches
drive.C_turntoAngle(-60.02),//turns left 60.02 degrees
intake.C_extendnintake(),//moves intake to floor position and turns the intake on
drive.C_driveinInches(-55.5),//moves backwards 55.5 inches
// intake.C_setPos("Shooter"),//sets the intake to shooter position
intake.C_stopIntake(),//turns off the intake motor
drive.C_driveinInches(55.5),//goes forward 55.5 inches
drive.C_turntoAngle(60.02),//turns right 60.02 degrees
drive.C_driveinInches(11.046),//goes forward 11.046 inches
//shoot.C_ShooterOut(),//turns on shooter motor
new WaitCommand(1),//lets the shooter motor warm up
intake.C_outtake(),//moves the note into the shooter to then be flung
new WaitCommand(1),//gives time for the note to be flung out
// shoot.C_ShooterStop(),//turns off the shooter motor
intake.C_stopIntake(),//turns off intake motor
drive.C_driveinInches(-11.046),//moves backwards 11.046 inches
drive.C_turntoAngle(-60.02),//turns left 60.02 degrees
drive.C_driveinInches(-55.5),//moves backwards 55.5 inches
intake.C_resetPos(),//resets the intake pivot position
drive.C_driveinInches(-18.95), //drive.C_driveinInches(-18.95),//No idea how this got here, leaving this here just in case
drive.C_turntoAngle(73.78)//drive.C_turntoAngle(73.78)//somebody needed it
);

}

public static Command autoLeft(driveTrain drive, intakeSub intake) {
return Commands.sequence(


//shoot.C_ShooterOut(),//turns on the shooter motor
intake.C_intake(),//makes sure the note is properly secure
new WaitCommand(1),//lets the shooter warm up to be at speed
intake.C_outtake(),//moves the note into the shooter to then be flung
new WaitCommand(1.0),//lets the note be flung out with time
intake.C_stopIntake(),//turns off the intake motor
//shoot.C_ShooterStop(),//turns off the shooter motor
drive.C_driveinInches(11.046),//moves backwards 11.046 inches
drive.C_turntoAngle(60.02),//turns the robot 60.02 degrees right
intake.C_extendnintake(),//moves the intake to the floor pivot positionand turns on the intake motor
drive.C_driveinInches(-55.5),//moves backwards 55.5 inches, picking up the note in a sweep
intakeSub.C_setShoot(),//moves the intake to the shooter position
intake.C_stopIntake(),//turns off the intake motor
drive.C_driveinInches(55.5),//moves forward 55.5 inches
drive.C_turntoAngle(-60.02),//turns left 60.02 degrees
drive.C_driveinInches(11.046),//moves forward 11.046 inches
//shoot.C_ShooterOut(),//turns on the shooter motor
new WaitCommand(1),//lets the shooter warm up
intake.C_outtake(),//makes the intake push the note into the shooter
new WaitCommand(.5),//lets the note be flung by the shooter into the speaker
//shoot.C_ShooterStop(),//turns off the shooter motor
intake.C_stopIntake(),//turns off the intake motor
drive.C_driveinInches(-11.046),//drives backwards 11.046 inches
drive.C_turntoAngle(60.02),//turns the robot 60.02 degrees right
drive.C_driveinInches(-55.5),//moves backwards 55.5 inches
intake.C_resetPos()//moves the intake into the shooter position




);
}
public static Command autoCenter(driveTrain drive, intakeSub intake) {
return Commands.sequence(

//shoot.C_ShooterOut(), //shootes out the note
new WaitCommand(1),//lets shooter speed up
intake.C_outtake(), //outtakes the intake
intake.C_extendnintake(),//extends the intake
new WaitCommand(1),
intake.C_stopIntake(),
//shoot.C_ShooterOut(), //shootes out the note
drive.C_driveinInches(-36),
//intake.C_setPos("Shooter"),// Set the intake to a shooter position
intake.C_stopIntake(), //Stop the intake
new WaitCommand(5),
drive.C_driveinInches(36),
intake.C_outtake(), //outtakes the intake
//shoot.C_ShooterOut(), //Shoots out the note
//shoot.C_ShooterStop(), //Stops the shooter from shooting
intake.C_stopIntake() //Stops the intake from shooting
);

}
public static Command autoTest(driveTrain drive, intakeSub intake) {
return Commands.sequence(
drive.C_driveinInches(2),
drive.C_turntoAngle(180),
drive.C_driveinInches(-2),
drive.C_turntoAngle(-180)
);

}
}


31 changes: 0 additions & 31 deletions src/main/java/frc/robot/commands/autoCenter.java

This file was deleted.

Loading

0 comments on commit 7148336

Please sign in to comment.