Subsystem
The composition of hardware components and their basic helper functions
What are subsystems in SolversLib?
Why do we use this Subsystem design?
Example Subsystem
package org.firstinspires.ftc.teamcode.subsystems;
// EXAMPLE SUBSYSTEM
public class Arm extends SubsystemBase {
// SUBSYSTEM ASSETS
private final MyRobot robot;
private final Servo wristServo, openServo, rollServo;
public final MotorEx motor;
// STATE VARIABLES
private double wristAng = HardwareNames.WRIST_MIN;
private double rollPos = HardwareNames.ROLL_MAX;
private boolean isOpen = false;
private int offset = 0;
public Arm(MyRobot robot) {
this.robot = robot;
HardwareMap hardwareMap = robot.opMode.hardwareMap;
// shoulder motor
this.motor = new MotorEx(hardwareMap, HardwareNames.ARM_MOTOR_NAME);
motor.setRunMode(Motor.RunMode.PositionControl);
motor.setInverted(true);
motor.setPositionCoefficient(HardwareNames.ARM_MOTOR_kP);
motor.setPositionTolerance(HardwareNames.ARM_MOTOR_TOLERANCE);
// servos
wristServo = hardwareMap.get(Servo.class, HardwareNames.WRIST_SERVO_NAME);
openServo = hardwareMap.get(Servo.class, HardwareNames.OPEN_SERVO_NAME);
rollServo = hardwareMap.get(Servo.class, HardwareNames.ROLL_SERVO_NAME);
wristServo.setPosition(wristAng);
openServo.setPosition(HardwareNames.CLAW_CLOSED_POS);
rollServo.setPosition(rollPos);
}
// -- EXAMPLE SERVO COMMANDS --
public void travelMode() {
closeClaw();
wristServo.setPosition(0);
wristAng = 0;
}
public void wristUp() {
wristAng -= HardwareNames.WRIST_INC;
wristAng = Range.clip(wristAng, HardwareNames.WRIST_MIN, HardwareNames.WRIST_MAX);
wristServo.setPosition(wristAng);
}
public void wristDown() {
wristAng += HardwareNames.WRIST_INC;
wristAng = Range.clip(wristAng, HardwareNames.WRIST_MIN, HardwareNames.WRIST_MAX);
wristServo.setPosition(wristAng);
}
public void openClaw() {
openServo.setPosition(HardwareNames.CLAW_OPEN_POS);
isOpen = true;
}
public void closeClaw() {
openServo.setPosition(HardwareNames.CLAW_CLOSED_POS);
isOpen = false;
}
public void toggleOpen() {
if(isOpen) {
closeClaw();
} else {
openClaw();
}
}
public void toggleRoll() {
if(rollServo.getPosition() >= .5){
rollServo.setPosition(HardwareNames.ROLL_MIN);
rollPos = HardwareNames.ROLL_MIN;
} else{
rollServo.setPosition(HardwareNames.ROLL_MAX);
rollPos = HardwareNames.ROLL_MAX;
}
}
@NonNull
@Override
public String toString() {
return String.format(Locale.ENGLISH, "OPR: (%f, %f, %f)",
openServo.getPosition(), wristServo.getPosition(), rollServo.getPosition());
}
}Beyond Commands:
Last updated
Was this helpful?