Compare commits
6 Commits
c38c3d1213
...
master
| Author | SHA1 | Date | |
|---|---|---|---|
|
|
e6e16b891e | ||
| f466c54a1d | |||
| 4906c7f0fb | |||
| f33f35b8f8 | |||
| 908aca7bd1 | |||
| 0bf71c7161 |
@@ -2,5 +2,5 @@
|
||||
"enableCppIntellisense": false,
|
||||
"currentLanguage": "java",
|
||||
"projectYear": "2025",
|
||||
"teamNumber": 2648
|
||||
"teamNumber": 9998
|
||||
}
|
||||
92
simgui-ds.json
Normal file
92
simgui-ds.json
Normal file
@@ -0,0 +1,92 @@
|
||||
{
|
||||
"keyboardJoysticks": [
|
||||
{
|
||||
"axisConfig": [
|
||||
{
|
||||
"decKey": 65,
|
||||
"incKey": 68
|
||||
},
|
||||
{
|
||||
"decKey": 87,
|
||||
"incKey": 83
|
||||
},
|
||||
{
|
||||
"decKey": 69,
|
||||
"decayRate": 0.0,
|
||||
"incKey": 82,
|
||||
"keyRate": 0.009999999776482582
|
||||
}
|
||||
],
|
||||
"axisCount": 3,
|
||||
"buttonCount": 4,
|
||||
"buttonKeys": [
|
||||
90,
|
||||
88,
|
||||
67,
|
||||
86
|
||||
],
|
||||
"povConfig": [
|
||||
{
|
||||
"key0": 328,
|
||||
"key135": 323,
|
||||
"key180": 322,
|
||||
"key225": 321,
|
||||
"key270": 324,
|
||||
"key315": 327,
|
||||
"key45": 329,
|
||||
"key90": 326
|
||||
}
|
||||
],
|
||||
"povCount": 1
|
||||
},
|
||||
{
|
||||
"axisConfig": [
|
||||
{
|
||||
"decKey": 74,
|
||||
"incKey": 76
|
||||
},
|
||||
{
|
||||
"decKey": 73,
|
||||
"incKey": 75
|
||||
}
|
||||
],
|
||||
"axisCount": 2,
|
||||
"buttonCount": 4,
|
||||
"buttonKeys": [
|
||||
77,
|
||||
44,
|
||||
46,
|
||||
47
|
||||
],
|
||||
"povCount": 0
|
||||
},
|
||||
{
|
||||
"axisConfig": [
|
||||
{
|
||||
"decKey": 263,
|
||||
"incKey": 262
|
||||
},
|
||||
{
|
||||
"decKey": 265,
|
||||
"incKey": 264
|
||||
}
|
||||
],
|
||||
"axisCount": 2,
|
||||
"buttonCount": 6,
|
||||
"buttonKeys": [
|
||||
260,
|
||||
268,
|
||||
266,
|
||||
261,
|
||||
269,
|
||||
267
|
||||
],
|
||||
"povCount": 0
|
||||
},
|
||||
{
|
||||
"axisCount": 0,
|
||||
"buttonCount": 0,
|
||||
"povCount": 0
|
||||
}
|
||||
]
|
||||
}
|
||||
@@ -4,30 +4,86 @@
|
||||
|
||||
package frc.robot;
|
||||
|
||||
import static edu.wpi.first.units.Units.Second;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
|
||||
import edu.wpi.first.wpilibj.shuffleboard.Shuffleboard;
|
||||
import edu.wpi.first.wpilibj.util.Color;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.RunCommand;
|
||||
import edu.wpi.first.wpilibj2.command.WaitCommand;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandPS5Controller;
|
||||
import edu.wpi.first.wpilibj2.command.button.CommandXboxController;
|
||||
import edu.wpi.first.wpilibj2.command.button.Trigger;
|
||||
import frc.robot.constants.ArmConstants;
|
||||
import frc.robot.constants.IOConstants;
|
||||
import frc.robot.constants.LEDConstants;
|
||||
import frc.robot.subsystems.Arm;
|
||||
import frc.robot.subsystems.DriveTrain;
|
||||
import frc.robot.subsystems.Grabber;
|
||||
import frc.robot.subsystems.HighFive;
|
||||
import frc.robot.subsystems.LEDs;
|
||||
|
||||
public class RobotContainer {
|
||||
CommandXboxController driver;
|
||||
|
||||
Arm arm;
|
||||
private CommandPS5Controller driver;
|
||||
private Arm arm;
|
||||
private DriveTrain driveTrain;
|
||||
private Grabber grabber;
|
||||
private HighFive highFive;
|
||||
private LEDs leds;
|
||||
|
||||
|
||||
public RobotContainer() {
|
||||
arm = new Arm();
|
||||
driver = new CommandXboxController(IOConstants.kDriverID0);
|
||||
driveTrain = new DriveTrain();
|
||||
grabber = new Grabber();
|
||||
driver = new CommandPS5Controller(IOConstants.kDriverID0);
|
||||
highFive = new HighFive();
|
||||
leds = new LEDs(LEDConstants.kPWMPortID, LEDConstants.kNumLEDs);
|
||||
configureBindings();
|
||||
}
|
||||
|
||||
private void configureBindings() {
|
||||
driveTrain.setDefaultCommand(
|
||||
driveTrain.driveArcade(
|
||||
driver::getLeftY,
|
||||
driver::getLeftX
|
||||
)
|
||||
);
|
||||
|
||||
grabber.setDefaultCommand(grabber.stop());
|
||||
|
||||
driver.R1().whileTrue(grabber.runGrabberMotor(1));
|
||||
|
||||
driver.L1().whileTrue(grabber.runGrabberMotor(-1));
|
||||
|
||||
arm.setDefaultCommand(arm.stop());
|
||||
|
||||
driver.povUp().whileTrue(arm.runArmMotor(1));
|
||||
|
||||
driver.povDown().whileTrue(arm.runArmMotor(-1));
|
||||
|
||||
Trigger highFiveTrigger = new Trigger(highFive::SwitchDigitalInput);
|
||||
|
||||
highFiveTrigger.onFalse(
|
||||
leds.blinkColorchange(Color.kGreen, Color.kRed, Color.kBlue, 0.5, 2)
|
||||
.andThen(
|
||||
//new WaitCommand(5),
|
||||
leds.setAll(Color.kBlack)
|
||||
)
|
||||
);
|
||||
|
||||
|
||||
|
||||
|
||||
Shuffleboard.getTab("HighFive")
|
||||
.addBoolean("Switch Pressed", () -> highFive.SwitchDigitalInput());
|
||||
}
|
||||
|
||||
|
||||
public Command getAutonomousCommand() {
|
||||
return Commands.print("No autonomous command configured");
|
||||
}
|
||||
}
|
||||
}
|
||||
6
src/main/java/frc/robot/constants/GrabberConstants.java
Normal file
6
src/main/java/frc/robot/constants/GrabberConstants.java
Normal file
@@ -0,0 +1,6 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class GrabberConstants {
|
||||
public static final int kGrabberLtMotorID6 = 6;
|
||||
public static final int kGrabberRtMotorID7 = 7;
|
||||
}
|
||||
6
src/main/java/frc/robot/constants/LEDConstants.java
Normal file
6
src/main/java/frc/robot/constants/LEDConstants.java
Normal file
@@ -0,0 +1,6 @@
|
||||
package frc.robot.constants;
|
||||
|
||||
public class LEDConstants {
|
||||
public static final int kPWMPortID = 0;
|
||||
public static final int kNumLEDs = 256;
|
||||
}
|
||||
@@ -18,4 +18,8 @@ public class Arm extends SubsystemBase {
|
||||
motor.set(speed);
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return run(() -> motor.set(0));
|
||||
}
|
||||
}
|
||||
|
||||
@@ -2,7 +2,6 @@ package frc.robot.subsystems;
|
||||
import java.util.function.DoubleSupplier;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
import com.ctre.phoenix6.controls.Follower;
|
||||
|
||||
import edu.wpi.first.wpilibj.drive.DifferentialDrive;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
@@ -28,17 +27,10 @@ public class DriveTrain extends SubsystemBase {
|
||||
|
||||
drive = new DifferentialDrive(motorLeftFt, motorRightFt);
|
||||
}
|
||||
|
||||
public Command driveArcade(DoubleSupplier xSpeed, DoubleSupplier zRotation) {
|
||||
return run(() -> {
|
||||
//makes car like steering possible
|
||||
drive.arcadeDrive(xSpeed.getAsDouble(), zRotation.getAsDouble());
|
||||
});
|
||||
}
|
||||
|
||||
public Command driveTank(DoubleSupplier leftSpeed, DoubleSupplier rightSpeed) {
|
||||
return run(() -> {
|
||||
//makes tank steering possible
|
||||
drive.tankDrive(leftSpeed.getAsDouble(), rightSpeed.getAsDouble());
|
||||
});
|
||||
}
|
||||
}
|
||||
|
||||
31
src/main/java/frc/robot/subsystems/Grabber.java
Normal file
31
src/main/java/frc/robot/subsystems/Grabber.java
Normal file
@@ -0,0 +1,31 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import com.ctre.phoenix.motorcontrol.can.WPI_TalonSRX;
|
||||
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import frc.robot.constants.ArmConstants;
|
||||
import frc.robot.constants.DriveTrainConstants;
|
||||
import frc.robot.constants.GrabberConstants;
|
||||
|
||||
public class Grabber extends SubsystemBase {
|
||||
private WPI_TalonSRX motorRight;
|
||||
private WPI_TalonSRX motorLeft;
|
||||
|
||||
public Grabber() {
|
||||
motorRight = new WPI_TalonSRX(GrabberConstants.kGrabberRtMotorID7);
|
||||
motorLeft = new WPI_TalonSRX(GrabberConstants.kGrabberLtMotorID6);
|
||||
|
||||
motorLeft.follow(motorRight);
|
||||
}
|
||||
|
||||
public Command runGrabberMotor(double speed) {
|
||||
return run(() -> {
|
||||
motorRight.set(speed);
|
||||
});
|
||||
}
|
||||
|
||||
public Command stop() {
|
||||
return run(() -> motorRight.set(0));
|
||||
}
|
||||
}
|
||||
16
src/main/java/frc/robot/subsystems/HighFive.java
Normal file
16
src/main/java/frc/robot/subsystems/HighFive.java
Normal file
@@ -0,0 +1,16 @@
|
||||
package frc.robot.subsystems;
|
||||
import edu.wpi.first.wpilibj.DigitalInput;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
|
||||
public class HighFive extends SubsystemBase {
|
||||
private DigitalInput switchDigitalInput;
|
||||
|
||||
public HighFive(){
|
||||
switchDigitalInput = new DigitalInput(0);
|
||||
}
|
||||
|
||||
public boolean SwitchDigitalInput() {
|
||||
return switchDigitalInput.get();
|
||||
}
|
||||
|
||||
}
|
||||
90
src/main/java/frc/robot/subsystems/LEDs.java
Normal file
90
src/main/java/frc/robot/subsystems/LEDs.java
Normal file
@@ -0,0 +1,90 @@
|
||||
package frc.robot.subsystems;
|
||||
|
||||
import edu.wpi.first.wpilibj.AddressableLED;
|
||||
import edu.wpi.first.wpilibj.AddressableLEDBuffer;
|
||||
import edu.wpi.first.wpilibj.util.Color;
|
||||
import edu.wpi.first.wpilibj2.command.Command;
|
||||
import edu.wpi.first.wpilibj2.command.Commands;
|
||||
import edu.wpi.first.wpilibj2.command.SubsystemBase;
|
||||
import edu.wpi.first.wpilibj2.command.WaitCommand;
|
||||
|
||||
public class LEDs extends SubsystemBase {
|
||||
private AddressableLED leds;
|
||||
private AddressableLEDBuffer buffer;
|
||||
|
||||
private int fluidColorIndex;
|
||||
|
||||
public LEDs(int pwmPort, int numLEDs) {
|
||||
buffer = new AddressableLEDBuffer(numLEDs);
|
||||
leds = new AddressableLED(pwmPort);
|
||||
leds.setLength(numLEDs);
|
||||
leds.setData(buffer);
|
||||
leds.start();
|
||||
|
||||
fluidColorIndex = 0;
|
||||
}
|
||||
|
||||
public Command fluidColor(double delayTime) {
|
||||
return Commands.repeatingSequence(
|
||||
runOnce(() -> {
|
||||
for(int i = 0; i < buffer.getLength(); i++) {
|
||||
buffer.setHSV(i, (i + fluidColorIndex) % 180, 255, 255);
|
||||
}
|
||||
leds.setData(buffer);
|
||||
fluidColorIndex++;
|
||||
}),
|
||||
new WaitCommand(delayTime)
|
||||
);
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
public Command blinkColor(Color color, double delayTime, int times) {
|
||||
Command sequence = Commands.none(); // start with an empty command
|
||||
|
||||
for (int i = 0; i < times; i++) {
|
||||
sequence = Commands.sequence(
|
||||
sequence,
|
||||
setAll(color),
|
||||
new WaitCommand(delayTime),
|
||||
setAll(Color.kBlack),
|
||||
new WaitCommand(delayTime)
|
||||
);
|
||||
}
|
||||
|
||||
return sequence;
|
||||
}
|
||||
|
||||
public Command blinkColorchange(Color color, Color color2, Color color3, double delayTime, int times) {
|
||||
Command sequence = Commands.none(); // start with an empty command
|
||||
|
||||
for (int i = 0; i < times; i++) {
|
||||
sequence = Commands.sequence(
|
||||
sequence,
|
||||
setAll(color),
|
||||
new WaitCommand(delayTime),
|
||||
setAll(color2),
|
||||
new WaitCommand(delayTime),
|
||||
setAll(color3),
|
||||
new WaitCommand(delayTime)
|
||||
);
|
||||
}
|
||||
|
||||
return sequence;
|
||||
}
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
public Command setAll(Color color) {
|
||||
return runOnce(() -> {
|
||||
for(int i = 0; i < buffer.getLength(); i++) {
|
||||
buffer.setLED(i, color);
|
||||
}
|
||||
|
||||
leds.setData(buffer);
|
||||
});
|
||||
}
|
||||
}
|
||||
Reference in New Issue
Block a user