Skip to content

Commit

Permalink
add dependency on forked library and change drive and localizers to u…
Browse files Browse the repository at this point in the history
…se it
  • Loading branch information
j5155 committed Jun 4, 2024
1 parent 168bb60 commit e53b9c8
Show file tree
Hide file tree
Showing 4 changed files with 12 additions and 9 deletions.
5 changes: 4 additions & 1 deletion TeamCode/build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -27,13 +27,16 @@ repositories {
maven {
url = 'https://maven.brott.dev/'
}
maven {
url = 'https://jitpack.io'
}
}

dependencies {
implementation project(':FtcRobotController')
annotationProcessor files('lib/OpModeAnnotationProcessor.jar')

implementation "com.acmerobotics.roadrunner:ftc:0.1.13"
implementation 'com.github.jdhs-ftc:road-runner-ftc-otos:master-SNAPSHOT'
implementation "com.acmerobotics.roadrunner:core:1.0.0-beta8"
implementation "com.acmerobotics.roadrunner:actions:1.0.0-beta8"
implementation "com.acmerobotics.dashboard:dashboard:0.4.14"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -126,7 +126,7 @@ public class DriveLocalizer implements Localizer {
public final Encoder leftFront, leftBack, rightBack, rightFront;
public final IMU imu;

private int lastLeftFrontPos, lastLeftBackPos, lastRightBackPos, lastRightFrontPos;
private double lastLeftFrontPos, lastLeftBackPos, lastRightBackPos, lastRightFrontPos;
private Rotation2d lastHeading;
private boolean initialized;

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -31,7 +31,7 @@ public static class Params {

public final double inPerTick;

private int lastPar0Pos, lastPar1Pos, lastPerpPos;
private double lastPar0Pos, lastPar1Pos, lastPerpPos;
private boolean initialized;

public ThreeDeadWheelLocalizer(HardwareMap hardwareMap, double inPerTick) {
Expand Down Expand Up @@ -70,9 +70,9 @@ public Twist2dDual<Time> update() {
);
}

int par0PosDelta = par0PosVel.position - lastPar0Pos;
int par1PosDelta = par1PosVel.position - lastPar1Pos;
int perpPosDelta = perpPosVel.position - lastPerpPos;
double par0PosDelta = par0PosVel.position - lastPar0Pos;
double par1PosDelta = par1PosVel.position - lastPar1Pos;
double perpPosDelta = perpPosVel.position - lastPerpPos;

Twist2dDual<Time> twist = new Twist2dDual<>(
new Vector2dDual<>(
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -34,7 +34,7 @@ public static class Params {
public final Encoder par, perp;
public final IMU imu;

private int lastParPos, lastPerpPos;
private double lastParPos, lastPerpPos;
private Rotation2d lastHeading;

private final double inPerTick;
Expand Down Expand Up @@ -91,8 +91,8 @@ public Twist2dDual<Time> update() {
);
}

int parPosDelta = parPosVel.position - lastParPos;
int perpPosDelta = perpPosVel.position - lastPerpPos;
double parPosDelta = parPosVel.position - lastParPos;
double perpPosDelta = perpPosVel.position - lastPerpPos;
double headingDelta = heading.minus(lastHeading);

Twist2dDual<Time> twist = new Twist2dDual<>(
Expand Down

0 comments on commit e53b9c8

Please sign in to comment.