Skip to content

Commit af4d2b0

Browse files
committed
加入 DriverProgram ,让机器的控制程序更加集成化
1 parent 8affb5c commit af4d2b0

File tree

8 files changed

+40
-19
lines changed

8 files changed

+40
-19
lines changed

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/DriveCommand.java renamed to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Commands/DriveCommand.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.DriveControls;
1+
package org.firstinspires.ftc.teamcode.DriveControls.Commands;
22

33
import androidx.annotation.NonNull;
44

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/DriveCommandPackage.java renamed to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Commands/DriveCommandPackage.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.DriveControls;
1+
package org.firstinspires.ftc.teamcode.DriveControls.Commands;
22

33
import java.util.LinkedList;
44

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/drivingCommandsBuilder.java renamed to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Commands/drivingCommandsBuilder.java

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,10 @@
1-
package org.firstinspires.ftc.teamcode.DriveControls;
1+
package org.firstinspires.ftc.teamcode.DriveControls.Commands;
22

33
import androidx.annotation.NonNull;
44

55
import com.acmerobotics.roadrunner.Vector2d;
66

7+
import org.firstinspires.ftc.teamcode.DriveControls.SimpleMecanumDrive;
78
import org.firstinspires.ftc.teamcode.utils.Enums.TrajectoryType;
89
import org.firstinspires.ftc.teamcode.utils.Mathematics;
910

@@ -12,7 +13,7 @@ public class drivingCommandsBuilder {
1213
private final SimpleMecanumDrive drive;
1314
private DriveCommand cache;
1415

15-
drivingCommandsBuilder(@NonNull SimpleMecanumDrive drive) {
16+
public drivingCommandsBuilder(@NonNull SimpleMecanumDrive drive) {
1617
commandPackage = new DriveCommandPackage();
1718
commandPackage.commands.add(new DriveCommand(drive.classic, drive.BufPower, drive.poseHistory.getLast()));
1819
this.drive = drive;
Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,14 @@
1+
package org.firstinspires.ftc.teamcode.DriveControls;
2+
3+
import androidx.annotation.NonNull;
4+
5+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DriveCommand;
6+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DriveCommandPackage;
7+
8+
import java.util.LinkedList;
9+
10+
public interface DriverProgram {
11+
void update();
12+
default void runCommandPackage(@NonNull DriveCommandPackage commandPackage){}
13+
default void runCommandPackage(@NonNull LinkedList<DriveCommand> commands){}
14+
}

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

Lines changed: 13 additions & 7 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,9 @@
99
import com.acmerobotics.roadrunner.Pose2d;
1010
import com.acmerobotics.roadrunner.Vector2d;
1111

12+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DriveCommand;
13+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DriveCommandPackage;
14+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.drivingCommandsBuilder;
1215
import org.firstinspires.ftc.teamcode.DriveControls.Localizers.DeadWheelSubassemblyLocalizer;
1316
import org.firstinspires.ftc.teamcode.DriveControls.Localizers.definition.Localizer;
1417
import org.firstinspires.ftc.teamcode.Hardwares.Classic;
@@ -23,15 +26,15 @@
2326

2427
import java.util.LinkedList;
2528

26-
public class SimpleMecanumDrive {
27-
protected final Classic classic;
29+
public class SimpleMecanumDrive implements DriverProgram{
30+
public final Classic classic;
2831
private final Motors motors;
2932
private final Client client;
3033
private final PID_processor pidProcessor;
3134

32-
protected final LinkedList<Pose2d> poseHistory = new LinkedList<>();
35+
public final LinkedList<Pose2d> poseHistory = new LinkedList<>();
3336
public Pose2d RobotPosition;
34-
protected double BufPower=1f;
37+
public double BufPower=1f;
3538

3639
public final Localizer localizer;
3740

@@ -56,7 +59,8 @@ public SimpleMecanumDrive(@NonNull Robot robot, Pose2d RobotPosition){
5659
/**
5760
* @param commands 要执行的LinkedList < DriveCommand >,不建议在使用时才定义driveCommandPackage,虽然没有任何坏处
5861
*/
59-
public void runDriveCommands(@NonNull LinkedList < DriveCommand > commands){
62+
@Override
63+
public void runCommandPackage(@NonNull LinkedList <DriveCommand> commands){
6064
DriveCommand[] commandLists=new DriveCommand[commands.size()];
6165
commands.toArray(commandLists);
6266
Vector2d[] PoseList;
@@ -147,8 +151,9 @@ public void runDriveCommands(@NonNull LinkedList < DriveCommand > commands){
147151
/**
148152
* @param driveCommandPackage 要执行的DriveCommandPackage,不建议在使用时才定义driveCommandPackage,虽然没有任何坏处
149153
*/
150-
public void runDriveCommandPackage(@NonNull DriveCommandPackage driveCommandPackage){
151-
runDriveCommands(driveCommandPackage.commands);
154+
@Override
155+
public void runCommandPackage(@NonNull DriveCommandPackage driveCommandPackage){
156+
runCommandPackage(driveCommandPackage.commands);
152157
}
153158

154159
/**
@@ -202,6 +207,7 @@ public drivingCommandsBuilder drivingCommandsBuilder(){
202207
return new drivingCommandsBuilder(this);
203208
}
204209

210+
@Override
205211
public void update(){
206212
localizer.update();
207213
RobotPosition = localizer.getCurrentPose();

TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_samples/AutonomousSample.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -4,7 +4,7 @@
44
import com.acmerobotics.roadrunner.Vector2d;
55
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
66

7-
import org.firstinspires.ftc.teamcode.DriveControls.DriveCommandPackage;
7+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DriveCommandPackage;
88
import org.firstinspires.ftc.teamcode.utils.Templates.AutonomousProgramTemplate;
99
import org.firstinspires.ftc.teamcode.utils.Enums.AutonomousLocation;
1010

@@ -36,7 +36,7 @@ public void runOpMode() {
3636
.TurnAngle(90)
3737
.StrafeInDistance(Math.toRadians(-90),Math.sqrt(1152))
3838
.END();
39-
drive.runDriveCommandPackage(command);
39+
drive.runCommandPackage(command);
4040
break;
4141
case right:
4242
break;

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
@@ -5,7 +5,7 @@
55
import com.qualcomm.robotcore.eventloop.opmode.Autonomous;
66

77
import org.firstinspires.ftc.teamcode.DriveControls.SimpleMecanumDrive;
8-
import org.firstinspires.ftc.teamcode.DriveControls.DriveCommandPackage;
8+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.DriveCommandPackage;
99
import org.firstinspires.ftc.teamcode.Robot;
1010
import org.firstinspires.ftc.teamcode.utils.Annotations.TuningOpModes;
1111
import org.firstinspires.ftc.teamcode.utils.Templates.AutonomousProgramTemplate;
@@ -35,7 +35,7 @@ public void runOpMode() {
3535
.StrafeTo(new Vector2d(24,0))
3636
.END();
3737

38-
drive.runDriveCommandPackage(trajectory);
38+
drive.runCommandPackage(trajectory);
3939
robot.update();
4040
robot.turnAngle(-90);
4141

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

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -13,7 +13,7 @@
1313

1414
import org.firstinspires.ftc.robotcore.external.Telemetry;
1515
import org.firstinspires.ftc.teamcode.DriveControls.SimpleMecanumDrive;
16-
import org.firstinspires.ftc.teamcode.DriveControls.drivingCommandsBuilder;
16+
import org.firstinspires.ftc.teamcode.DriveControls.Commands.drivingCommandsBuilder;
1717
import org.firstinspires.ftc.teamcode.Hardwares.Classic;
1818
import org.firstinspires.ftc.teamcode.Hardwares.Structure;
1919
import org.firstinspires.ftc.teamcode.Hardwares.Webcam;
@@ -142,11 +142,11 @@ public drivingCommandsBuilder drivingCommandsBuilder(){
142142
*/
143143
public void turnAngle(double angle){
144144
if(RunningState==runningState.ManualDrive)return;
145-
drive.runDriveCommandPackage(drive.drivingCommandsBuilder().TurnAngle(angle).END());
145+
drive.runCommandPackage(drive.drivingCommandsBuilder().TurnAngle(angle).END());
146146
}
147147
public void strafeTo(Vector2d pose){
148148
if(RunningState==runningState.ManualDrive)return;
149-
drive.runDriveCommandPackage(drive.drivingCommandsBuilder().StrafeTo(pose).END());
149+
drive.runCommandPackage(drive.drivingCommandsBuilder().StrafeTo(pose).END());
150150
}
151151

152152
public Pose2d pose(){
@@ -160,7 +160,7 @@ public Pose2d pose(){
160160
*/
161161
public void SetGlobalBufPower(double BufPower){
162162
if(drive!=null) {
163-
drive.runDriveCommandPackage(drive.drivingCommandsBuilder().SetPower(BufPower).END());//考虑是否删去此代码片段
163+
drive.runCommandPackage(drive.drivingCommandsBuilder().SetPower(BufPower).END());//考虑是否删去此代码片段
164164
}
165165
motors.setBufPower(BufPower);
166166
}

0 commit comments

Comments
 (0)