Skip to content

Commit fe8fc55

Browse files
authored
Merge branch 'main' into SZ-W3-AutonAdventuresPart1
2 parents 45eef02 + acaa5c7 commit fe8fc55

File tree

11 files changed

+339
-17
lines changed

11 files changed

+339
-17
lines changed

README.md

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,4 @@
1+
#2024 FRC Season
2+
This is the code base for FRC 3603, Cyber Coyotes, robot for the 2024 season.
3+
4+
Find us on social media @FRC3603

src/main/java/frc/robot/Constants.java

Lines changed: 5 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -21,6 +21,9 @@
2121
* constants are needed, to reduce verbosity.
2222
*/
2323
public final class Constants {
24+
25+
public int noteDistanceCheck = 100;
26+
2427
public static class OperatorConstants {
2528
public static final int K_DRIVER_CONTROLLER_PORT = 0;
2629
}
@@ -56,7 +59,8 @@ public static class CANIDs {
5659
public static final int INTAKE_CAN = 10;
5760
public static final int INDEX_CAN = 11;
5861

59-
public static final int TIME_OF_FLIGHT_ID = 12;
62+
public static final int NOTE_SENSOR_ID = 12; // Time of Flight sensor for the note
63+
6064

6165
public static final int BASS_GUITAR = 13;
6266

src/main/java/frc/robot/RobotContainer.java

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -3,10 +3,9 @@
33
// the WPILib BSD license file in the root directory of this project.
44

55
package frc.robot;
6-
76
import frc.robot.Constants.OperatorConstants;
8-
import frc.robot.subsystems.RatioMotorSubsystem;
97
import frc.robot.subsystems.CommandSwerveDrivetrain;
8+
import frc.robot.subsystems.LauncherSubsystem;
109
import frc.robot.subsystems.OrchestraSubsystem;
1110
import com.ctre.phoenix6.hardware.TalonFX;
1211
import com.ctre.phoenix6.signals.NeutralModeValue;
@@ -48,7 +47,7 @@ public class RobotContainer {
4847
// #endregion
4948

5049
// #region Subsystems
51-
RatioMotorSubsystem shooter;
50+
LauncherSubsystem shooter;
5251
OrchestraSubsystem daTunes;
5352
// #endregion Subsystems
5453

@@ -77,7 +76,7 @@ public RobotContainer() {
7776
shooterMotorMain = new TalonFX(Constants.CANIDs.RIGHT_FLYWHEEL_CAN);
7877
// #endregion
7978

80-
shooter = new RatioMotorSubsystem(shooterMotorMain, shooterMotorSub);
79+
shooter = new LauncherSubsystem(shooterMotorMain, shooterMotorSub);
8180
shooter.SetStatePower(1);
8281
shooter.SetRatio(1);
8382

Lines changed: 33 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,8 +1,39 @@
11
package frc.robot.commands;
22

33
import edu.wpi.first.wpilibj2.command.Command;
4+
import frc.robot.subsystems.NoteSensorSubsystem;
45

56
/* A simple but often used command to get a loaded (true) or nonloaded (false) status of the time of flight sensor pointed at the 'note' */
67
public class GetNoteStatus extends Command {
7-
8-
}
8+
/* */
9+
10+
private final NoteSensorSubsystem m_noteSensorSub;
11+
12+
public GetNoteStatus(NoteSensorSubsystem noteSensorSub) {
13+
this.m_noteSensorSub = noteSensorSub;
14+
addRequirements(noteSensorSub);
15+
}
16+
17+
@Override
18+
public void initialize() {
19+
// Code to run when the command is first initialized
20+
}
21+
22+
@Override
23+
public void execute() {
24+
// Code to run repeatedly while the command is scheduled to run
25+
m_noteSensorSub.isNoteLoaded();
26+
}
27+
28+
@Override
29+
public void end(boolean interrupted) {
30+
// Code to run when the command ends or is interrupted
31+
}
32+
33+
@Override
34+
public boolean isFinished() {
35+
// Return true when the command should end
36+
return false;
37+
}
38+
39+
} // end of class GetNoteStatus
Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,5 @@
1+
package frc.robot.subsystems;
2+
3+
public class ArmSubsytem {
4+
5+
}

src/main/java/frc/robot/subsystems/IntakeSubsystem.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -27,7 +27,7 @@ public IntakeSubsystem() {
2727
dutyCycle = new DutyCycleOut(0);
2828
motor.setControl(dutyCycle);
2929

30-
sensor = new TimeOfFlight(Constants.CANIDs.TIME_OF_FLIGHT_ID);
30+
sensor = new TimeOfFlight(Constants.CANIDs.NOTE_SENSOR_ID);
3131
// Every 20ms it updates ()
3232
sensor.setRangingMode(RangingMode.Short, 1);
3333
}

src/main/java/frc/robot/subsystems/RatioMotorSubsystem.java renamed to src/main/java/frc/robot/subsystems/LauncherSubsystem.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
* Set configs before creating this class/subsystem.
1313
* {@link #SetStatePower} is used to set the main power.
1414
*/
15-
public class RatioMotorSubsystem extends SubsystemBase {
15+
public class LauncherSubsystem extends SubsystemBase {
1616
/** As opposed to double */
1717
private boolean singleMotor;
1818
private TalonFX m_main;
@@ -34,7 +34,7 @@ public class RatioMotorSubsystem extends SubsystemBase {
3434
* Set configs before creating this class/subsystem.
3535
* {@link #SetStatePower} is used to set the main power.
3636
*/
37-
public RatioMotorSubsystem(TalonFX main, TalonFX sub) {
37+
public LauncherSubsystem(TalonFX main, TalonFX sub) {
3838

3939
singleMotor = false;
4040
this.m_main = main;
@@ -51,7 +51,7 @@ public RatioMotorSubsystem(TalonFX main, TalonFX sub) {
5151
* Set configs before creating this class/subsystem.
5252
* {@link #SetStatePower} is used to set the main power.
5353
*/
54-
public RatioMotorSubsystem(TalonFX only) {
54+
public LauncherSubsystem(TalonFX only) {
5555

5656
this.m_main = only;
5757
singleMotor = true;

src/main/java/frc/robot/subsystems/LedSubsystem.java

Lines changed: 66 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -4,10 +4,73 @@
44
* It will be use data from the Time of Flight sensor data (NoteSensorSubsystem) for determining the load status/position of a 'note'
55
* It is also partially cosmetic
66
*/
7-
public class LedSubsystem {
7+
8+
/*
9+
CANdle requires the Phoenix (v5) vendordep
10+
https://maven.ctr-electronics.com/release/com/ctre/phoenix/Phoenix5-frc2024-latest.json
11+
12+
com.ctre.phoenix.led.CANdle Class Reference
13+
https://api.ctr-electronics.com/phoenix/release/java/
14+
*/
15+
16+
import com.ctre.phoenix.led.CANdle;
17+
import com.ctre.phoenix.led.CANdle.LEDStripType;
18+
import com.ctre.phoenix.led.CANdle.VBatOutputMode;
19+
import com.ctre.phoenix.led.CANdleConfiguration;
20+
21+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
22+
import frc.robot.Constants;
23+
24+
25+
public class LedSubsystem extends SubsystemBase{
26+
private final CANdle m_candle = new CANdle(Constants.CANIDs.NOTE_SENSOR_ID, "rio");
827

28+
/* Update once the LEDs are installed if using Animations */
29+
// private final int LedCount = 69;
30+
931
/* Constructor */
32+
//private AnimationTypes m_currentAnimation;
1033
public LedSubsystem() {
11-
}
34+
// this.joystick = joy;
35+
//changeAnimation(AnimationTypes.SetAll);
36+
CANdleConfiguration configAll = new CANdleConfiguration();
37+
configAll.statusLedOffWhenActive = true;
38+
configAll.disableWhenLOS = false;
39+
configAll.stripType = LEDStripType.GRB;
40+
configAll.brightnessScalar = 0.1;
41+
configAll.vBatOutputMode = VBatOutputMode.Modulated;
42+
m_candle.configAllSettings(configAll, 100);
43+
}
44+
45+
public double getVbat() { return m_candle.getBusVoltage(); }
46+
public double get5V() { return m_candle.get5VRailVoltage(); }
47+
public void configBrightness(double percent, LedSubsystem ledSubsystem) { m_candle.configBrightnessScalar(percent, 0); }
48+
public void configLos(boolean disableWhenLos) { m_candle.configLOSBehavior(disableWhenLos, 0); }
49+
public void configLedType(LEDStripType type) { m_candle.configLEDType(type, 0); }
50+
public void configStatusLedBehavior(boolean offWhenActive) { m_candle.configStatusLedState(offWhenActive, 0); }
51+
52+
public void ColorOrange (){
53+
m_candle.setLEDs(255,60,0) ;
54+
}
55+
public void ColorRed (){
56+
m_candle.setLEDs(255,0,0) ;
57+
}
58+
public void ColorGreen (){
59+
m_candle.setLEDs(0,255,0) ;
60+
}
61+
public void ColorBlue (){
62+
m_candle.setLEDs(0,0,255) ;
63+
}
64+
65+
/*******************************
66+
Color | RGB Values
67+
----------------------------
68+
Red | (255, 0, 0)
69+
Green | (0, 255, 0)
70+
Blue | (0, 0, 255)
71+
Orange | (255, 165, 0)
72+
Dark Orange | (255, 60,0)
73+
74+
********************************/
1275

13-
} // end of class LedSubsystem
76+
} // end of class LedSubsystem

src/main/java/frc/robot/subsystems/NoteSensorSubsystem.java

Lines changed: 66 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,12 +2,77 @@
22

33
/* Subsystem class to primarily use a Time of Flight sensor from 'Playing with Fusion'.
44
* It will read the distance from the sensor to the 'note' and determine if the note is in a load position.
5+
* It should return an actual distance reading to the SmartDashboard and a boolean for a method 'isNoteLoaded'
56
* This sensor data will change LED status and enable/disable intake and index motors
67
*/
7-
public class NoteSensorSubsystem {
8+
9+
import edu.wpi.first.wpilibj2.command.SubsystemBase;
10+
11+
import com.playingwithfusion.TimeOfFlight;
12+
import com.playingwithfusion.TimeOfFlight.RangingMode;
13+
14+
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
15+
import frc.robot.Constants;
16+
17+
public class NoteSensorSubsystem extends SubsystemBase{
818

19+
/* Set ID in web interface http://172.22.11.2:5812/ */
20+
private TimeOfFlight noteDistance = new TimeOfFlight(Constants.CANIDs.NOTE_SENSOR_ID);
21+
22+
/*
23+
* This line declares a private instance variable called `m_ledSubsystem` of type `LedSubsystem`
24+
* It is initialized with a new instance of the `LedSubsystem` class
25+
* It is needed to control the LEDs based on the method `isNoteLoaded()`
26+
*/
27+
private LedSubsystem m_ledSubsystem = new LedSubsystem();
28+
29+
/* Set the distance to the note to be considered load position.'
30+
Measure in (mm) to determine an appropriate value.*/
31+
public int noteDistanceCheck = 100;
32+
933
/* Constructor */
1034
public NoteSensorSubsystem() {
35+
/* Initialize the sensor, and '.setRangingMode(RangingMode.Short)' for this usage.
36+
*
37+
| Sample value | Time |
38+
|---------------|--------|
39+
| 1 | 20 ms |
40+
| 2 | 33 ms |
41+
| 3 | 50 ms |
42+
| 4 (default) | 100 ms |
43+
| 5 | 200 ms |
44+
*****************************/
45+
noteDistance.setRangingMode(RangingMode.Short,0.5);
46+
}
47+
48+
public double getNoteDistance() {
49+
/* Gets the distance from the sensor to the nearest edge of the note*/
50+
return noteDistance.getRange(); // return NoteDistance.
51+
}
52+
53+
public boolean isNoteLoaded() {
54+
/* Returns true if the note is loaded, false if not */
55+
return noteDistance.getRange() < noteDistanceCheck ; // return NoteDistance.
56+
}
57+
58+
public void setLEDColor() {
59+
/* Set the LED color based on the note position.
60+
* Requires 'isNoteLoadeded' value and two led methods */
61+
if (isNoteLoaded() == true) {
62+
// SetColor decide loaded color
63+
m_ledSubsystem.ColorGreen();
64+
65+
} else if (isNoteLoaded() == false) {
66+
//SetColor decide UnLoaded color
67+
m_ledSubsystem.ColorRed();
68+
}
69+
}
70+
71+
public void periodic() {
72+
// This method will be called once per scheduler run
73+
// It did not seem to be called on the dashboard until I added a Command to the RobotContainer, but it would display updated data even when the button was not pressed.
74+
SmartDashboard.putNumber("Note Distance", noteDistance.getRange());
75+
SmartDashboard.putBoolean("Note Loaded", isNoteLoaded());
1176
}
1277

1378
} // end of class NoteSensorSubsystem

src/main/java/frc/robot/subsystems/PulleySubsystem.java renamed to src/main/java/frc/robot/subsystems/WinchSubsystem.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,11 +10,11 @@
1010
/**
1111
* Made of a motor, connected to a pulley. Contains manual drive for now.
1212
*/
13-
public class PulleySubsystem extends SubsystemBase {
13+
public class WinchSubsystem extends SubsystemBase {
1414
private TalonFX m_motor;
1515
private DutyCycleOut controlRequest;
1616

17-
public PulleySubsystem(TalonFX motor) {
17+
public WinchSubsystem(TalonFX motor) {
1818
m_motor = motor;
1919
controlRequest = new DutyCycleOut(0);
2020
m_motor.setControl(controlRequest);

0 commit comments

Comments
 (0)