Skip to content

Commit

Permalink
Merge pull request #69 from CyberCoyotes/noteSubsystem-01-24
Browse files Browse the repository at this point in the history
Note subsystem 01 24
  • Loading branch information
JediScoy authored Jan 26, 2024
2 parents 866738f + 68fd8e3 commit a1d1dfd
Show file tree
Hide file tree
Showing 2 changed files with 46 additions and 11 deletions.
35 changes: 33 additions & 2 deletions src/main/java/frc/robot/commands/GetNoteStatus.java
Original file line number Diff line number Diff line change
@@ -1,8 +1,39 @@
package frc.robot.commands;

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

/* 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' */
public class GetNoteStatus extends Command {

}
/* */

private final NoteSensorSubsystem m_noteSensorSub;

public GetNoteStatus(NoteSensorSubsystem noteSensorSub) {
this.m_noteSensorSub = noteSensorSub;
addRequirements(noteSensorSub);
}

@Override
public void initialize() {
// Code to run when the command is first initialized
}

@Override
public void execute() {
// Code to run repeatedly while the command is scheduled to run
m_noteSensorSub.isNoteLoaded();
}

@Override
public void end(boolean interrupted) {
// Code to run when the command ends or is interrupted
}

@Override
public boolean isFinished() {
// Return true when the command should end
return false;
}

} // end of class GetNoteStatus
22 changes: 13 additions & 9 deletions src/main/java/frc/robot/subsystems/NoteSensorSubsystem.java
Original file line number Diff line number Diff line change
@@ -1,24 +1,29 @@
package frc.robot.subsystems;

/* Subsystem class to primarily use a Time of Flight sensor from 'Playing with Fusion'.
* It will read the distance from the sensor to the 'note' and determine if the note is in a load position.
* It should return an actual distance reading to the SmartDashboard and a boolean for a method 'isNoteLoaded'
* This sensor data will change LED status and enable/disable intake and index motors
*/

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

import com.playingwithfusion.TimeOfFlight;
import com.playingwithfusion.TimeOfFlight.RangingMode;

import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.SubsystemBase;
import frc.robot.Constants;

/* Subsystem class to primarily use a Time of Flight sensor from 'Playing with Fusion'.
* It will read the distance from the sensor to the 'note' and determine if the note is in a load position.
* This sensor data will change LED status and enable/disable intake and index motors
*/
public class NoteSensorSubsystem extends SubsystemBase {
/* Set ID in web interface http://172.22.11.2:5812/ */
public class NoteSensorSubsystem extends SubsystemBase{

/* Set ID in web interface http://172.22.11.2:5812/ */
private TimeOfFlight sensorNoteDistance = new TimeOfFlight(Constants.CANIDs.timeOfFlightID);

/* Set the distance to the note to be considered 'in load position.'
Measure in (mm) to determine an appropriate value.*/
public int noteDistanceCheck = 0;

/* Constructor */
public NoteSensorSubsystem() {
/* Initialize the sensor, and '.setRangingMode(RandingMode.short)' for this usage.
Expand Down Expand Up @@ -48,13 +53,12 @@ public void setLEDColor() {
* Requires 'isNoteLoadeded' value and two led methods */

}


public void periodic() {
// This method will be called once per scheduler run
// 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.
SmartDashboard.putNumber("Note Distance", sensorNoteDistance.getRange());
SmartDashboard.putBoolean("Note Loaded", isNoteLoaded());
}

} // end of class NoteSensorSubsystem

0 comments on commit a1d1dfd

Please sign in to comment.