Skip to content

Commit b743970

Browse files
authored
合并拉取请求 #10
修复 roadrunner 的软件包错误,顺便测试基于AndriodStudio的PullRequest
2 parents 3689abe + afdc852 commit b743970

13 files changed

+60
-47
lines changed

roadrunnerCores/src/main/java/org/roadrunner/core/messages/DriveCommandMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
import com.acmerobotics.roadrunner.PoseVelocity2dDual;
44
import com.acmerobotics.roadrunner.Time;

roadrunnerCores/src/main/java/org/roadrunner/core/messages/MecanumCommandMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
public final class MecanumCommandMessage {
44
public long timestamp;

roadrunnerCores/src/main/java/org/roadrunner/core/messages/MecanumLocalizerInputsMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
44

roadrunnerCores/src/main/java/org/roadrunner/core/messages/PoseMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
import com.acmerobotics.roadrunner.Pose2d;
44

roadrunnerCores/src/main/java/org/roadrunner/core/messages/TankCommandMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
public final class TankCommandMessage {
44
public long timestamp;

roadrunnerCores/src/main/java/org/roadrunner/core/messages/TankLocalizerInputsMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
44

roadrunnerCores/src/main/java/org/roadrunner/core/messages/ThreeDeadWheelInputsMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
44

roadrunnerCores/src/main/java/org/roadrunner/core/messages/TwoDeadWheelInputsMessage.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.messages;
1+
package org.roadrunner.core.messages;
22

33
import com.acmerobotics.roadrunner.ftc.PositionVelocityPair;
44

roadrunnerCores/src/main/java/org/roadrunner/core/tuning/LocalizationTest.java

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.tuning;
1+
package org.roadrunner.core.tuning;
22

33
import com.acmerobotics.dashboard.FtcDashboard;
44
import com.acmerobotics.dashboard.telemetry.MultipleTelemetry;
@@ -8,9 +8,9 @@
88
import com.acmerobotics.roadrunner.Vector2d;
99
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
1010

11-
import org.firstinspires.ftc.teamcode.roadrunner.Drawing;
12-
import org.firstinspires.ftc.teamcode.roadrunner.MecanumDrive;
13-
import org.firstinspires.ftc.teamcode.roadrunner.TankDrive;
11+
import org.roadrunner.core.Drawing;
12+
import org.roadrunner.core.MecanumDrive;
13+
import org.roadrunner.core.TankDrive;
1414

1515
public class LocalizationTest extends LinearOpMode {
1616
@Override
Lines changed: 39 additions & 27 deletions
Original file line numberDiff line numberDiff line change
@@ -1,31 +1,23 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.tuning;
1+
package org.roadrunner.core.tuning;
2+
3+
import androidx.annotation.NonNull;
24

35
import com.acmerobotics.roadrunner.Pose2d;
46
import com.acmerobotics.roadrunner.ftc.Actions;
57
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
68

7-
import org.firstinspires.ftc.teamcode.roadrunner.MecanumDrive;
8-
import org.firstinspires.ftc.teamcode.roadrunner.TankDrive;
9-
import org.firstinspires.ftc.teamcode.roadrunner.ThreeDeadWheelLocalizer;
10-
import org.firstinspires.ftc.teamcode.roadrunner.TwoDeadWheelLocalizer;
9+
import org.roadrunner.core.MecanumDrive;
10+
import org.roadrunner.core.TankDrive;
11+
import org.roadrunner.core.ThreeDeadWheelLocalizer;
12+
import org.roadrunner.core.TwoDeadWheelLocalizer;
1113

1214
public final class ManualFeedbackTuner extends LinearOpMode {
1315
public static double DISTANCE = 64;
1416

1517
@Override
1618
public void runOpMode() throws InterruptedException {
1719
if (TuningOpModes.DRIVE_CLASS.equals(MecanumDrive.class)) {
18-
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
19-
20-
if (drive.localizer instanceof TwoDeadWheelLocalizer) {
21-
if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) {
22-
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
23-
}
24-
} else if (drive.localizer instanceof ThreeDeadWheelLocalizer) {
25-
if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) {
26-
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
27-
}
28-
}
20+
MecanumDrive drive = getMecanumDrive();
2921
waitForStart();
3022

3123
while (opModeIsActive()) {
@@ -36,17 +28,7 @@ public void runOpMode() throws InterruptedException {
3628
.build());
3729
}
3830
} else if (TuningOpModes.DRIVE_CLASS.equals(TankDrive.class)) {
39-
TankDrive drive = new TankDrive(hardwareMap, new Pose2d(0, 0, 0));
40-
41-
if (drive.localizer instanceof TwoDeadWheelLocalizer) {
42-
if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) {
43-
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
44-
}
45-
} else if (drive.localizer instanceof ThreeDeadWheelLocalizer) {
46-
if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) {
47-
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
48-
}
49-
}
31+
TankDrive drive = getTankDrive();
5032
waitForStart();
5133

5234
while (opModeIsActive()) {
@@ -60,4 +42,34 @@ public void runOpMode() throws InterruptedException {
6042
throw new RuntimeException();
6143
}
6244
}
45+
46+
private @NonNull MecanumDrive getMecanumDrive() {
47+
MecanumDrive drive = new MecanumDrive(hardwareMap, new Pose2d(0, 0, 0));
48+
49+
if (drive.localizer instanceof TwoDeadWheelLocalizer) {
50+
if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) {
51+
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
52+
}
53+
} else if (drive.localizer instanceof ThreeDeadWheelLocalizer) {
54+
if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) {
55+
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
56+
}
57+
}
58+
return drive;
59+
}
60+
61+
private @NonNull TankDrive getTankDrive() {
62+
TankDrive drive = new TankDrive(hardwareMap, new Pose2d(0, 0, 0));
63+
64+
if (drive.localizer instanceof TwoDeadWheelLocalizer) {
65+
if (TwoDeadWheelLocalizer.PARAMS.perpXTicks == 0 && TwoDeadWheelLocalizer.PARAMS.parYTicks == 0) {
66+
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
67+
}
68+
} else if (drive.localizer instanceof ThreeDeadWheelLocalizer) {
69+
if (ThreeDeadWheelLocalizer.PARAMS.perpXTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par0YTicks == 0 && ThreeDeadWheelLocalizer.PARAMS.par1YTicks == 1) {
70+
throw new RuntimeException("Odometry wheel locations not set! Run AngularRampLogger to tune them.");
71+
}
72+
}
73+
return drive;
74+
}
6375
}

roadrunnerCores/src/main/java/org/roadrunner/core/tuning/SplineTest.java

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,12 +1,12 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.tuning;
1+
package org.roadrunner.core.tuning;
22

33
import com.acmerobotics.roadrunner.Pose2d;
44
import com.acmerobotics.roadrunner.Vector2d;
55
import com.acmerobotics.roadrunner.ftc.Actions;
66
import com.qualcomm.robotcore.eventloop.opmode.LinearOpMode;
77

8-
import org.firstinspires.ftc.teamcode.roadrunner.MecanumDrive;
9-
import org.firstinspires.ftc.teamcode.roadrunner.TankDrive;
8+
import org.roadrunner.core.MecanumDrive;
9+
import org.roadrunner.core.TankDrive;
1010

1111
public final class SplineTest extends LinearOpMode {
1212
@Override

roadrunnerCores/src/main/java/org/roadrunner/core/tuning/TuningOpModes.java

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -1,4 +1,4 @@
1-
package org.firstinspires.ftc.teamcode.roadrunner.tuning;
1+
package org.roadrunner.core.tuning;
22

33
import com.acmerobotics.dashboard.FtcDashboard;
44
import com.acmerobotics.dashboard.config.reflection.ReflectionConfig;
@@ -22,10 +22,10 @@
2222
import com.qualcomm.robotcore.eventloop.opmode.OpModeRegistrar;
2323

2424
import org.firstinspires.ftc.robotcore.internal.opmode.OpModeMeta;
25-
import org.firstinspires.ftc.teamcode.roadrunner.MecanumDrive;
26-
import org.firstinspires.ftc.teamcode.roadrunner.TankDrive;
27-
import org.firstinspires.ftc.teamcode.roadrunner.ThreeDeadWheelLocalizer;
28-
import org.firstinspires.ftc.teamcode.roadrunner.TwoDeadWheelLocalizer;
25+
import org.roadrunner.core.MecanumDrive;
26+
import org.roadrunner.core.TankDrive;
27+
import org.roadrunner.core.ThreeDeadWheelLocalizer;
28+
import org.roadrunner.core.TwoDeadWheelLocalizer;
2929

3030
import java.util.ArrayList;
3131
import java.util.Arrays;

settings.gradle

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,4 @@
11
include ':FtcRobotController'
22
include ':TeamCode'
33
include ':roadrunnerCores'
4+
include ':FtcTeamCodeSample'

0 commit comments

Comments
 (0)