Skip to content

Commit

Permalink
changes at competition
Browse files Browse the repository at this point in the history
  • Loading branch information
EdzmLeGoat committed Mar 3, 2025
1 parent 25bcfb1 commit abdf468
Show file tree
Hide file tree
Showing 12 changed files with 189 additions and 151 deletions.
4 changes: 3 additions & 1 deletion src/main/deploy/autoscore/reefPlacement.js
Original file line number Diff line number Diff line change
Expand Up @@ -32,7 +32,9 @@ const confirmReefButton = document.getElementById("confirmReefButton");

["touchend", "mouseleave"].forEach(_ => {
locationImg.addEventListener(_, () => {
locationImg.src = "locationSelectorImages/locationSelectorNone.png";
if(!areaSelected) {
locationImg.src = "locationSelectorImages/locationSelectorNone.png";
}
});
});

Expand Down
36 changes: 24 additions & 12 deletions src/main/deploy/autoscore/robotCommunication.js
Original file line number Diff line number Diff line change
Expand Up @@ -46,6 +46,20 @@ function valueUpdateHandler( topic, timestamp_us, value ) {
console.log("value updated: " + topic.name);
if(topic.name == "/webcom/Alliance") {
setAlliance(value);
} else if(topic.name == "/webcom/isDone" && value===true) {
document.getElementById("manualText").innerText = `Scoring on Area ${numberToLetter[11-(reefArea+4)%12]} and Level ${coralLevel}`;
showContainer("manualContainer");
["pivotForward", "pivotBack", "elevatorUp", "elevatorDown", "wristForward", "wristBack"].forEach(
id => {
const elt = document.getElementById(id);
const eltinterval = setInterval(() => {
if(window.getComputedStyle(elt).backgroundColor == "rgb(200, 0, 0)") {
setCommand(id);
}
}, 0.02);
intervalList.push(eltinterval);
}
);
}
}

Expand Down Expand Up @@ -97,8 +111,9 @@ let coralLevel = -1;
let reefArea = -1;
let coralSelected = false;
let areaSelected = false;
let intervalList = [];

const resetReefStuff = () => {
const resetReef = () => {
coralSelected = false;
areaSelected = false;
coralLevel = -1;
Expand All @@ -108,12 +123,14 @@ const resetReefStuff = () => {
document.getElementById("areaText").innerText = "Reef Area: None";
document.getElementById("coralText").innerText = "Coral Level: None";
document.getElementById("locationSelect").src = "locationSelectorImages/locationSelectorNone.png";
intervalList.forEach(ivl => clearInterval(ivl));
intervalList.length = 0;
}

document.getElementById("confirmReefButton").onclick = async () => {
if(coralSelected && areaSelected) {
document.getElementById("manualText").innerText = `Scoring on Area ${numberToLetter[11-(reefArea+4)%12]} and Level ${coralLevel}`
showContainer("manualContainer");
scoreReef(reefArea, coralLevel);
document.getElementById("confirmReefButton").innerText = "Scoring...";
}
}

Expand All @@ -132,7 +149,6 @@ const scoreProcessor = async () => {
}

const intakeCoral = async (isAtTopSide) => {
console.log("intaking coral");
if(isAtTopSide) {
setCommand("intakeCoralTop");
} else {
Expand All @@ -145,11 +161,6 @@ const scoreReef = async (location, level) => {
setCommand(`l${level} location${location > 3 ? location-3 : location+9}`);
}

["pivotForward", "pivotBack", "elevatorUp", "elevatorDown", "wristForward", "wristBack"].forEach(
id => document.getElementById(id).onclick = () => {
setCommand(id);
});

const scoringContainer = document.querySelector(".scoringContainer");
const messageContainer = document.querySelector(".messageContainer");
const msgDisplay = document.getElementById("messageDisplay");
Expand All @@ -169,18 +180,19 @@ const connection = () => {
messageContainer.style.display = "none";
scoringContainer.style.display = "flex";
msgDisplay.innerText = "";
resetReef();
showContainer("reefContainer");
}

document.getElementById("cancel").onclick = () => {
setCommand("cancel");
resetReefStuff();
resetReef();
showContainer("reefContainer");
}

document.getElementById("score").onclick = () => {
scoreReef();
resetReefStuff();
setCommand("score");
resetReef();
showContainer("reefContainer");
}

Expand Down
5 changes: 4 additions & 1 deletion src/main/deploy/autoscore/style.css
Original file line number Diff line number Diff line change
Expand Up @@ -47,6 +47,8 @@ body {

.coralLevelImage {
width: 25%;
align-items: center;
align-content: center;
}

.reefText {
Expand Down Expand Up @@ -78,7 +80,7 @@ body {

#coral {
width: 100%;
height: 100%;
aspect-ratio: 0.5;
}

#locationSelect {
Expand Down Expand Up @@ -122,6 +124,7 @@ body {
justify-content: center;
text-align: center;
padding: 0 1vh;
user-select: none;
}

#confirmReefButton {
Expand Down
Original file line number Diff line number Diff line change
@@ -1,7 +1,6 @@
package frc.team449.commands.autoscoreCommands

import edu.wpi.first.math.geometry.Pose2d
import edu.wpi.first.math.kinematics.ChassisSpeeds
import edu.wpi.first.wpilibj.DriverStation
import edu.wpi.first.wpilibj.DriverStation.Alliance
import edu.wpi.first.wpilibj.RobotBase
Expand All @@ -13,9 +12,26 @@ import frc.team449.subsystems.superstructure.SuperstructureGoal

class AutoScoreCommands(private val robot: Robot) {
private var currentCommand: Command = InstantCommand()
private var scoreCommand: Command = InstantCommand()
var waitingForScore = false
private var moving = false

fun scoreCommand(): Command {
waitingForScore = false
return scoreCommand
}

fun currentCommandFinished(): Boolean {
if(!currentCommand.isScheduled && moving) {
moving = false
return true
}
return false
}

fun getReefCommand(rl: AutoScoreCommandConstants.ReefLocation, cl: AutoScoreCommandConstants.CoralLevel): Command {
return runOnce({
moving = true
val reefLocationPose =
if (DriverStation.getAlliance().get() == Alliance.Red) {
when (rl) {
Expand Down Expand Up @@ -62,64 +78,82 @@ class AutoScoreCommands(private val robot: Robot) {
}
robot.poseSubsystem.autoscoreCommandPose = reefLocationPose

val scoreCommand = if (!RobotBase.isSimulation()) {
scoreCommand = if (!RobotBase.isSimulation()) {
robot.superstructureManager.requestGoal(scoreGoal)
} else InstantCommand()
} else {
InstantCommand()
}

val premoveCommand = robot.superstructureManager.requestGoal(premoveGoal)

currentCommand =
AutoScoreWrapperCommand(
robot, AutoScorePathfinder(robot, reefLocationPose), premoveCommand
).andThen(InstantCommand({
scoreCommand.schedule()
robot.drive.defaultCommand = robot.driveCommand
}))
robot,
AutoScorePathfinder(robot, reefLocationPose),
premoveCommand
).andThen(
InstantCommand({
robot.drive.defaultCommand = robot.driveCommand
waitingForScore = true
})
)
currentCommand.schedule()
})
}

fun getProcessorCommand(): Command {
return runOnce({
moving = true
val processorPose = if (DriverStation.getAlliance().get() == Alliance.Red) AutoScoreCommandConstants.processorPoseRed else AutoScoreCommandConstants.processorPoseBlue
val scoreCommand = InstantCommand()
scoreCommand = InstantCommand()
val premoveCommand = InstantCommand()
robot.poseSubsystem.autoscoreCommandPose = processorPose
currentCommand =
AutoScoreWrapperCommand(
robot, AutoScorePathfinder(robot, processorPose), premoveCommand
).andThen(InstantCommand({
scoreCommand.schedule()
robot.drive.defaultCommand = robot.driveCommand
}))
robot,
AutoScorePathfinder(robot, processorPose),
premoveCommand
).andThen(
InstantCommand({
robot.drive.defaultCommand = robot.driveCommand
waitingForScore = true
})
)
currentCommand.schedule()
})
}

fun getNetCommand(atRedSide: Boolean): Command {
return runOnce({
moving = true
val netPose = Pose2d(
AutoScoreCommandConstants.centerOfField + AutoScoreCommandConstants.centerOfField * if (atRedSide) 1 else -1,
robot.poseSubsystem.pose.translation.y,
if (atRedSide) AutoScoreCommandConstants.netRotation2dRed else AutoScoreCommandConstants.netRotation2dBlue
)
val scoreCommand = InstantCommand()
scoreCommand = InstantCommand()
val premoveCommand = InstantCommand()
currentCommand =
AutoScoreWrapperCommand(
robot, AutoScorePathfinder(robot, netPose), premoveCommand
).andThen(InstantCommand({
scoreCommand.schedule()
robot.drive.defaultCommand = robot.driveCommand
}))
robot,
AutoScorePathfinder(robot, netPose),
premoveCommand
).andThen(
InstantCommand({
robot.drive.defaultCommand = robot.driveCommand
waitingForScore = true
})
)
currentCommand.schedule()
})
}

fun cancelCommand(): Command {
return InstantCommand({
moving = false
currentCommand.cancel()
robot.drive.defaultCommand = robot.driveCommand
waitingForScore = false
})
}
}
Loading

0 comments on commit abdf468

Please sign in to comment.