mirror of
https://github.com/TimeCrafters/CenterStage
synced 2025-12-15 08:42:35 +00:00
Compare commits
2 Commits
4980caf0c2
...
1c71771034
| Author | SHA1 | Date | |
|---|---|---|---|
| 1c71771034 | |||
| 688ccdf70e |
@@ -41,6 +41,8 @@ public abstract class CyberarmEngine extends OpMode {
|
||||
private GamepadChecker gamepadCheckerGamepad1, gamepadCheckerGamepad2;
|
||||
private boolean useThreads = true;
|
||||
|
||||
private long startTime;
|
||||
|
||||
/**
|
||||
* Called when INIT button on Driver Station is pushed
|
||||
* ENSURE to call super.init() if you override this method
|
||||
@@ -84,6 +86,8 @@ public abstract class CyberarmEngine extends OpMode {
|
||||
* ENSURE to call super.start() if you override this method
|
||||
*/
|
||||
public void start() {
|
||||
startTime = System.currentTimeMillis();
|
||||
|
||||
if (cyberarmStates.size() > 0) {
|
||||
runState(cyberarmStates.get(0));
|
||||
}
|
||||
@@ -534,4 +538,12 @@ public abstract class CyberarmEngine extends OpMode {
|
||||
public void threadless() {
|
||||
useThreads = false;
|
||||
}
|
||||
|
||||
/**
|
||||
* Time in milliseconds since START button was pushed
|
||||
* @return runTime
|
||||
*/
|
||||
public double runTime() {
|
||||
return (System.currentTimeMillis() - startTime);
|
||||
}
|
||||
}
|
||||
|
||||
@@ -88,8 +88,10 @@ public class RedCrabMinibot {
|
||||
public final DcMotorEx deadWheelXLeft, deadWheelXRight;
|
||||
public final EncoderCustomKB2040 deadWheelYCenter;
|
||||
public final DigitalChannel greenLED, redLED;
|
||||
public final boolean LED_OFF = true, LED_ON = false;
|
||||
|
||||
final CyberarmEngine engine;
|
||||
public final boolean autonomous;
|
||||
|
||||
public TimeCraftersConfiguration config;
|
||||
private final PIDFController clawArmPIDFController;
|
||||
@@ -124,6 +126,7 @@ public class RedCrabMinibot {
|
||||
|
||||
public RedCrabMinibot(boolean autonomous) {
|
||||
engine = CyberarmEngine.instance;
|
||||
this.autonomous = autonomous;
|
||||
|
||||
config = new TimeCraftersConfiguration("cyberarm_RedCrab");
|
||||
loadConstants();
|
||||
@@ -254,8 +257,8 @@ public class RedCrabMinibot {
|
||||
|
||||
greenLED.setMode(DigitalChannel.Mode.OUTPUT);
|
||||
redLED.setMode(DigitalChannel.Mode.OUTPUT);
|
||||
greenLED.setState(true);
|
||||
redLED.setState(true);
|
||||
greenLED.setState(LED_OFF);
|
||||
redLED.setState(LED_ON);
|
||||
|
||||
// Bulk read from hubs
|
||||
Utilities.hubsBulkReadMode(engine.hardwareMap, LynxModule.BulkCachingMode.MANUAL);
|
||||
@@ -269,6 +272,12 @@ public class RedCrabMinibot {
|
||||
RedCrabMinibot.localizer.reset();
|
||||
}
|
||||
|
||||
public void shutdown() {
|
||||
// Prevent LED(s) from being on while idle
|
||||
greenLED.setMode(DigitalChannel.Mode.INPUT);
|
||||
redLED.setMode(DigitalChannel.Mode.INPUT);
|
||||
}
|
||||
|
||||
public void reloadConfig() {
|
||||
config = new TimeCraftersConfiguration("cyberarm_RedCrab");
|
||||
|
||||
|
||||
File diff suppressed because one or more lines are too long
@@ -4,12 +4,11 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab BLUE AUDIENCE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousBlueAudienceEngine extends RedCrabAutonomousEngine {
|
||||
public class RedCrabAutonomousBlueAudienceEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
|
||||
@@ -4,12 +4,11 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab BLUE BACKSTAGE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousBlueBackstageEngine extends RedCrabAutonomousEngine {
|
||||
public class RedCrabAutonomousBlueBackstageEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
|
||||
@@ -8,7 +8,7 @@ import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab Auto DEBUGGING", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousDebuggingOnlyEngine extends RedCrabAutonomousEngine {
|
||||
public class RedCrabAutonomousDebuggingOnlyEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
|
||||
@@ -1,22 +0,0 @@
|
||||
package dev.cyberarm.minibots.red_crab.engines;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.engine.V2.Utilities;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
|
||||
public abstract class RedCrabAutonomousEngine extends CyberarmEngine {
|
||||
protected RedCrabMinibot robot;
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
Utilities.hubsClearBulkReadCache(hardwareMap);
|
||||
if (RedCrabMinibot.localizer != null) {
|
||||
RedCrabMinibot.localizer.integrate();
|
||||
}
|
||||
|
||||
super.loop();
|
||||
|
||||
if (robot != null)
|
||||
robot.standardTelemetry();
|
||||
}
|
||||
}
|
||||
@@ -4,12 +4,11 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab RED AUDIENCE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousRedAudienceEngine extends RedCrabAutonomousEngine {
|
||||
public class RedCrabAutonomousRedAudienceEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
|
||||
@@ -4,12 +4,11 @@ import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
|
||||
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab RED BACKSTAGE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousRedBackstageEngine extends RedCrabAutonomousEngine {
|
||||
public class RedCrabAutonomousRedBackstageEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
|
||||
@@ -0,0 +1,52 @@
|
||||
package dev.cyberarm.minibots.red_crab.engines;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.engine.V2.Utilities;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
|
||||
public abstract class RedCrabEngine extends CyberarmEngine {
|
||||
protected RedCrabMinibot robot;
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
Utilities.hubsClearBulkReadCache(hardwareMap);
|
||||
if (RedCrabMinibot.localizer != null) {
|
||||
RedCrabMinibot.localizer.integrate();
|
||||
}
|
||||
|
||||
super.loop();
|
||||
|
||||
robot.standardTelemetry();
|
||||
|
||||
if (robot.autonomous) {
|
||||
if (runTime() < 20_000.0) { // KEEP CALM and CARRY ON
|
||||
robot.redLED.setState(robot.LED_OFF);
|
||||
robot.greenLED.setState(robot.LED_ON);
|
||||
} else if (runTime() < 25_000.0) { // RUNNING LOW ON TIME
|
||||
robot.redLED.setState(robot.LED_ON);
|
||||
robot.greenLED.setState(robot.LED_ON);
|
||||
} else { // 5 SECONDS LEFT!
|
||||
robot.redLED.setState(robot.LED_ON);
|
||||
robot.greenLED.setState(robot.LED_OFF);
|
||||
}
|
||||
} else {
|
||||
if (runTime() >= 90_000.0) { // LAUNCH DRONE and DO CHIN UP
|
||||
robot.redLED.setState(robot.LED_OFF);
|
||||
robot.greenLED.setState(robot.LED_ON);
|
||||
} else if (runTime() >= 80_000.0) { // GET READY
|
||||
robot.redLED.setState(robot.LED_ON);
|
||||
robot.greenLED.setState(robot.LED_ON);
|
||||
} else { // KEEP CALM and CARRY ON
|
||||
robot.redLED.setState(robot.LED_ON);
|
||||
robot.greenLED.setState(robot.LED_OFF);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void stop() {
|
||||
robot.shutdown();
|
||||
|
||||
super.stop();
|
||||
}
|
||||
}
|
||||
@@ -10,13 +10,14 @@ import dev.cyberarm.engine.V2.Utilities;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
|
||||
@TeleOp(name = "Cyberarm Red Crab TeleOp DEBUGGING", group = "MINIBOT")
|
||||
public class RedCrabTeleOpDebuggingOnlyEngine extends CyberarmEngine {
|
||||
public class RedCrabTeleOpDebuggingOnlyEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
threadless();
|
||||
|
||||
robot = new RedCrabMinibot(false);
|
||||
|
||||
addState(new CyberarmState() {
|
||||
final RedCrabMinibot robot = new RedCrabMinibot(false);
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
@@ -30,18 +31,6 @@ public class RedCrabTeleOpDebuggingOnlyEngine extends CyberarmEngine {
|
||||
robot.clawArm.setMode(DcMotor.RunMode.RUN_WITHOUT_ENCODER);
|
||||
robot.clawArm.setPower(-engine.gamepad1.left_stick_y * 0.5);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void telemetry() {
|
||||
robot.standardTelemetry();
|
||||
}
|
||||
});
|
||||
}
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
Utilities.hubsClearBulkReadCache(hardwareMap);
|
||||
|
||||
super.loop();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -9,23 +9,13 @@ import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.Pilot;
|
||||
|
||||
@TeleOp(name = "Cyberarm Red Crab TeleOp", group = "MINIBOT")
|
||||
public class RedCrabTeleOpEngine extends CyberarmEngine {
|
||||
public class RedCrabTeleOpEngine extends RedCrabEngine {
|
||||
@Override
|
||||
public void setup() {
|
||||
RedCrabMinibot robot = new RedCrabMinibot(false);
|
||||
robot = new RedCrabMinibot(false);
|
||||
|
||||
addTask(new ClawArmTask(robot));
|
||||
|
||||
addState(new Pilot(robot));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
Utilities.hubsClearBulkReadCache(hardwareMap);
|
||||
if (RedCrabMinibot.localizer != null) {
|
||||
RedCrabMinibot.localizer.integrate();
|
||||
}
|
||||
|
||||
super.loop();
|
||||
}
|
||||
}
|
||||
|
||||
@@ -22,6 +22,7 @@ public class MoveToCoordinate extends CyberarmState {
|
||||
private double distanceFromTargetMM = 0;
|
||||
private double velocity = 0;
|
||||
private double angleDiffDegrees = 0;
|
||||
private double rotationStrength = 0;
|
||||
|
||||
public MoveToCoordinate(RedCrabMinibot robot, String groupName, String actionName) {
|
||||
this.robot = robot;
|
||||
@@ -85,10 +86,11 @@ public class MoveToCoordinate extends CyberarmState {
|
||||
}
|
||||
|
||||
private void drivetrain(Vector2D direction) {
|
||||
double rotationStrength = Utilities.lerp(
|
||||
minVelocityMM,
|
||||
maxVelocityMM,
|
||||
Range.clip(Math.abs(angleDiffDegrees) / lerpDegrees, 0.0, 1.0));
|
||||
// rotationStrength = Utilities.lerp(
|
||||
// minVelocityMM,
|
||||
// maxVelocityMM,
|
||||
// Range.clip(Math.abs(angleDiffDegrees) / lerpDegrees, 0.0, 1.0));
|
||||
rotationStrength = Range.clip(Math.abs(angleDiffDegrees) / lerpDegrees, 0.0, 1.0);
|
||||
if (angleDiffDegrees < 0)
|
||||
rotationStrength *= -1;
|
||||
|
||||
@@ -153,7 +155,7 @@ public class MoveToCoordinate extends CyberarmState {
|
||||
public void telemetry() {
|
||||
engine.telemetry.addData("Current Position MM", "X: %.2f Y: %.2f", robotPosMM.x(), robotPosMM.y());
|
||||
engine.telemetry.addData("Target Position MM", "X: %.2f Y: %.2f", targetPosMM.x(), targetPosMM.y());
|
||||
engine.telemetry.addData("Move NORMAL", "X: %.2f Y: %.2f", direction.x(), direction.y());
|
||||
engine.telemetry.addData("Move NORMAL", "X: %.2f Y: %.2f R: %.2f", direction.x(), direction.y(), rotationStrength);
|
||||
engine.telemetry.addData("Distance MM", "%.2fmm", distanceFromTargetMM);
|
||||
engine.telemetry.addData("Angle Diff DEGREES", "%.2f degrees", angleDiffDegrees);
|
||||
// engine.telemetry.addData("Velocity", "%.2f T/s", velocity);
|
||||
|
||||
@@ -130,11 +130,6 @@ public class Pilot extends CyberarmState {
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void telemetry() {
|
||||
robot.standardTelemetry();
|
||||
}
|
||||
|
||||
private void drivetrain() {
|
||||
// https://gm0.org/en/latest/docs/software/tutorials/mecanum-drive.html#field-centric
|
||||
|
||||
|
||||
Reference in New Issue
Block a user