mirror of
https://github.com/TimeCrafters/CenterStage
synced 2025-12-12 23:32:36 +00:00
RedCrab: Moved Localizer updater into Task, corrected track width and forward offsets
This commit is contained in:
@@ -13,12 +13,12 @@ import dev.cyberarm.engine.V2.Utilities;
|
||||
public class Localizer {
|
||||
private final RedCrabMinibot robot;
|
||||
private double rawX = 0, rawY = 0, rawR = 0, offsetX = 0, offsetY = 0;
|
||||
private final double trackWidthMM = 365.0, forwardOffsetMM = 140.0, wheelDiameterMM = 90.0;
|
||||
private final double trackWidthMM = 387.35, forwardOffsetMM = 133.35, wheelDiameterMM = 90.0;
|
||||
private final int encoderTicksPerRevolution = 8192;
|
||||
private final double encoderGearRatio = 1;
|
||||
private double lastEncoderXLeftMM, lastEncoderXRightMM, lastEncoderYCenterMM;
|
||||
// private double xDeltaMultiplier = 0.87012987, yDeltaMultiplier = 0.25;
|
||||
private double xDeltaMultiplier = 1, yDeltaMultiplier = 1;
|
||||
private double xPosMultiplier = 0.675956739, yPosMultiplier = 0.941867531;
|
||||
private HolonomicOdometry odometry;
|
||||
public Localizer(RedCrabMinibot robot) {
|
||||
this.robot = robot;
|
||||
@@ -100,11 +100,11 @@ public class Localizer {
|
||||
}
|
||||
|
||||
public double xMM() {
|
||||
return odometry.getPose().getX() + offsetX; //rawX;
|
||||
return odometry.getPose().getX() * xPosMultiplier + offsetX; //rawX;
|
||||
}
|
||||
|
||||
public double yMM() {
|
||||
return odometry.getPose().getY() + offsetY; //rawY;
|
||||
return odometry.getPose().getY() * xPosMultiplier + offsetY; //rawY;
|
||||
}
|
||||
|
||||
public double xIn() {
|
||||
|
||||
File diff suppressed because one or more lines are too long
@@ -6,6 +6,7 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig
|
||||
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab BLUE AUDIENCE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousBlueAudienceEngine extends RedCrabEngine {
|
||||
@@ -13,6 +14,7 @@ public class RedCrabAutonomousBlueAudienceEngine extends RedCrabEngine {
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
addTask(new ClawArmTask(robot));
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
setupFromConfig(
|
||||
new TimeCraftersConfiguration("cyberarm_RedCrab"),
|
||||
|
||||
@@ -6,6 +6,7 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig
|
||||
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab BLUE BACKSTAGE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousBlueBackstageEngine extends RedCrabEngine {
|
||||
@@ -13,6 +14,7 @@ public class RedCrabAutonomousBlueBackstageEngine extends RedCrabEngine {
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
addTask(new ClawArmTask(robot));
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
setupFromConfig(
|
||||
new TimeCraftersConfiguration("cyberarm_RedCrab"),
|
||||
|
||||
@@ -6,6 +6,7 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig
|
||||
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab Auto DEBUGGING", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousDebuggingOnlyEngine extends RedCrabEngine {
|
||||
@@ -13,6 +14,7 @@ public class RedCrabAutonomousDebuggingOnlyEngine extends RedCrabEngine {
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
addTask(new ClawArmTask(robot));
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
setupFromConfig(
|
||||
new TimeCraftersConfiguration("cyberarm_RedCrab"),
|
||||
|
||||
@@ -6,6 +6,7 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig
|
||||
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab RED AUDIENCE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousRedAudienceEngine extends RedCrabEngine {
|
||||
@@ -13,6 +14,7 @@ public class RedCrabAutonomousRedAudienceEngine extends RedCrabEngine {
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
addTask(new ClawArmTask(robot));
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
setupFromConfig(
|
||||
new TimeCraftersConfiguration("cyberarm_RedCrab"),
|
||||
|
||||
@@ -6,6 +6,7 @@ import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfig
|
||||
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
|
||||
@Autonomous(name = "Cyberarm Red Crab RED BACKSTAGE", group = "MINIBOT", preselectTeleOp = "Cyberarm Red Crab TeleOp")
|
||||
public class RedCrabAutonomousRedBackstageEngine extends RedCrabEngine {
|
||||
@@ -13,6 +14,7 @@ public class RedCrabAutonomousRedBackstageEngine extends RedCrabEngine {
|
||||
public void setup() {
|
||||
robot = new RedCrabMinibot(true);
|
||||
addTask(new ClawArmTask(robot));
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
setupFromConfig(
|
||||
new TimeCraftersConfiguration("cyberarm_RedCrab"),
|
||||
|
||||
@@ -10,9 +10,6 @@ public abstract class RedCrabEngine extends CyberarmEngine {
|
||||
@Override
|
||||
public void loop() {
|
||||
Utilities.hubsClearBulkReadCache(hardwareMap);
|
||||
if (RedCrabMinibot.localizer != null) {
|
||||
RedCrabMinibot.localizer.integrate();
|
||||
}
|
||||
|
||||
super.loop();
|
||||
|
||||
|
||||
@@ -8,6 +8,7 @@ import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.engine.V2.CyberarmState;
|
||||
import dev.cyberarm.engine.V2.Utilities;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
|
||||
@TeleOp(name = "Cyberarm Red Crab TeleOp DEBUGGING", group = "MINIBOT")
|
||||
public class RedCrabTeleOpDebuggingOnlyEngine extends RedCrabEngine {
|
||||
@@ -17,6 +18,8 @@ public class RedCrabTeleOpDebuggingOnlyEngine extends RedCrabEngine {
|
||||
|
||||
robot = new RedCrabMinibot(false);
|
||||
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
addState(new CyberarmState() {
|
||||
|
||||
@Override
|
||||
|
||||
@@ -6,6 +6,7 @@ import dev.cyberarm.engine.V2.CyberarmEngine;
|
||||
import dev.cyberarm.engine.V2.Utilities;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
import dev.cyberarm.minibots.red_crab.states.ClawArmTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.LocalizerTask;
|
||||
import dev.cyberarm.minibots.red_crab.states.Pilot;
|
||||
|
||||
@TeleOp(name = "Cyberarm Red Crab TeleOp", group = "MINIBOT")
|
||||
@@ -15,6 +16,7 @@ public class RedCrabTeleOpEngine extends RedCrabEngine {
|
||||
robot = new RedCrabMinibot(false);
|
||||
|
||||
addTask(new ClawArmTask(robot));
|
||||
addTask(new LocalizerTask(robot));
|
||||
|
||||
addState(new Pilot(robot));
|
||||
}
|
||||
|
||||
@@ -0,0 +1,21 @@
|
||||
package dev.cyberarm.minibots.red_crab.states;
|
||||
|
||||
import dev.cyberarm.engine.V2.CyberarmState;
|
||||
import dev.cyberarm.engine.V2.Utilities;
|
||||
import dev.cyberarm.minibots.red_crab.RedCrabMinibot;
|
||||
|
||||
public class LocalizerTask extends CyberarmState {
|
||||
private final RedCrabMinibot robot;
|
||||
|
||||
public LocalizerTask(RedCrabMinibot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
@Override
|
||||
public void exec() {
|
||||
Utilities.hubsClearBulkReadCache(engine.hardwareMap);
|
||||
|
||||
if (RedCrabMinibot.localizer != null) {
|
||||
RedCrabMinibot.localizer.integrate();
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -98,7 +98,7 @@ public class MoveToCoordinate extends CyberarmState {
|
||||
|
||||
double y = direction.x(); // robot forward is in the X axis
|
||||
double x = direction.y(); // robot side to side is on the Y axis
|
||||
double rx = rotationStrength; //engine.gamepad1.right_stick_x;
|
||||
double rx = 0; // -rotationStrength; //engine.gamepad1.right_stick_x;
|
||||
|
||||
double botHeading = robot.imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.RADIANS);
|
||||
|
||||
|
||||
Reference in New Issue
Block a user