Skip to content

Commit

Permalink
Drivetrain speeds changed, PID intensity altered
Browse files Browse the repository at this point in the history
  • Loading branch information
frc5430c committed Apr 5, 2024
1 parent 2f0a615 commit 9b931e2
Show file tree
Hide file tree
Showing 14 changed files with 594 additions and 362 deletions.
80 changes: 80 additions & 0 deletions src/main/java/com/team5430/util/log.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,80 @@
package com.team5430.util;

import com.ctre.phoenix.motorcontrol.StickyFaults;
import com.ctre.phoenix.motorcontrol.can.TalonSRX;
import com.ctre.phoenix6.hardware.TalonFX;

import edu.wpi.first.wpilibj2.command.WaitCommand;

public class log {

public log() {
}

public void println(String printing) {
System.out.println(printing);
}

public void motor(TalonSRX name) {
StickyFaults errors = new StickyFaults();

name.getStickyFaults(errors);

String motorName = name.toString();

double startup = 0;

if (errors.APIError == true) {
println(motorName + ": API Error, check firmware");
} else if (errors.HardwareESDReset == true) {
println(motorName + ": Not used.");
} else if (errors.RemoteLossOfSignal == true) {
println(motorName + ": RemoteSensor lost conection.");
} else if (errors.ResetDuringEn == true) {
println(motorName + ": Has been turned on while enabled, or reset, please check wiring.");
} else if (errors.SensorOutOfPhase == true) {
println(motorName + ": Sensor is not aligned properly.");
} else if (errors.SensorOverflow == true) {
println(motorName + ": Sensor Overflow.");
} else if (errors.SupplyOverV == true) {
println(motorName + ": voltage is above rated voltage.");
} else if (errors.SupplyUnstable == true) {
println(motorName + ": voltage is fluctuating too much, check battery");
} else if (errors.UnderVoltage == true) {
println(motorName + ": voltage is under 6.5V");
} else if (errors.HardwareESDReset == false && startup >= 1) {
println(motorName + ": [✓]");
startup++;
}
new WaitCommand(1);
}

public void motor(TalonFX name) {
String motorName = name.toString();
double startup = 0;
if (name.getStickyFault_ProcTemp().getValue() == true) {
println(motorName + ": Temperature exceeded limit.");
} else if (name.getStickyFault_MissingDifferentialFX().getValue() == true) {
println(motorName + ": Not used.");
} else if (name.getStickyFault_RemoteSensorDataInvalid().getValue() == true) {
println(motorName + ": RemoteSensor lost conection, data may not be accurate any");
} else if (name.getStickyFault_Hardware().getValue() == true) {
println(motorName + ": Hardware fault occured.");
} else if (name.getStickyFault_FusedSensorOutOfSync().getValue() == true) {
println(motorName + ": Sensor is not in sync.");
} else if (name.getStickyFault_RemoteSensorPosOverflow().getValue() == true) {
println(motorName + ": Sensor Overflow.");
} else if (name.getStickyFault_OverSupplyV().getValue() == true) {
println(motorName + ": voltage is above rated voltage.");
} else if (name.getStickyFault_UnstableSupplyV().getValue() == true) {
println(motorName + ": voltage is fluctuating too much, check battery");
} else if (name.getStickyFault_Undervoltage().getValue() == true) {
println(motorName + ": voltage is under 6.5V");
} else if (name.getStickyFault_BootDuringEnable().getValue() == false && startup >= 1) {
println(motorName + ": [✓]");
startup++;
}
new WaitCommand(1);
}

}
8 changes: 4 additions & 4 deletions src/main/java/frc/robot/Constants.java
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@

public class Constants {
//multiplier must not be 0
public static double multiplier = .5;
public static double multiplier = 1;

//
public static double gyroPos = 0;
Expand All @@ -15,7 +15,7 @@ public class Constants {
//represents number of inches in a foot
public static double inches = 12;
// ratio of the intake
public static double Iratio = 56/12;
public static double Iratio = 225;
// represents the amount of gear ratio * rotations needed for 1 degree of pivot rotation
public static double degree = 1.0891/90;
// the time it takes to pull the arms down
Expand All @@ -26,8 +26,9 @@ public class Constants {
public static double driveinInchespower = 0.3;

public static double delay = 1;

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

Expand All @@ -36,7 +37,6 @@ public static class CANid {
public static int frontLeftMotor = 4;
public static int backRightMotor = 3;
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;
Expand Down
102 changes: 59 additions & 43 deletions src/main/java/frc/robot/RobotContainer.java
Original file line number Diff line number Diff line change
Expand Up @@ -9,65 +9,74 @@
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.InstantCommand;
import edu.wpi.first.wpilibj2.command.ProxyCommand;
import edu.wpi.first.wpilibj2.command.RunCommand;
import edu.wpi.first.wpilibj2.command.button.CommandJoystick;
import edu.wpi.first.wpilibj2.command.button.Trigger;
import frc.robot.commands.Autos;
import frc.robot.commands.setPos;
import frc.robot.subsystems.driveTrain;
import frc.robot.subsystems.hangSub;
import frc.robot.subsystems.intakeSub;

import frc.robot.subsystems.intakeSub.Value;

public class RobotContainer {


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

//Joysticks are initialized as CommandJoysticks
// 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); //Controller is initalized as CommandJoySticks
private CommandJoystick CO_Con = new CommandJoystick(Constants.OperatorC.CO_Con); // Controller is initalized as

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

public RobotContainer() {

configureBindings();

//motor configs
// motor configs
m_driveTrain.motorConfig();
m_IntakeSub.motorConfig();

m_intakeSub.motorConfig();

// Default command for Drive Train
m_driveTrain.setDefaultCommand(
new RunCommand( () -> m_driveTrain.drive(L_Joy.getY(), R_Joy.getY()), m_driveTrain)); //The drivetrain control will be set as defaultCommand
new RunCommand(() -> m_driveTrain.drive(L_Joy.getY(), R_Joy.getY()), m_driveTrain));
// The drivetrain control
// will be set as
// defaultCommand

// shuffleboard options
m_chooser.setDefaultOption("Run This One", Autos.panicAuto(m_driveTrain));
//m_chooser.addOption("Right", Autos.autoRight(m_driveTrain, m_IntakeSub));
//m_chooser.addOption("Center", Autos.autoCenter(m_driveTrain, m_IntakeSub));
//m_chooser.addOption("Left", Autos.autoLeft(m_driveTrain, m_IntakeSub));

m_chooser.addOption("Click this one", Autos.panicAuto(m_driveTrain));
// m_chooser.addOption("Right", Autos.autoRight(m_driveTrain, m_IntakeSub));
// m_chooser.addOption("Center", Autos.autoCenter(m_driveTrain, m_IntakeSub));
// m_chooser.addOption("Left", Autos.autoLeft(m_driveTrain, m_IntakeSub));

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

SmartDashboard.putNumber("Delay", Constants.delay);

}

private void configureBindings() { //initializes and binds all the buttons to methods inside subsystem class
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

//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);
// 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 R1_Button = CO_Con.button(6);
Expand All @@ -79,33 +88,40 @@ private void configureBindings() { //initializes and binds all the buttons to me
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
// Code down here are buttons assigned to the specific methods/actions from
// subsystems
// in "instantCommand( ));" is a methods from subsystem binded to the buttona

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

L_JoyButton.onTrue(new InstantCommand(m_driveTrain::VariableSpeedIncreaseNORMAL, m_driveTrain));
L_JoyButton.onFalse(new InstantCommand(m_driveTrain::VariableSpeedDecrease, m_driveTrain));
L_JoyButton.onTrue(new InstantCommand(m_driveTrain::LSpeed, m_driveTrain));
L_JoyButton.onFalse(new InstantCommand(m_driveTrain::DefaultSpeed, m_driveTrain));

/*
UP_DPad.onTrue(new InstantCommand(m_intakeSub.setPos(Value.SPEAKER))); // Dpad for intake to move up in shoot position to score // speaker
RIGHT_DPad.onTrue(new ProxyCommand(new setPos(Value.AMP, m_intakeSub))); // Dpad right for intake to move into Amp Position
DOWN_DPad.onTrue(new ProxyCommand(new setPos(Value.FLOOR, m_intakeSub))); // Dpad down for intake to move in floor position to intake note
*/

UP_DPad.onTrue(new InstantCommand(m_intakeSub::setSpeaker, m_intakeSub));
RIGHT_DPad.onTrue(new InstantCommand(m_intakeSub::setAmp, m_intakeSub));
DOWN_DPad.onTrue(new InstantCommand(m_intakeSub::setFloor, m_intakeSub));



// 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::setAmp)); //Dpad right for intake to move into Amp Position

//A_Button.onTrue(new InstantCommand(intakeSub:: outtake));
//A_Button.onFalse(new InstantCommand(intakeSub:: stopIntake));
//B_Button.onTrue(new InstantCommand(intakeSub:: intake));
//B_Button.onFalse(new InstantCommand(intakeSub:: stopIntake));
/*
* A_Button.onTrue(new InstantCommand(intakeSub:: outtake));
* A_Button.onFalse(new InstantCommand(intakeSub:: stopIntake));
* B_Button.onTrue(new InstantCommand(intakeSub:: intake));
* B_Button.onFalse(new InstantCommand(intakeSub:: stopIntake));
*/


// Goes to shooter point after pressing up
L1_Button.onTrue(new InstantCommand(m_HangSub:: L_hang));
L1_Button.onFalse(new InstantCommand(m_HangSub:: stop_Lhang));
// Control
L1_Button.onTrue(new InstantCommand(m_HangSub::L_hang));
L1_Button.onFalse(new InstantCommand(m_HangSub::stop_Lhang));

R1_Button.onTrue(new InstantCommand(m_HangSub:: R_hang));
R1_Button.onFalse(new InstantCommand(m_HangSub:: stop_Rhang));
R1_Button.onTrue(new InstantCommand(m_HangSub::R_hang));
R1_Button.onFalse(new InstantCommand(m_HangSub::stop_Rhang));
}

public Command getAutonomousCommand() {
Expand Down
8 changes: 5 additions & 3 deletions src/main/java/frc/robot/commands/Autos.java
Original file line number Diff line number Diff line change
Expand Up @@ -5,7 +5,7 @@
import edu.wpi.first.wpilibj2.command.WaitCommand;
import frc.robot.Constants;
import frc.robot.subsystems.driveTrain;
import frc.robot.subsystems.intakeSub;
import frc.robot.subsystems.intakeSub.Value;

public class Autos {

Expand Down Expand Up @@ -108,9 +108,11 @@ public static Command panicAuto(driveTrain drive) {
return Commands.sequence(
new WaitCommand(Constants.delay),
drive.C_driveinInches(-65)
);

);
}


}
}


27 changes: 27 additions & 0 deletions src/main/java/frc/robot/commands/DriveToDistance.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,27 @@
package frc.robot.commands;

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

public class DriveToDistance extends Command{

private driveTrain _drive;

private double Inches;

public DriveToDistance(driveTrain drive, double inches){
_drive = drive;
addRequirements(_drive);
Inches = inches;
}

@Override
public void initialize(){
_drive.driveininches(Inches);
}

@Override
public boolean isFinished(){
return true;
}
}
42 changes: 42 additions & 0 deletions src/main/java/frc/robot/commands/IntakeNote.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,42 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intakeSub;
import frc.robot.subsystems.intakeSub.Value;

public class IntakeNote extends Command {

private intakeSub _intake;

// require the intake subsystem to run this command
public IntakeNote(intakeSub intake) {
intake = _intake;
addRequirements(intake);
}

// runs when command is called initally
@Override
public void initialize() {
new setPos(Value.FLOOR, _intake);
new IntakeSet(Value.INTAKE, _intake);
new TransversalSet(Value.INTAKE, _intake);
System.out.println("HELLO");
}

// Miguel was here

// runs when command ends
@Override
public void end(boolean isFinished) {
new IntakeSet(Value.STOP, _intake);
new TransversalSet(Value.STOP, _intake);
new setPos(Value.SPEAKER, _intake);
}

// tells scheduler that this command runs once*
@Override
public boolean isFinished() {
return true;
}

}
18 changes: 18 additions & 0 deletions src/main/java/frc/robot/commands/IntakeSet.java
Original file line number Diff line number Diff line change
@@ -0,0 +1,18 @@
package frc.robot.commands;

import edu.wpi.first.wpilibj2.command.Command;
import frc.robot.subsystems.intakeSub;
import frc.robot.subsystems.intakeSub.Value;;

public class IntakeSet extends Command {

private intakeSub _intake;

// no intake required as to allow running at any point
public IntakeSet(final Value value, intakeSub intake) {
_intake = intake;
addRequirements(_intake);
_intake.intakeSet(value);
}

}
Loading

0 comments on commit 9b931e2

Please sign in to comment.