Skip to content

Commit

Permalink
Merge pull request #53 from WHS-FRC-3467/add-coastmode-to-dash
Browse files Browse the repository at this point in the history
added coast and brake commands to dashboard, along with match timer
  • Loading branch information
Noah-H3467 authored Feb 17, 2025
2 parents 1abe5d2 + f94f78f commit ed16d7e
Show file tree
Hide file tree
Showing 4 changed files with 192 additions and 9 deletions.
161 changes: 157 additions & 4 deletions Elastic Json/3467_Elastic_V2.json
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,8 @@
"type": "Camera Stream",
"properties": {
"topic": "/CameraPublisher/front_left-raw",
"period": 0.06
"period": 0.06,
"rotation_turns": 0
}
},
{
Expand All @@ -121,7 +122,8 @@
"type": "Camera Stream",
"properties": {
"topic": "/CameraPublisher/front_right-raw",
"period": 0.06
"period": 0.06,
"rotation_turns": 0
}
},
{
Expand Down Expand Up @@ -206,7 +208,8 @@
"type": "Camera Stream",
"properties": {
"topic": "/CameraPublisher/front_left-processed",
"period": 0.06
"period": 0.06,
"rotation_turns": 0
}
},
{
Expand All @@ -218,7 +221,8 @@
"type": "Camera Stream",
"properties": {
"topic": "/CameraPublisher/front_right-processed",
"period": 0.06
"period": 0.06,
"rotation_turns": 0
}
},
{
Expand Down Expand Up @@ -1728,6 +1732,155 @@
}
]
}
},
{
"name": "Pit",
"grid_layout": {
"layouts": [
{
"title": "ClawRollerLaserCAN",
"x": 950.0,
"y": 300.0,
"width": 300.0,
"height": 150.0,
"type": "List Layout",
"properties": {
"label_position": "TOP"
},
"children": [
{
"title": "Distance",
"x": 0.0,
"y": 0.0,
"width": 150.0,
"height": 150.0,
"type": "Text Display",
"properties": {
"topic": "/AdvantageKit/ClawRollerLaserCAN/Distance",
"period": 0.06,
"data_type": "double",
"show_submit_button": false
}
}
]
},
{
"title": "IntakeLaserCAN",
"x": 650.0,
"y": 300.0,
"width": 300.0,
"height": 150.0,
"type": "List Layout",
"properties": {
"label_position": "TOP"
},
"children": [
{
"title": "Distance",
"x": 0.0,
"y": 0.0,
"width": 150.0,
"height": 150.0,
"type": "Text Display",
"properties": {
"topic": "/AdvantageKit/IntakeLaserCAN/Distance",
"period": 0.06,
"data_type": "double",
"show_submit_button": false
}
}
]
}
],
"containers": [
{
"title": "Elevator Coast Command",
"x": 650.0,
"y": 0.0,
"width": 300.0,
"height": 150.0,
"type": "Command",
"properties": {
"topic": "/SmartDashboard/Elevator Coast Command",
"period": 0.06,
"show_type": false
}
},
{
"title": "Arm Coast Command",
"x": 950.0,
"y": 0.0,
"width": 300.0,
"height": 150.0,
"type": "Command",
"properties": {
"topic": "/SmartDashboard/Arm Coast Command",
"period": 0.06,
"show_type": false
}
},
{
"title": "Arm Brake Command",
"x": 950.0,
"y": 150.0,
"width": 300.0,
"height": 150.0,
"type": "Command",
"properties": {
"topic": "/SmartDashboard/Arm Brake Command",
"period": 0.06,
"show_type": false
}
},
{
"title": "Elevator Brake Command",
"x": 650.0,
"y": 150.0,
"width": 300.0,
"height": 150.0,
"type": "Command",
"properties": {
"topic": "/SmartDashboard/Elevator Brake Command",
"period": 0.06,
"show_type": false
}
},
{
"title": "Triggered",
"x": 950.0,
"y": 450.0,
"width": 300.0,
"height": 100.0,
"type": "Boolean Box",
"properties": {
"topic": "/AdvantageKit/RealOutputs/ClawRollerLaserCAN/Triggered",
"period": 0.06,
"data_type": "boolean",
"true_color": 4283215696,
"false_color": 4294198070,
"true_icon": "None",
"false_icon": "None"
}
},
{
"title": "Triggered",
"x": 650.0,
"y": 450.0,
"width": 300.0,
"height": 100.0,
"type": "Boolean Box",
"properties": {
"topic": "/AdvantageKit/RealOutputs/IntakeLaserCAN/Triggered",
"period": 0.06,
"data_type": "boolean",
"true_color": 4283215696,
"false_color": 4294198070,
"true_icon": "None",
"false_icon": "None"
}
}
]
}
}
]
}
6 changes: 3 additions & 3 deletions src/main/java/frc/robot/Robot.java
Original file line number Diff line number Diff line change
Expand Up @@ -134,15 +134,15 @@ public void robotPeriodic()
// Return to normal thread priority
Threads.setCurrentThreadPriority(false, 10);

Logger.recordOutput("ZeroedCompPoses", new Pose3d());
SmartDashboard.putNumber("Match Time", DriverStation.getMatchTime());
}

/** This function is called once when the robot is disabled. */
@Override
public void disabledInit()
{
m_robotContainer.resetSimulationField();
Elastic.selectTab(1);
Elastic.selectTab(0);
SmartDashboard.putData("Auto Path Preview", m_autoTraj);
}

Expand Down Expand Up @@ -190,7 +190,7 @@ public void teleopInit()
if (m_autonomousCommand != null) {
m_autonomousCommand.cancel();
}
Elastic.selectTab(2);
Elastic.selectTab(1);
}

/** This function is called periodically during operator control. */
Expand Down
17 changes: 16 additions & 1 deletion src/main/java/frc/robot/subsystems/Arm/Arm.java
Original file line number Diff line number Diff line change
Expand Up @@ -4,6 +4,7 @@
import org.littletonrobotics.junction.Logger;
import edu.wpi.first.math.util.Units;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import frc.robot.subsystems.GenericMotionProfiledSubsystem.GenericMotionProfiledSubsystem;
Expand Down Expand Up @@ -41,7 +42,9 @@ public enum State implements TargetState {
BARGE(() -> Units.degreesToRotations(30.0), ProfileType.MM_POSITION),
TUNING(() -> Units.degreesToRotations(positionTuning.getAsDouble()),
ProfileType.MM_POSITION),
CHARACTERIZATION(() -> 0.0, ProfileType.CHARACTERIZATION);
CHARACTERIZATION(() -> 0.0, ProfileType.CHARACTERIZATION),
COAST(() -> 0.0, ProfileType.DISABLED_COAST),
BRAKE(() -> 0.0, ProfileType.DISABLED_BRAKE);

private final DoubleSupplier output;
private final ProfileType profileType;
Expand All @@ -60,6 +63,8 @@ public enum State implements TargetState {
public Arm(ArmIO io, boolean isSim)
{
super(ProfileType.MM_POSITION, ArmConstants.kSubSysConstants, io, isSim);
SmartDashboard.putData("Arm Coast Command", setCoastStateCommand());
SmartDashboard.putData("Arm Brake Command", setBrakeStateCommand());
}

/** Constructor */
Expand All @@ -68,6 +73,16 @@ public Command setStateCommand(State state)
return this.runOnce(() -> this.state = state);
}

public Command setCoastStateCommand()
{
return this.runOnce(() -> this.state = State.COAST);
}

public Command setBrakeStateCommand()
{
return this.runOnce(() -> this.state = State.BRAKE);
}

public boolean atPosition(double tolerance)
{
return io.atPosition(tolerance);
Expand Down
17 changes: 16 additions & 1 deletion src/main/java/frc/robot/subsystems/Elevator/Elevator.java
Original file line number Diff line number Diff line change
Expand Up @@ -6,6 +6,7 @@
import edu.wpi.first.math.filter.Debouncer.DebounceType;
import edu.wpi.first.wpilibj.Alert;
import edu.wpi.first.wpilibj.Timer;
import edu.wpi.first.wpilibj.smartdashboard.SmartDashboard;
import edu.wpi.first.wpilibj2.command.Command;
import edu.wpi.first.wpilibj2.command.Commands;
import edu.wpi.first.wpilibj2.command.InstantCommand;
Expand Down Expand Up @@ -45,7 +46,9 @@ public enum State implements TargetState {
ALGAE_SCORE(() -> 0.05, ProfileType.MM_POSITION),
BARGE(() -> 4.0, ProfileType.MM_POSITION),
TUNING(() -> positionTuning.getAsDouble(), ProfileType.MM_POSITION),
CHARACTERIZATION(() -> 0.0, ProfileType.CHARACTERIZATION);
CHARACTERIZATION(() -> 0.0, ProfileType.CHARACTERIZATION),
COAST(() -> 0.0, ProfileType.DISABLED_COAST),
BRAKE(() -> 0.0, ProfileType.DISABLED_BRAKE);

private final DoubleSupplier output;
private final ProfileType profileType;
Expand All @@ -66,13 +69,25 @@ public enum State implements TargetState {
public Elevator(ElevatorIO io, boolean isSim)
{
super(ProfileType.MM_POSITION, ElevatorConstants.kSubSysConstants, io, isSim);
SmartDashboard.putData("Elevator Coast Command", setCoastStateCommand());
SmartDashboard.putData("Elevator Brake Command", setBrakeStateCommand());
}

public Command setStateCommand(State state)
{
return this.runOnce(() -> this.state = state);
}

public Command setCoastStateCommand()
{
return this.runOnce(() -> this.state = State.COAST);
}

public Command setBrakeStateCommand()
{
return this.runOnce(() -> this.state = State.BRAKE);
}

private Debouncer homedDebouncer = new Debouncer(.25, DebounceType.kRising);

public Trigger homedTrigger =
Expand Down

0 comments on commit ed16d7e

Please sign in to comment.