From d5fb76b2f506a499c4f732f15798d1342f64b08d Mon Sep 17 00:00:00 2001 From: Benny0Li Date: Wed, 21 Aug 2024 11:30:07 +0800 Subject: [PATCH] =?UTF-8?q?=E6=96=B0=E5=A2=9E=20HardwareDevices=20?= =?UTF-8?q?=E4=BB=A5=E7=BB=B4=E6=8A=A4=E7=A1=AC=E4=BB=B6=20=E5=B9=B6?= =?UTF-8?q?=E7=A7=BB=E9=99=A4=E4=BA=86=20namespace?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../Localizers/ImuLocalizer.java | 3 +- .../{HardwareSet.java => DeviceMap.java} | 48 ++++++++--------- .../ftc/teamcode/Hardwares/basic/Motors.java | 54 +++++++------------ .../ftc/teamcode/Hardwares/basic/Sensors.java | 6 +-- .../ftc/teamcode/Hardwares/basic/Servos.java | 28 +++------- .../RIC_tuning/Auto_IMUPositionTuner.java | 3 +- .../teamcode/RIC_tuning/IMUPositionTuner.java | 3 +- .../org/firstinspires/ftc/teamcode/Robot.java | 10 ++-- .../firstinspires/ftc/teamcode/namespace.java | 26 --------- .../teamcode/utils/enums/HardwareDevices.java | 28 ++++++++++ .../teamcode/utils/enums/HardwareType.java | 7 --- .../teamcode/utils/enums/RobotDevices.java | 12 +++++ 12 files changed, 100 insertions(+), 128 deletions(-) rename TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/{HardwareSet.java => DeviceMap.java} (51%) delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/namespace.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareDevices.java delete mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareType.java create mode 100644 TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/RobotDevices.java diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Localizers/ImuLocalizer.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Localizers/ImuLocalizer.java index 3beb2f9..680fe07 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Localizers/ImuLocalizer.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/DriveControls/Localizers/ImuLocalizer.java @@ -49,7 +49,8 @@ public void update() { Complex angle=new Complex(Math.toDegrees(pose.heading.toDouble())); complex=complex.minus(error.times(angle).divide(angle.magnitude())); pose=new Pose2d(complex.toVector2d(),pose.heading); - }/** + } + /** * @return 返回我们重写的Localizer的格式,返回参数为实际位置。 */ @Override diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/HardwareSet.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/DeviceMap.java similarity index 51% rename from TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/HardwareSet.java rename to TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/DeviceMap.java index 301cb89..33af3ec 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/HardwareSet.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/DeviceMap.java @@ -1,14 +1,13 @@ package org.firstinspires.ftc.teamcode.Hardwares.basic; -import android.util.Log; - import com.qualcomm.robotcore.hardware.DcMotor; import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; import com.qualcomm.robotcore.hardware.HardwareDevice; +import com.qualcomm.robotcore.hardware.HardwareMap; import com.qualcomm.robotcore.hardware.Servo; -import org.firstinspires.ftc.teamcode.utils.enums.HardwareType; +import org.firstinspires.ftc.teamcode.utils.enums.HardwareDevices; import java.util.HashMap; import java.util.Map; @@ -16,57 +15,58 @@ /** * @apiNote OpenCvCamera和BNU055IMU都不属于接口HardwareDevice */ -public class HardwareSet { - public Map devices; - public HardwareSet(){ +public class DeviceMap { + public Map devices; + public DeviceMap(HardwareMap hardwareMap){ devices=new HashMap<>(); + for(HardwareDevices device: HardwareDevices.values()){ + devices.put(device,(HardwareDevice)hardwareMap.get(device.classType,device.deviceName)); + } } - public void addDevice(HardwareDevice device, HardwareType hardwareType){ - devices.put(hardwareType,device); - Log.i("HardwareSet",device.getDeviceName()+" added."); - } - public HardwareDevice getDevice(HardwareType hardwareType){ - if(devices.containsKey(hardwareType)){ - return devices.get(hardwareType); + public HardwareDevice getDevice(HardwareDevices hardwareDevices){ + if(devices.containsKey(hardwareDevices)){ + return devices.get(hardwareDevices); }else{ - throw new NullPointerException("Device Not Found:"+hardwareType.toString()); + throw new NullPointerException("Device Not Found:"+ hardwareDevices.toString()); } } - public void setDirection(HardwareType hardwareType, DcMotorSimple.Direction direction){ - HardwareDevice device=getDevice(hardwareType); + public void setDirection(HardwareDevices hardwareDevices, DcMotorSimple.Direction direction){ + HardwareDevice device=getDevice(hardwareDevices); if(device instanceof DcMotorEx){ ((DcMotorEx) device).setDirection(direction); }else{ throw new RuntimeException("DcMotor's Direction Only Matches To DcMotor"); } } - public void setPower(HardwareType hardwareType, double power){ - HardwareDevice device=getDevice(hardwareType); + public void setPower(HardwareDevices hardwareDevices, double power){ + HardwareDevice device=getDevice(hardwareDevices); if(device instanceof DcMotorEx){ ((DcMotorEx) device).setPower(power); }else if(device instanceof DcMotor){ ((DcMotor) device).setPower(power); }else if(device instanceof Servos){ - throw new RuntimeException("Cannot set the power of a servo at HardwareSet.class"); + throw new RuntimeException("Cannot set the power of a servo at DeviceMap.class"); } } - public void setPosition(HardwareType hardwareType, double position){ - HardwareDevice device=getDevice(hardwareType); + public void setPosition(HardwareDevices hardwareDevices, double position){ + HardwareDevice device=getDevice(hardwareDevices); if(device instanceof Servo){ ((Servo) device).setPosition(position); }else{ throw new RuntimeException("Not allowed to set the position of a device witch isn't a Servo"); } } - public double getPosition(HardwareType hardwareType){ - HardwareDevice device=getDevice(hardwareType); + public double getPosition(HardwareDevices hardwareDevices){ + HardwareDevice device=getDevice(hardwareDevices); if (device instanceof Servo) { return ((Servo) device).getPosition(); + }else if(device instanceof DcMotorEx){ + return ((DcMotorEx) device).getCurrentPosition(); }else if(device instanceof DcMotor){ return ((DcMotor) device).getCurrentPosition(); }else{ - throw new RuntimeException("Cannot get the position of other devices at HardwareSet.class"); + throw new RuntimeException("Cannot get the position of other devices at DeviceMap.class"); } } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Motors.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Motors.java index 14371d0..cc84e46 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Motors.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Motors.java @@ -1,20 +1,15 @@ package org.firstinspires.ftc.teamcode.Hardwares.basic; -import androidx.annotation.NonNull; - import com.acmerobotics.roadrunner.Vector2d; -import com.qualcomm.robotcore.hardware.DcMotorEx; import com.qualcomm.robotcore.hardware.DcMotorSimple; -import com.qualcomm.robotcore.hardware.HardwareMap; import org.firstinspires.ftc.teamcode.RuntimeOption; -import org.firstinspires.ftc.teamcode.namespace; import org.firstinspires.ftc.teamcode.utils.Complex; import org.firstinspires.ftc.teamcode.utils.Mathematics; -import org.firstinspires.ftc.teamcode.utils.enums.HardwareType; +import org.firstinspires.ftc.teamcode.utils.enums.HardwareDevices; public class Motors { - public HardwareSet hardware; + public DeviceMap hardware; //除非在手动程序中,不建议直接更改下列数值 public double LeftFrontPower,RightFrontPower,LeftRearPower,RightRearPower; @@ -23,12 +18,8 @@ public class Motors { private double ClassicBufPower =1, StructureBufPower =1; - public Motors(@NonNull HardwareMap hardwareMap){ - this(hardwareMap,new HardwareSet()); - } - public Motors(@NonNull HardwareMap hardwareMap,HardwareSet hardwareSet){ - namespace namespace = new namespace(); - hardware=hardwareSet; + public Motors(DeviceMap deviceMap){ + hardware= deviceMap; LeftFrontPower=0; RightFrontPower=0; LeftRearPower=0; @@ -38,24 +29,15 @@ public Motors(@NonNull HardwareMap hardwareMap,HardwareSet hardwareSet){ SuspensionArmPower=0; IntakePower=0; - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.LeftFront)), HardwareType.LeftFront); - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.LeftRear)), HardwareType.LeftRear); - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.RightFront)), HardwareType.RightFront); - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.RightRear)), HardwareType.RightRear); - - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.PlacementArm)), HardwareType.PlacementArm); - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.SuspensionArm)), HardwareType.SuspensionArm); - hardware.addDevice(hardwareMap.get(DcMotorEx.class, namespace.Hardware.get(HardwareType.Intake)), HardwareType.Intake); - //TODO:根据实际情况修改 - hardware.setDirection(HardwareType.LeftFront, DcMotorSimple.Direction.FORWARD); - hardware.setDirection(HardwareType.LeftRear, DcMotorSimple.Direction.FORWARD); - hardware.setDirection(HardwareType.RightFront, DcMotorSimple.Direction.REVERSE); - hardware.setDirection(HardwareType.RightRear, DcMotorSimple.Direction.REVERSE); + hardware.setDirection(HardwareDevices.LeftFront, DcMotorSimple.Direction.FORWARD); + hardware.setDirection(HardwareDevices.LeftRear, DcMotorSimple.Direction.FORWARD); + hardware.setDirection(HardwareDevices.RightFront, DcMotorSimple.Direction.REVERSE); + hardware.setDirection(HardwareDevices.RightRear, DcMotorSimple.Direction.REVERSE); - hardware.setDirection(HardwareType.PlacementArm, DcMotorSimple.Direction.REVERSE); - hardware.setDirection(HardwareType.Intake, DcMotorSimple.Direction.REVERSE); - hardware.setDirection(HardwareType.SuspensionArm, DcMotorSimple.Direction.FORWARD); + hardware.setDirection(HardwareDevices.PlacementArm, DcMotorSimple.Direction.REVERSE); + hardware.setDirection(HardwareDevices.Intake, DcMotorSimple.Direction.REVERSE); + hardware.setDirection(HardwareDevices.SuspensionArm, DcMotorSimple.Direction.FORWARD); } public void clearDriveOptions(){ @@ -102,15 +84,15 @@ public void updateDriveOptions(){ RightFrontPower=Mathematics.intervalClip(RightFrontPower,-1,1); RightRearPower=Mathematics.intervalClip(RightRearPower,-1,1); // hardware.setPower( - hardware.setPower(HardwareType.LeftFront, LeftFrontPower* ClassicBufPower); - hardware.setPower(HardwareType.LeftRear, LeftRearPower* ClassicBufPower); - hardware.setPower(HardwareType.RightFront, RightFrontPower* ClassicBufPower); - hardware.setPower(HardwareType.RightRear, RightRearPower* ClassicBufPower); + hardware.setPower(HardwareDevices.LeftFront, LeftFrontPower* ClassicBufPower); + hardware.setPower(HardwareDevices.LeftRear, LeftRearPower* ClassicBufPower); + hardware.setPower(HardwareDevices.RightFront, RightFrontPower* ClassicBufPower); + hardware.setPower(HardwareDevices.RightRear, RightRearPower* ClassicBufPower); } public void updateStructureOptions(){ - hardware.setPower(HardwareType.PlacementArm, PlacementArmPower* StructureBufPower); - hardware.setPower(HardwareType.Intake, IntakePower* StructureBufPower); - hardware.setPower(HardwareType.SuspensionArm, SuspensionArmPower* StructureBufPower); + hardware.setPower(HardwareDevices.PlacementArm, PlacementArmPower* StructureBufPower); + hardware.setPower(HardwareDevices.Intake, IntakePower* StructureBufPower); + hardware.setPower(HardwareDevices.SuspensionArm, SuspensionArmPower* StructureBufPower); } /** * @param headingDeg 必须在使用driverUsingAxisPowerInsteadOfCurrentPower时给出,其他状态下给出是无效的 diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Sensors.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Sensors.java index 402cc30..d1b719e 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Sensors.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Sensors.java @@ -9,8 +9,7 @@ import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit; import org.firstinspires.ftc.robotcore.external.navigation.AxesOrder; import org.firstinspires.ftc.robotcore.external.navigation.AxesReference; -import org.firstinspires.ftc.teamcode.namespace; -import org.firstinspires.ftc.teamcode.utils.enums.HardwareType; +import org.firstinspires.ftc.teamcode.utils.enums.RobotDevices; public class Sensors { /** BNO055IMU 比 IMU 的稳定性更好 @@ -19,8 +18,7 @@ public class Sensors { public double FirstAngle,XMoved,YMoved; public Sensors(@NonNull HardwareMap hardwareMap){ - org.firstinspires.ftc.teamcode.namespace namespace=new namespace(); - imu=hardwareMap.get(BNO055IMU.class,namespace.Hardware.get(HardwareType.imu)); + imu=hardwareMap.get(BNO055IMU.class,RobotDevices.imu.name); BNO055IMU.Parameters parameters = new BNO055IMU.Parameters(); parameters.angleUnit= BNO055IMU.AngleUnit.DEGREES; diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Servos.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Servos.java index 77300eb..60e57bb 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Servos.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Hardwares/basic/Servos.java @@ -1,39 +1,25 @@ package org.firstinspires.ftc.teamcode.Hardwares.basic; -import androidx.annotation.NonNull; - -import com.qualcomm.robotcore.hardware.HardwareMap; -import com.qualcomm.robotcore.hardware.Servo; - -import org.firstinspires.ftc.teamcode.utils.enums.HardwareType; -import org.firstinspires.ftc.teamcode.namespace; +import org.firstinspires.ftc.teamcode.utils.enums.HardwareDevices; public class Servos { - public HardwareSet hardware; + public DeviceMap hardware; public double FrontClipPosition,RearClipPosition; private final static double AllowErrorPosition=0.1; private boolean PositionInPlace; - public Servos(@NonNull HardwareMap hardwareMap){ - this(hardwareMap,new HardwareSet()); - } - public Servos(@NonNull HardwareMap hardwareMap,HardwareSet hardware){ - namespace namespace=new namespace(); + public Servos(DeviceMap hardware){ this.hardware=hardware; - - this.hardware.addDevice(hardwareMap.get(Servo.class, namespace.Hardware.get(HardwareType.FrontClip)), HardwareType.FrontClip); - this.hardware.addDevice(hardwareMap.get(Servo.class, namespace.Hardware.get(HardwareType.RearClip)), HardwareType.RearClip); - PositionInPlace=false; } public void update(){ - hardware.setPosition(HardwareType.FrontClip,FrontClipPosition); - hardware.setPosition(HardwareType.RearClip,RearClipPosition); + hardware.setPosition(HardwareDevices.FrontClip,FrontClipPosition); + hardware.setPosition(HardwareDevices.RearClip,RearClipPosition); - PositionInPlace=(Math.abs(hardware.getPosition(HardwareType.RearClip) - RearClipPosition) < AllowErrorPosition) && - (Math.abs(hardware.getPosition(HardwareType.FrontClip)- FrontClipPosition) < AllowErrorPosition); + PositionInPlace=(Math.abs(hardware.getPosition(HardwareDevices.RearClip) - RearClipPosition) < AllowErrorPosition) && + (Math.abs(hardware.getPosition(HardwareDevices.FrontClip)- FrontClipPosition) < AllowErrorPosition); } /** diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/Auto_IMUPositionTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/Auto_IMUPositionTuner.java index 43e5609..24092ae 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/Auto_IMUPositionTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/Auto_IMUPositionTuner.java @@ -5,7 +5,6 @@ import org.firstinspires.ftc.teamcode.DriveControls.Localizers.ImuLocalizer; import org.firstinspires.ftc.teamcode.Robot; -import org.firstinspires.ftc.teamcode.utils.Client; import org.firstinspires.ftc.teamcode.utils.enums.driveDirection; import org.firstinspires.ftc.teamcode.utils.enums.runningState; @@ -21,7 +20,7 @@ public class Auto_IMUPositionTuner extends LinearOpMode { @Override public void runOpMode() { double xP,yP,r; - robot=new Robot(hardwareMap, runningState.Autonomous,new Client(telemetry)); + robot=new Robot(hardwareMap, runningState.Autonomous,telemetry); while(!opModeIsActive()&&!isStopRequested()){ sleep(50); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/IMUPositionTuner.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/IMUPositionTuner.java index c6bbab6..b0cb7d7 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/IMUPositionTuner.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/RIC_tuning/IMUPositionTuner.java @@ -5,7 +5,6 @@ import org.firstinspires.ftc.teamcode.DriveControls.Localizers.ImuLocalizer; import org.firstinspires.ftc.teamcode.Robot; -import org.firstinspires.ftc.teamcode.utils.Client; import org.firstinspires.ftc.teamcode.utils.enums.runningState; /** @@ -46,6 +45,6 @@ public void runOpMode() { } } public void INIT(){ - robot=new Robot(hardwareMap, runningState.Autonomous,new Client(telemetry)); + robot=new Robot(hardwareMap, runningState.Autonomous,telemetry); } } diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Robot.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Robot.java index 916f366..54d97a5 100644 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Robot.java +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/Robot.java @@ -15,7 +15,7 @@ import org.firstinspires.ftc.teamcode.Hardwares.Classic; import org.firstinspires.ftc.teamcode.Hardwares.Structure; import org.firstinspires.ftc.teamcode.Hardwares.Webcam; -import org.firstinspires.ftc.teamcode.Hardwares.basic.HardwareSet; +import org.firstinspires.ftc.teamcode.Hardwares.basic.DeviceMap; import org.firstinspires.ftc.teamcode.Hardwares.basic.Motors; import org.firstinspires.ftc.teamcode.Hardwares.basic.Sensors; import org.firstinspires.ftc.teamcode.Hardwares.basic.Servos; @@ -28,7 +28,7 @@ import java.util.Objects; public class Robot { - public HardwareSet devices; + public DeviceMap devices; public final Motors motors; public final Sensors sensors; @@ -51,11 +51,11 @@ public Robot(@NonNull HardwareMap hardwareMap, @NonNull runningState state, @Non this(hardwareMap,state,new Client(telemetry)); } public Robot(@NonNull HardwareMap hardwareMap, @NonNull runningState state, @NonNull Client client){ - devices=new HardwareSet(); + devices=new DeviceMap(hardwareMap); - motors=new Motors(hardwareMap,devices); + motors=new Motors(devices); sensors=new Sensors(hardwareMap); - servos=new Servos(hardwareMap,devices); + servos=new Servos(devices); classic=new Classic(motors,sensors); structure=new Structure(motors,servos); diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/namespace.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/namespace.java deleted file mode 100644 index c81c50c..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/namespace.java +++ /dev/null @@ -1,26 +0,0 @@ -package org.firstinspires.ftc.teamcode; - -import org.firstinspires.ftc.teamcode.utils.enums.HardwareType; - -import java.util.HashMap; - -public class namespace { - public final HashMap Hardware=new HashMap<>(); - - public namespace(){ - //TODO:根据实际情况修改名称,这里的名称是根据我们的机器得到的 - Hardware.put(HardwareType.LeftFront,"leftFront"); - Hardware.put(HardwareType.LeftRear,"leftRear"); - Hardware.put(HardwareType.RightFront,"rightFront"); - Hardware.put(HardwareType.RightRear,"rightRear"); - - Hardware.put(HardwareType.PlacementArm,"rightLift"); - Hardware.put(HardwareType.SuspensionArm,"rack"); - Hardware.put(HardwareType.Intake,"intake"); - - Hardware.put(HardwareType.FrontClip,"frontCilp"); - Hardware.put(HardwareType.RearClip,"rearCilp"); - - Hardware.put(HardwareType.imu,"imu"); - } -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareDevices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareDevices.java new file mode 100644 index 0000000..9b0ad7f --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareDevices.java @@ -0,0 +1,28 @@ +package org.firstinspires.ftc.teamcode.utils.enums; + +import com.qualcomm.robotcore.hardware.DcMotorEx; +import com.qualcomm.robotcore.hardware.Servo; + +/** + * 仅适用于类型为HardwareDevice 接口下的硬件 + *

+ * 可以自动登记硬件的名字及其类型 + */ +public enum HardwareDevices { + LeftFront("leftFront", DcMotorEx.class), + RightFront("eightFront", DcMotorEx.class), + LeftRear("leftRear", DcMotorEx.class), + RightRear("rightRear", DcMotorEx.class), + PlacementArm("rightLift", DcMotorEx.class), + Intake("intake", DcMotorEx.class), + FrontClip("frontClip", Servo.class), + RearClip("rearClip", Servo.class), + SuspensionArm("rack", DcMotorEx.class); + public final String deviceName; + public final Class classType; + + HardwareDevices(String deviceName, Class classType){ + this.deviceName=deviceName; + this.classType=classType; + } +} \ No newline at end of file diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareType.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareType.java deleted file mode 100644 index 5f66a65..0000000 --- a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/HardwareType.java +++ /dev/null @@ -1,7 +0,0 @@ -package org.firstinspires.ftc.teamcode.utils.enums; - -public enum HardwareType { - LeftFront,RightFront,LeftRear,RightRear, - PlacementArm, - Intake, FrontClip, RearClip, imu, SuspensionArm -} diff --git a/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/RobotDevices.java b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/RobotDevices.java new file mode 100644 index 0000000..5b46290 --- /dev/null +++ b/TeamCode/src/main/java/org/firstinspires/ftc/teamcode/utils/enums/RobotDevices.java @@ -0,0 +1,12 @@ +package org.firstinspires.ftc.teamcode.utils.enums; + +/** + * 仅适用于类型不是HardwareDevice 接口下的硬件 + */ +public enum RobotDevices { + imu("imu"); + public final String name; + RobotDevices(String name){ + this.name=name; + } +}