Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Hardware features #3

Merged
merged 1 commit into from
Aug 4, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -0,0 +1,50 @@
package org.firstinspires.ftc.teamcode;

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.HardwareMap;

import org.firstinspires.ftc.teamcode.hardware.AutoClearEncoder;
import org.firstinspires.ftc.teamcode.hardware.HardwareMapper;
import org.firstinspires.ftc.teamcode.hardware.HardwareName;
import org.firstinspires.ftc.teamcode.hardware.Reversed;
import org.firstinspires.ftc.teamcode.hardware.ZeroPower;

public class Hardware extends HardwareMapper {
// left = left motor = exp 0 frontLeft
// right = right motor = ctr 0 frontRight
// center = ctr 3 intake

@HardwareName("frontLeft")
@Reversed
@ZeroPower(DcMotor.ZeroPowerBehavior.BRAKE)
public DcMotor frontLeft;

@HardwareName("frontRight")
@ZeroPower(DcMotor.ZeroPowerBehavior.BRAKE)
public DcMotor frontRight;

@HardwareName("backLeft")
@ZeroPower(DcMotor.ZeroPowerBehavior.BRAKE)
@Reversed
public DcMotor backLeft;

@HardwareName("backRight")
@ZeroPower(DcMotor.ZeroPowerBehavior.BRAKE)
public DcMotor backRight;

@HardwareName("frontLeft")
@AutoClearEncoder
public DcMotor encoderLeft;

@HardwareName("intake")
@AutoClearEncoder
public DcMotor encoderCenter;

@HardwareName("frontRight")
@AutoClearEncoder
public DcMotor encoderRight;

public Hardware(HardwareMap hwMap) {
super(hwMap);
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,15 @@
package org.firstinspires.ftc.teamcode.hardware;

import java.lang.annotation.Documented;
import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;

/**
* Specifies that an encoder should be cleared when the robot is initialized.
*/
@Documented
@Retention(RetentionPolicy.RUNTIME)
@Target(ElementType.FIELD)
public @interface AutoClearEncoder { }
Original file line number Diff line number Diff line change
@@ -0,0 +1,111 @@
package org.firstinspires.ftc.teamcode.hardware;

import com.qualcomm.robotcore.hardware.DcMotor;
import com.qualcomm.robotcore.hardware.DcMotorSimple;
import com.qualcomm.robotcore.hardware.HardwareMap;

import java.lang.annotation.Annotation;
import java.lang.reflect.Field;

/**
* Annotation processor for hardware map things.
*/
public abstract class HardwareMapper {
/**
* Represents an annotation processor for hardware devices.
* Internals are a bit of a mess right now.
* <p> </p>
* HardwareName is hardcoded because it provides the value of the field.
*/
static final class DeviceAnnotation<AnnotationT extends Annotation, TargetT> {
private final Class<AnnotationT> annotationClass;
private final Class<TargetT> targetClass;
private final Action<AnnotationT, TargetT> action;

@FunctionalInterface
interface Action<AnnotationT extends Annotation, TargetType> {
void use(AnnotationT annotation, TargetType target);
}

DeviceAnnotation(Class<AnnotationT> annotationClass, Class<TargetT> targetClass, Action<AnnotationT, TargetT> action) {
this.annotationClass = annotationClass;
this.targetClass = targetClass;
this.action = action;
}

private boolean check(Field t, Object value) {
if (!t.isAnnotationPresent(annotationClass)) return false;
AnnotationT annotation = t.getAnnotation(annotationClass);
if (annotation == null)
throw new NullPointerException("Annotation is null! (isAnnotationPresent is true but getAnnotation returned null)");
if (!targetClass.isAssignableFrom(value.getClass()))
throw new ClassCastException("Annotation " + annotationClass.getName() + " can only be used on " + targetClass.getName() + " (or subclasses)");
return true;
}

void use(Field t, Object value) {
if (!check(t, value)) return;
AnnotationT annotation = t.getAnnotation(annotationClass);
if (annotation == null)
throw new NullPointerException("Annotation disappeared between check and use");
action.use(annotation, targetClass.cast(value));
}
}

static final DeviceAnnotation<Reversed, DcMotorSimple> reversed =
new DeviceAnnotation<>(
Reversed.class,
DcMotorSimple.class,
(annotation, target) -> target.setDirection(DcMotorSimple.Direction.REVERSE)
);

static final DeviceAnnotation<ZeroPower, DcMotor> zeroPower =
new DeviceAnnotation<>(
ZeroPower.class,
DcMotor.class,
(annotation, target) -> target.setZeroPowerBehavior(annotation.value())
);

static final DeviceAnnotation<AutoClearEncoder, DcMotor> autoClearEncoder =
new DeviceAnnotation<>(
AutoClearEncoder.class,
DcMotor.class,
(annotation, target) -> {
DcMotor.RunMode current = target.getMode();
target.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER);
target.setMode(current);
}
);

public HardwareMapper(HardwareMap map) {
Field[] fields = this.getClass().getDeclaredFields();
for (Field field : fields) {
boolean accessible = field.isAccessible();
if (!accessible) field.setAccessible(true);
try {
Class<?> targetType = field.getType();
HardwareName annotation = field.getAnnotation(HardwareName.class);
if (annotation == null) continue;
Object result = map.tryGet(targetType, annotation.value());

if (result == null) {
throw new RuntimeException("Hardware: '" + field.getName() + "' not found, expected type " + targetType.getName() + " for field " + field.getName() + " in " + this.getClass().getName());
}
try {
field.set(this, result);
} catch (IllegalAccessException e) {
throw new RuntimeException("Field " + field.getName() + " assign failed: " + result.getClass().getName() + " to " + field.getType().getName());
}

reversed.use(field, result);
zeroPower.use(field, result);
autoClearEncoder.use(field, result);
} catch (IllegalArgumentException e) {
throw new RuntimeException("Field " + field.getName() + " typecast failed");
} finally {
// lock the field back if it was locked
field.setAccessible(accessible);
}
}
}
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,14 @@
package org.firstinspires.ftc.teamcode.hardware;

import java.lang.annotation.Documented;
import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;

@Retention(RetentionPolicy.RUNTIME)
@Target(ElementType.FIELD)
@Documented
public @interface HardwareName {
String value();
}
Original file line number Diff line number Diff line change
@@ -0,0 +1,16 @@
package org.firstinspires.ftc.teamcode.hardware;

import java.lang.annotation.Documented;
import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;

/**
* Specifies that a motor should start with its direction reversed.
* The annotated field must be a DcMotorSimple or subclass.
*/
@Retention(RetentionPolicy.RUNTIME)
@Target(ElementType.FIELD)
@Documented
public @interface Reversed {}
Original file line number Diff line number Diff line change
@@ -0,0 +1,19 @@
package org.firstinspires.ftc.teamcode.hardware;

import com.qualcomm.robotcore.hardware.DcMotor;

import java.lang.annotation.Documented;
import java.lang.annotation.ElementType;
import java.lang.annotation.Retention;
import java.lang.annotation.RetentionPolicy;
import java.lang.annotation.Target;

/**
* Defiles the zero power behavior of a motor.
*/
@Documented
@Retention(RetentionPolicy.RUNTIME)
@Target(ElementType.FIELD)
public @interface ZeroPower {
DcMotor.ZeroPowerBehavior value();
}