RedCrab: Use common engine subclass, fixed MoveToCoordinate ONLY rotating with there's rotation set, LED stuff.

This commit is contained in:
2024-01-31 09:08:35 -06:00
parent 4980caf0c2
commit 688ccdf70e
11 changed files with 32 additions and 42 deletions

View File

@@ -88,6 +88,7 @@ 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;
@@ -254,8 +255,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 +270,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

View File

@@ -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);

View File

@@ -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);

View File

@@ -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);

View File

@@ -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);

View File

@@ -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);

View File

@@ -4,7 +4,7 @@ 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 {
public abstract class RedCrabEngine extends CyberarmEngine {
protected RedCrabMinibot robot;
@Override
@@ -19,4 +19,11 @@ public abstract class RedCrabAutonomousEngine extends CyberarmEngine {
if (robot != null)
robot.standardTelemetry();
}
@Override
public void stop() {
robot.shutdown();
super.stop();
}
}

View File

@@ -10,7 +10,7 @@ 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();
@@ -30,18 +30,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();
}
}

View File

@@ -9,7 +9,7 @@ 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);
@@ -18,14 +18,4 @@ public class RedCrabTeleOpEngine extends CyberarmEngine {
addState(new Pilot(robot));
}
@Override
public void loop() {
Utilities.hubsClearBulkReadCache(hardwareMap);
if (RedCrabMinibot.localizer != null) {
RedCrabMinibot.localizer.integrate();
}
super.loop();
}
}

View File

@@ -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);