Skip to content

Commit 7510864

Browse files
committed
试图制作 TuningOrSampleAutonomousRegister
1 parent 0f06ad2 commit 7510864

File tree

10 files changed

+76
-20
lines changed

10 files changed

+76
-20
lines changed
Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -4,24 +4,24 @@
44

55
import com.acmerobotics.roadrunner.Vector2d;
66

7+
import org.firstinspires.ftc.teamcode.DriveControls.MecanumDrive;
78
import org.firstinspires.ftc.teamcode.DriveControls.OrderDefinition.DriveOrderBuilder;
89
import org.firstinspires.ftc.teamcode.DriveControls.OrderDefinition.DriveOrderPackage;
910
import org.firstinspires.ftc.teamcode.DriveControls.OrderDefinition.DriverProgram;
10-
import org.firstinspires.ftc.teamcode.DriveControls.SimpleMecanumDrive;
1111
import org.firstinspires.ftc.teamcode.Utils.Enums.TrajectoryType;
1212
import org.firstinspires.ftc.teamcode.Utils.Functions;
1313

14-
public class DrivingActionsBuilder implements DriveOrderBuilder {
14+
public class DriveActionBuilder implements DriveOrderBuilder {
1515
private final DriveActionPackage actionPackage;
1616
private final DriverProgram drive;
1717
private DriveAction cache;
1818

19-
public DrivingActionsBuilder(@NonNull SimpleMecanumDrive drive) {
19+
public DriveActionBuilder(@NonNull MecanumDrive drive) {
2020
actionPackage = new DriveActionPackage();
2121
actionPackage.actions.add(new DriveAction(drive.classic, drive.BufPower, drive.poseHistory.getLast()));
2222
this.drive = drive;
2323
}
24-
DrivingActionsBuilder(DriverProgram drive, DriveActionPackage actionPackage) {
24+
DriveActionBuilder(DriverProgram drive, DriveActionPackage actionPackage) {
2525
this.actionPackage = actionPackage;
2626
this.drive = drive;
2727
}
@@ -33,7 +33,7 @@ public DriveOrderBuilder SetPower(double power) {
3333
cache.SetPower(power);
3434
cache.trajectoryType = TrajectoryType.WithoutChangingPosition;
3535
actionPackage.actions.add(cache);
36-
return new DrivingActionsBuilder(drive, actionPackage);
36+
return new DriveActionBuilder(drive, actionPackage);
3737
}
3838

3939
@Override
@@ -43,7 +43,7 @@ public DriveOrderBuilder TurnRadians(double radians) {
4343
cache.Turn(radians);
4444
cache.trajectoryType = TrajectoryType.TurnOnly;
4545
actionPackage.actions.add(cache);
46-
return new DrivingActionsBuilder(drive, actionPackage);
46+
return new DriveActionBuilder(drive, actionPackage);
4747
}
4848

4949
@Override
@@ -57,7 +57,7 @@ public DriveOrderBuilder StrafeInDistance(double radians, double distance) {
5757
cache.StrafeInDistance(radians, distance);
5858
cache.trajectoryType = TrajectoryType.LinerStrafe;
5959
actionPackage.actions.add(cache);
60-
return new DrivingActionsBuilder(drive, actionPackage);
60+
return new DriveActionBuilder(drive, actionPackage);
6161
}
6262

6363
@Override
@@ -66,7 +66,7 @@ public DriveOrderBuilder StrafeTo(Vector2d pose) {
6666
cache.StrafeTo(pose);
6767
cache.trajectoryType = TrajectoryType.LinerStrafe;
6868
actionPackage.actions.add(cache);
69-
return new DrivingActionsBuilder(drive, actionPackage);
69+
return new DriveActionBuilder(drive, actionPackage);
7070
}
7171

7272
@Override

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/MecanumDrive.java

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -15,6 +15,7 @@
1515
import com.acmerobotics.roadrunner.ftc.Actions;
1616

1717
import org.firstinspires.ftc.teamcode.DriveControls.Actions.DriveAction;
18+
import org.firstinspires.ftc.teamcode.DriveControls.Actions.DriveActionBuilder;
1819
import org.firstinspires.ftc.teamcode.DriveControls.Localizers.DeadWheelSubassemblyLocalizer;
1920
import org.firstinspires.ftc.teamcode.DriveControls.Localizers.LocalizerDefinition.Localizer;
2021
import org.firstinspires.ftc.teamcode.DriveControls.OrderDefinition.DriveOrder;
@@ -200,4 +201,16 @@ public void preview(@NonNull Canvas fieldOverlay){
200201
public Classic getClassic() {
201202
return classic;
202203
}
204+
205+
@Override
206+
public Pose2d getCurrentPose() {
207+
return RobotPosition;
208+
}
209+
210+
/**
211+
* @return 定义开启新的 DriveActionBuilder
212+
*/
213+
public DriveActionBuilder drivingCommandsBuilder(){
214+
return new DriveActionBuilder(this);
215+
}
203216
}

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/OrderDefinition/DriverProgram.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,8 @@
22

33
import androidx.annotation.NonNull;
44

5+
import com.acmerobotics.roadrunner.Pose2d;
6+
57
import org.firstinspires.ftc.teamcode.Hardwares.Classic;
68

79
import java.util.LinkedList;
@@ -11,4 +13,5 @@ public interface DriverProgram {
1113
default void runOrderPackage(@NonNull DriveOrderPackage orderPackage){}
1214
default void runOrderPackage(@NonNull LinkedList<DriveOrder> orders){}
1315
Classic getClassic();
16+
Pose2d getCurrentPose();
1417
}

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/SimpleMecanumDrive.java

Lines changed: 5 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -161,6 +161,11 @@ public Classic getClassic() {
161161
return classic;
162162
}
163163

164+
@Override
165+
public Pose2d getCurrentPose() {
166+
return RobotPosition;
167+
}
168+
164169
/**
165170
* @param driveOrderPackage 要执行的DriveCommandPackage,不建议在使用时才定义driveCommandPackage,虽然没有任何坏处
166171
*/

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/LocalizationTest.java

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -11,7 +11,7 @@ public class LocalizationTest extends TeleopProgramTemplate {
1111
SimpleMecanumDrive drive;
1212
@Override
1313
public void whenInit() {
14-
drive=robot.InitMecanumDrive(new Pose2d(0,0,0));
14+
drive= (SimpleMecanumDrive) robot.InitMecanumDrive(new Pose2d(0,0,0));
1515
robot.addData("POSITION","WAIT FOR START");
1616
}
1717

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/SMDTest.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -25,9 +25,9 @@ public void runOpMode() {
2525

2626
if (!opModeIsActive() || isStopRequested())return;
2727

28-
drive=robot.InitMecanumDrive(new Pose2d(0,0,0));
28+
drive= (SimpleMecanumDrive) robot.InitMecanumDrive(new Pose2d(0,0,0));
2929

30-
DriveCommandPackage trajectory=robot.drivingCommandsBuilder()
30+
DriveCommandPackage trajectory= (DriveCommandPackage) robot.DrivingOrderBuilder()
3131
.StrafeInDistance(0,24)
3232
.TurnAngle(90)
3333
.StrafeTo(new Vector2d(24,0))

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Robot.java

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -12,8 +12,10 @@
1212
import com.qualcomm.robotcore.hardware.HardwareMap;
1313

1414
import org.firstinspires.ftc.robotcore.external.Telemetry;
15+
import org.firstinspires.ftc.teamcode.DriveControls.MecanumDrive;
16+
import org.firstinspires.ftc.teamcode.DriveControls.OrderDefinition.DriveOrderBuilder;
17+
import org.firstinspires.ftc.teamcode.DriveControls.OrderDefinition.DriverProgram;
1518
import org.firstinspires.ftc.teamcode.DriveControls.SimpleMecanumDrive;
16-
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DrivingCommandsBuilder;
1719
import org.firstinspires.ftc.teamcode.Hardwares.Classic;
1820
import org.firstinspires.ftc.teamcode.Hardwares.Structure;
1921
import org.firstinspires.ftc.teamcode.Hardwares.Webcam;
@@ -46,7 +48,7 @@ public class Robot {
4648

4749
public State state;
4850
public org.firstinspires.ftc.teamcode.Utils.Enums.RunningState RunningState;
49-
private SimpleMecanumDrive drive=null;
51+
private DriverProgram drive=null;
5052

5153
public Timer timer;
5254

@@ -88,7 +90,7 @@ public Robot(@NonNull HardwareMap hardwareMap, @NonNull org.firstinspires.ftc.te
8890
* 自动初始化SimpleMecanumDrive
8991
* @return 返回定义好的SimpleMecanumDrive
9092
*/
91-
public SimpleMecanumDrive InitMecanumDrive(Pose2d RobotPosition){
93+
public DriverProgram InitMecanumDrive(Pose2d RobotPosition){
9294
drive=new SimpleMecanumDrive(this,RobotPosition);
9395
if(RunningState!= org.firstinspires.ftc.teamcode.Utils.Enums.RunningState.Autonomous) {
9496
Log.w("Robot.java","Initialized Driving Program in Manual Driving State.");
@@ -131,8 +133,12 @@ public void operateThroughGamePad(Gamepad gamepad1,Gamepad gamepad2){
131133
classic.operateThroughGamePad(gamepad1);
132134
structure.operateThroughGamePad(gamepad2);
133135
}
134-
public DrivingCommandsBuilder drivingCommandsBuilder(){
135-
return drive.drivingCommandsBuilder();
136+
public DriveOrderBuilder DrivingOrderBuilder(){
137+
if(drive instanceof SimpleMecanumDrive)
138+
return ((SimpleMecanumDrive) drive).drivingCommandsBuilder();
139+
else if(drive instanceof MecanumDrive)
140+
return ((MecanumDrive) drive).drivingCommandsBuilder();
141+
return null;
136142
}
137143

138144
/**
@@ -141,16 +147,16 @@ public DrivingCommandsBuilder drivingCommandsBuilder(){
141147
*/
142148
public void turnAngle(double angle){
143149
if(RunningState== org.firstinspires.ftc.teamcode.Utils.Enums.RunningState.ManualDrive)return;
144-
drive.runOrderPackage(drive.drivingCommandsBuilder().TurnAngle(angle).END());
150+
drive.runOrderPackage(DrivingOrderBuilder().TurnAngle(angle).END());
145151
}
146152
public void strafeTo(Vector2d pose){
147153
if(RunningState== org.firstinspires.ftc.teamcode.Utils.Enums.RunningState.ManualDrive)return;
148-
drive.runOrderPackage(drive.drivingCommandsBuilder().StrafeTo(pose).END());
154+
drive.runOrderPackage(DrivingOrderBuilder().StrafeTo(pose).END());
149155
}
150156

151157
public Pose2d pose(){
152158
drive.update();
153-
return drive.RobotPosition;
159+
return drive.getCurrentPose();
154160
}
155161

156162
/**
@@ -159,7 +165,7 @@ public Pose2d pose(){
159165
*/
160166
public void SetGlobalBufPower(double BufPower){
161167
if(drive!=null) {
162-
drive.runOrderPackage(drive.drivingCommandsBuilder().SetPower(BufPower).END());//考虑是否删去此代码片段
168+
drive.runOrderPackage(DrivingOrderBuilder().SetPower(BufPower).END());//考虑是否删去此代码片段
163169
}
164170
motors.setBufPower(BufPower);
165171
}
Lines changed: 23 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,23 @@
1+
package org.firstinspires.ftc.teamcode;
2+
3+
import com.qualcomm.robotcore.eventloop.opmode.OpModeManager;
4+
import com.qualcomm.robotcore.eventloop.opmode.OpModeRegistrar;
5+
6+
import org.firstinspires.ftc.teamcode.Utils.Annotations.TuningOrSampleAutonomous;
7+
8+
import java.io.IOException;
9+
import java.lang.reflect.TypeVariable;
10+
11+
/**
12+
* @see org.firstinspires.ftc.teamcode.Utils.Annotations.TuningOrSampleAutonomous
13+
*/
14+
@Deprecated
15+
public final class TuningOrSampleAutonomousRegister {
16+
//TODO:将DISABLED设为true以禁用TuningOrSampleAutonomous
17+
public static final boolean DISABLED = false;
18+
19+
@OpModeRegistrar
20+
public static void mainRegister(OpModeManager manager) throws IOException {
21+
Class<? extends TypeVariable[]> aClass = TuningOrSampleAutonomous.class.getTypeParameters().getClass();
22+
}
23+
}

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils/Annotations/TuningOrSampleAutonomous.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,8 @@
55

66
import java.lang.annotation.Documented;
77
import java.lang.annotation.ElementType;
8+
import java.lang.annotation.Retention;
9+
import java.lang.annotation.RetentionPolicy;
810
import java.lang.annotation.Target;
911

1012
/**
@@ -14,6 +16,7 @@
1416
//@Disabled
1517
@Target({ElementType.TYPE})
1618
@Documented
19+
@Retention(RetentionPolicy.RUNTIME)
1720
public @interface TuningOrSampleAutonomous {
1821
@UserRequirementFunctions
1922
boolean DISABLED() default false;

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Utils/Annotations/TuningOrSampleTeleOPs.java

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -5,6 +5,8 @@
55

66
import java.lang.annotation.Documented;
77
import java.lang.annotation.ElementType;
8+
import java.lang.annotation.Retention;
9+
import java.lang.annotation.RetentionPolicy;
810
import java.lang.annotation.Target;
911

1012
/**
@@ -13,6 +15,7 @@
1315
//@Disabled
1416
@Target({ElementType.TYPE})
1517
@Documented
18+
@Retention(RetentionPolicy.RUNTIME)
1619
public @interface TuningOrSampleTeleOPs {
1720
@UserRequirementFunctions
1821
boolean DISABLED() default false;

0 commit comments

Comments
 (0)