mirror of
https://github.com/TimeCrafters/FTC_2022
synced 2025-12-15 12:12:33 +00:00
Fixed broken build due to imcomplete addition of RoadRunner, Refactored minibots out of my package..., added initial implementation of CHIRON minibot.
This commit is contained in:
5
.idea/jarRepositories.xml
generated
5
.idea/jarRepositories.xml
generated
@@ -26,5 +26,10 @@
|
||||
<option name="name" value="Google" />
|
||||
<option name="url" value="https://dl.google.com/dl/android/maven2/" />
|
||||
</remote-repository>
|
||||
<remote-repository>
|
||||
<option name="id" value="maven" />
|
||||
<option name="name" value="maven" />
|
||||
<option name="url" value="https://maven.brott.dev/" />
|
||||
</remote-repository>
|
||||
</component>
|
||||
</project>
|
||||
@@ -20,8 +20,14 @@ android {
|
||||
buildFeatures {
|
||||
mlModelBinding true
|
||||
}
|
||||
androidResources {
|
||||
noCompress 'tflite'
|
||||
}
|
||||
|
||||
packagingOptions {
|
||||
jniLibs {
|
||||
pickFirsts += ['**/*.so']
|
||||
}
|
||||
jniLibs.useLegacyPackaging true
|
||||
}
|
||||
}
|
||||
|
||||
@@ -7,7 +7,7 @@ import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.states.MecanumRobot;
|
||||
|
||||
public class LaserState extends CyberarmState {
|
||||
Rev2mDistanceSensor laser;
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
package org.timecrafters.minibots.cyberarm;
|
||||
package org.timecrafters.minibots;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.minibots.cyberarm.engines.Common;
|
||||
import org.timecrafters.minibots.engines.Common;
|
||||
|
||||
@TeleOp (name = "light test")
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.minibots.cyberarm;
|
||||
package org.timecrafters.minibots;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.minibots.cyberarm;
|
||||
package org.timecrafters.minibots;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
|
||||
@@ -1,9 +1,9 @@
|
||||
package org.timecrafters.minibots.cyberarm;
|
||||
package org.timecrafters.minibots;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.engines.Common;
|
||||
import org.timecrafters.minibots.engines.Common;
|
||||
|
||||
public class State extends CyberarmState {
|
||||
|
||||
@@ -0,0 +1,266 @@
|
||||
package org.timecrafters.minibots.cyberarm.chiron;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevHubOrientationOnRobot;
|
||||
import com.qualcomm.robotcore.hardware.ColorSensor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorEx;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.IMU;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
import com.qualcomm.robotcore.hardware.ServoImplEx;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.AngleUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.CurrentUnit;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.backend.config.Action;
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.backend.config.Variable;
|
||||
|
||||
public class Robot {
|
||||
public final DcMotorEx leftDrive, rightDrive, frontDrive, backDrive, liftDrive;
|
||||
public final ServoImplEx gripper, wrist;
|
||||
public final IMU imu;
|
||||
public final ColorSensor indicatorA, indicatorB;
|
||||
|
||||
public final double imuAngleOffset;
|
||||
public boolean wristManuallyControlled = false;
|
||||
public boolean automaticAntiTipActive = false;
|
||||
public boolean hardwareFault = false;
|
||||
|
||||
public Status status = Status.OKAY;
|
||||
|
||||
public enum LiftPosition {
|
||||
COLLECT,
|
||||
GROUND,
|
||||
LOW,
|
||||
MEDIUM,
|
||||
HIGH
|
||||
|
||||
}
|
||||
|
||||
public enum Status {
|
||||
OKAY,
|
||||
MONITORING,
|
||||
WARNING,
|
||||
DANGER
|
||||
}
|
||||
|
||||
private final CyberarmEngine engine;
|
||||
private final TimeCraftersConfiguration configuration;
|
||||
|
||||
public Robot(CyberarmEngine engine, TimeCraftersConfiguration configuration) {
|
||||
this.engine = engine;
|
||||
this.configuration = configuration;
|
||||
imuAngleOffset = hardwareConfig("imu_angle_offset").value();
|
||||
|
||||
// Define hardware
|
||||
leftDrive = engine.hardwareMap.get(DcMotorEx.class, "left_drive"); // MOTOR PORT: ?
|
||||
rightDrive = engine.hardwareMap.get(DcMotorEx.class, "right_drive"); // MOTOR PORT: ?
|
||||
|
||||
frontDrive = engine.hardwareMap.get(DcMotorEx.class, "front_drive"); // MOTOR PORT: ?
|
||||
backDrive = engine.hardwareMap.get(DcMotorEx.class, "back_drive"); // MOTOR PORT: ?
|
||||
|
||||
liftDrive = engine.hardwareMap.get(DcMotorEx.class, "lift_drive"); // MOTOR PORT: ?
|
||||
|
||||
gripper = engine.hardwareMap.get(ServoImplEx.class, "gripper"); // SERVO PORT: ?
|
||||
wrist = engine.hardwareMap.get(ServoImplEx.class, "wrist"); // SERVO PORT: ?
|
||||
|
||||
indicatorA = engine.hardwareMap.colorSensor.get("indicator_A"); // I2C
|
||||
indicatorB = engine.hardwareMap.colorSensor.get("indicator_B"); // I2C
|
||||
|
||||
imu = engine.hardwareMap.get(IMU.class, "imu");
|
||||
|
||||
|
||||
// Configure hardware
|
||||
// MOTORS
|
||||
// DIRECTION
|
||||
leftDrive.setDirection(hardwareConfig("left_drive_direction_forward").value() ? DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE);
|
||||
rightDrive.setDirection(hardwareConfig("right_drive_direction_forward").value() ? DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
frontDrive.setDirection(hardwareConfig("front_drive_direction_forward").value() ? DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE);
|
||||
backDrive.setDirection(hardwareConfig("back_drive_direction_forward").value() ? DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
liftDrive.setDirection(hardwareConfig("lift_drive_direction_forward").value() ? DcMotorSimple.Direction.FORWARD : DcMotorSimple.Direction.REVERSE);
|
||||
|
||||
// RUNMODE
|
||||
leftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); leftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
rightDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); rightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
frontDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); frontDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
backDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); backDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
liftDrive.setMode(DcMotor.RunMode.STOP_AND_RESET_ENCODER); liftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
// ZERO POWER BEHAVIOR
|
||||
leftDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
rightDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
frontDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
backDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
liftDrive.setZeroPowerBehavior(DcMotor.ZeroPowerBehavior.BRAKE);
|
||||
|
||||
// SERVOS (POSITIONAL)
|
||||
// Gripper
|
||||
gripper.setDirection(hardwareConfig("gripper_direction_forward").value() ? Servo.Direction.FORWARD : Servo.Direction.REVERSE);
|
||||
gripper.setPosition(hardwareConfig("gripper_initial_position").value());
|
||||
|
||||
// Wrist
|
||||
wrist.setDirection(hardwareConfig("wrist_direction_forward").value() ? Servo.Direction.FORWARD : Servo.Direction.REVERSE);
|
||||
wrist.setPosition(hardwareConfig("wrist_initial_position").value());
|
||||
|
||||
// SENSORS
|
||||
// COLOR SENSORS
|
||||
indicatorA.enableLed(false);
|
||||
indicatorB.enableLed(false);
|
||||
|
||||
// IMU
|
||||
IMU.Parameters parameters = new IMU.Parameters(
|
||||
new RevHubOrientationOnRobot(
|
||||
RevHubOrientationOnRobot.LogoFacingDirection.UP,
|
||||
RevHubOrientationOnRobot.UsbFacingDirection.FORWARD));
|
||||
|
||||
imu.initialize(parameters);
|
||||
}
|
||||
|
||||
public void standardTelemetry() {
|
||||
// Motor Powers
|
||||
engine.telemetry.addLine("Motor Powers");
|
||||
engine.telemetry.addData(" Left Drive", leftDrive.getPower());
|
||||
engine.telemetry.addData(" Right Drive", rightDrive.getPower());
|
||||
|
||||
engine.telemetry.addData(" Front Drive", frontDrive.getPower());
|
||||
engine.telemetry.addData(" Back Drive", backDrive.getPower());
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
engine.telemetry.addData(" Lift Drive", backDrive.getPower());
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
// Motor Positions
|
||||
engine.telemetry.addLine("Motor Positions");
|
||||
engine.telemetry.addData(" Left Drive", "%d (%.2f in)", leftDrive.getCurrentPosition(), ticksToUnit(DistanceUnit.INCH, leftDrive.getCurrentPosition()));
|
||||
engine.telemetry.addData(" Right Drive", "%d (%.2f in)", rightDrive.getCurrentPosition(), ticksToUnit(DistanceUnit.INCH, rightDrive.getCurrentPosition()));
|
||||
|
||||
engine.telemetry.addData(" Front Drive", "%d (%.2f in)", frontDrive.getCurrentPosition(), ticksToUnit(DistanceUnit.INCH, frontDrive.getCurrentPosition()));
|
||||
engine.telemetry.addData(" Back Drive", "%d (%.2f in)", backDrive.getCurrentPosition(), ticksToUnit(DistanceUnit.INCH, backDrive.getCurrentPosition()));
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
engine.telemetry.addData(" Lift Drive", "%d (%.2d degrees)", leftDrive.getCurrentPosition(), ticksToAngle(liftDrive.getCurrentPosition()));
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
// Motor Currents
|
||||
engine.telemetry.addLine("Motor Currents (AMPS)");
|
||||
engine.telemetry.addData(" Left Drive", leftDrive.getCurrent(CurrentUnit.AMPS));
|
||||
engine.telemetry.addData(" Right Drive", rightDrive.getCurrent(CurrentUnit.AMPS));
|
||||
|
||||
engine.telemetry.addData(" Front Drive", frontDrive.getCurrent(CurrentUnit.AMPS));
|
||||
engine.telemetry.addData(" Back Drive", backDrive.getCurrent(CurrentUnit.AMPS));
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
engine.telemetry.addData(" Lift Drive", backDrive.getCurrent(CurrentUnit.AMPS));
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
// Motor Directions
|
||||
engine.telemetry.addLine("Motor Directions");
|
||||
engine.telemetry.addData(" Left Drive", leftDrive.getDirection());
|
||||
engine.telemetry.addData(" Right Drive", rightDrive.getDirection());
|
||||
|
||||
engine.telemetry.addData(" Front Drive", frontDrive.getDirection());
|
||||
engine.telemetry.addData(" Back Drive", backDrive.getDirection());
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
engine.telemetry.addData(" Lift Drive", backDrive.getDirection());
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
// Servos
|
||||
engine.telemetry.addLine("Servos");
|
||||
engine.telemetry.addData(" Gripper Direction", gripper.getDirection());
|
||||
engine.telemetry.addData(" Gripper Position", gripper.getPosition());
|
||||
engine.telemetry.addData(" Gripper Enabled", gripper.isPwmEnabled());
|
||||
engine.telemetry.addLine();
|
||||
engine.telemetry.addData(" Wrist Direction", wrist.getDirection());
|
||||
engine.telemetry.addData(" Wrist Position", wrist.getPosition());
|
||||
engine.telemetry.addData(" Wrist Enabled", wrist.isPwmEnabled());
|
||||
|
||||
engine.telemetry.addLine();
|
||||
|
||||
// Sensors / IMU
|
||||
engine.telemetry.addLine("IMU");
|
||||
engine.telemetry.addData(" Facing", facing());
|
||||
engine.telemetry.addData(" Turn Rate", turnRate());
|
||||
}
|
||||
|
||||
public TimeCraftersConfiguration getConfiguration() {
|
||||
return configuration;
|
||||
}
|
||||
|
||||
// For: Drive Wheels
|
||||
public int unitToTicks(DistanceUnit unit, double distance) {
|
||||
double inches = unit.toInches(unit.fromUnit(unit, distance)); // NOTE: UNTESTED
|
||||
|
||||
// FIXME: This should be stored as a presudo constant at initialization
|
||||
double wheelRadius = tuningConfig("wheel_radius").value();
|
||||
double gearRatio = tuningConfig("wheel_gear_ratio").value();
|
||||
double ticksPerRevolution = tuningConfig("wheel_ticks_per_revolution").value();
|
||||
|
||||
return 0;
|
||||
}
|
||||
|
||||
// For: Drive Wheels
|
||||
public double ticksToUnit(DistanceUnit unit, int ticks) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// For: Lift Arm
|
||||
public int angleToTicks(double angle) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
// For: Lift Arm
|
||||
public double ticksToAngle(int ticks) {
|
||||
return 0;
|
||||
}
|
||||
|
||||
public Variable hardwareConfig(String variableName) {
|
||||
Action hardwareConfiguration = configuration.action("Robot", "Hardware");
|
||||
|
||||
for (Variable v : hardwareConfiguration.getVariables()) {
|
||||
if (variableName.trim().equals(v.name)) {
|
||||
return v;
|
||||
}
|
||||
}
|
||||
|
||||
throw new RuntimeException("Failed to find variable with name: " + variableName + " in group: Robot, action: Hardware");
|
||||
}
|
||||
|
||||
public Variable tuningConfig(String variableName) {
|
||||
Action action = configuration.action("Robot", "Tuning");
|
||||
|
||||
for (Variable v : action.getVariables()) {
|
||||
if (variableName.trim().equals(v.name)) {
|
||||
return v;
|
||||
}
|
||||
}
|
||||
|
||||
throw new RuntimeException("Failed to find variable with name: " + variableName + " in group: Robot, action: Tuning");
|
||||
}
|
||||
|
||||
// TODO: Convert to 360 degree range with +90 degrees being on the RIGHT
|
||||
public double facing() {
|
||||
// FIXME: Apply imuAngleOffset
|
||||
return imu.getRobotYawPitchRollAngles().getYaw(AngleUnit.DEGREES);
|
||||
}
|
||||
|
||||
public double turnRate() {
|
||||
return imu.getRobotAngularVelocity(AngleUnit.DEGREES).yRotationRate; // NOTE: UNTESTED
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,23 @@
|
||||
package org.timecrafters.minibots.cyberarm.chiron.engines;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.TimeCraftersConfigurationTool.library.TimeCraftersConfiguration;
|
||||
import org.timecrafters.minibots.cyberarm.chiron.Robot;
|
||||
import org.timecrafters.minibots.cyberarm.chiron.states.DriverControlState;
|
||||
|
||||
public class TeleOpEngine extends CyberarmEngine {
|
||||
private Robot robot;
|
||||
@Override
|
||||
public void setup() {
|
||||
this.robot = new Robot(this, new TimeCraftersConfiguration("CHIRON"));
|
||||
|
||||
addState(new DriverControlState(robot));
|
||||
}
|
||||
|
||||
@Override
|
||||
public void loop() {
|
||||
super.loop();
|
||||
|
||||
robot.standardTelemetry();
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,284 @@
|
||||
package org.timecrafters.minibots.cyberarm.chiron.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.cyberarm.engine.V2.GamepadChecker;
|
||||
import org.timecrafters.minibots.cyberarm.chiron.Robot;
|
||||
|
||||
public class DriverControlState extends CyberarmState {
|
||||
private final Robot robot;
|
||||
private final GamepadChecker controller;
|
||||
private final double releaseConfirmationDelay;
|
||||
private double lastLiftManualControlTime = 0, lastWristManualControlTime = 0, lastLEDStatusAnimationTime = 0;
|
||||
private boolean LEDStatusToggle = false;
|
||||
|
||||
public DriverControlState(Robot robot) {
|
||||
this.robot = robot;
|
||||
this.controller = new GamepadChecker(engine, engine.gamepad1);
|
||||
|
||||
this.releaseConfirmationDelay = robot.tuningConfig("cone_release_confirmation_delay").value(); // ms
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
double forwardSpeed = engine.gamepad1.left_stick_y * -1;
|
||||
double rightSpeed = engine.gamepad1.right_stick_x;
|
||||
double forwardAngle = robot.facing();
|
||||
|
||||
robot.status = Robot.Status.OKAY;
|
||||
|
||||
move(forwardAngle, forwardSpeed, rightSpeed);
|
||||
liftManualControl();
|
||||
wristManualControl();
|
||||
|
||||
automatics();
|
||||
|
||||
controller.update();
|
||||
}
|
||||
|
||||
// FIXME: replace .setPower with .setVelocity
|
||||
private void move(double forwardAngle, double forwardSpeed, double rightSpeed) {
|
||||
if (robot.automaticAntiTipActive || robot.hardwareFault) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (rightSpeed == 0 && forwardSpeed != 0) { // DRIVE STRAIGHT
|
||||
robot.leftDrive.setPower(forwardSpeed);
|
||||
robot.rightDrive.setPower(forwardSpeed);
|
||||
|
||||
robot.frontDrive.setPower(0);
|
||||
robot.backDrive.setPower(0);
|
||||
|
||||
} else if (rightSpeed != 0 && forwardSpeed == 0) { // TURN IN PLACE
|
||||
robot.leftDrive.setPower(rightSpeed);
|
||||
robot.rightDrive.setPower(-rightSpeed);
|
||||
|
||||
robot.frontDrive.setPower(rightSpeed);
|
||||
robot.backDrive.setPower(-rightSpeed);
|
||||
|
||||
} else if (rightSpeed != 0 && forwardSpeed != 0) { // ANGLE DRIVE
|
||||
// TODO
|
||||
stopDrive();
|
||||
} else {
|
||||
stopDrive();
|
||||
}
|
||||
}
|
||||
|
||||
private void stopDrive() {
|
||||
robot.leftDrive.setPower(0);
|
||||
robot.rightDrive.setPower(0);
|
||||
|
||||
robot.frontDrive.setPower(0);
|
||||
robot.backDrive.setPower(0);
|
||||
}
|
||||
|
||||
private void liftManualControl() {
|
||||
if (robot.hardwareFault) {
|
||||
return;
|
||||
}
|
||||
|
||||
robot.status = Robot.Status.WARNING;
|
||||
|
||||
double stepInterval = robot.tuningConfig("lift_manual_step_interval").value();
|
||||
int stepSize = robot.tuningConfig("lift_manual_step_size").value();
|
||||
|
||||
if ((engine.gamepad1.left_trigger > 0 || engine.gamepad1.right_trigger > 0) && runTime() - lastWristManualControlTime >= stepInterval) {
|
||||
lastWristManualControlTime = runTime();
|
||||
|
||||
if (engine.gamepad1.left_trigger > 0) { // Lift DOWN
|
||||
// robot.liftDrive.setVelocity(5, AngleUnit.DEGREES);
|
||||
robot.liftDrive.setTargetPosition(robot.leftDrive.getTargetPosition() - stepSize);
|
||||
|
||||
} else if (engine.gamepad1.right_trigger > 0) { // Lift UP
|
||||
robot.liftDrive.setTargetPosition(robot.leftDrive.getTargetPosition() + stepSize);
|
||||
}
|
||||
}
|
||||
|
||||
// FIXME: Detect when the triggers have been released and park lift arm at the current position
|
||||
}
|
||||
|
||||
private void wristManualControl() {
|
||||
if (robot.hardwareFault) {
|
||||
return;
|
||||
}
|
||||
|
||||
double stepInterval = robot.tuningConfig("wrist_manual_step_interval").value();
|
||||
double stepSize = robot.tuningConfig("wrist_manual_step_size").value();
|
||||
|
||||
if ((engine.gamepad1.dpad_left || engine.gamepad1.dpad_right) && runTime() - lastLiftManualControlTime >= stepInterval) {
|
||||
lastLiftManualControlTime = runTime();
|
||||
|
||||
if (engine.gamepad1.dpad_left) { // Wrist Left
|
||||
robot.wrist.setPosition(robot.wrist.getPosition() - stepSize);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right) { // Wrist Right
|
||||
robot.wrist.setPosition(robot.wrist.getPosition() + stepSize);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
private void stopLift() {
|
||||
robot.liftDrive.setPower(0);
|
||||
}
|
||||
|
||||
private void automatics() {
|
||||
automaticWrist();
|
||||
automaticAntiTip(); // NO OP
|
||||
automaticHardwareMonitor();
|
||||
|
||||
automaticLEDStatus();
|
||||
}
|
||||
|
||||
private void automaticWrist() {
|
||||
if (robot.wristManuallyControlled) {
|
||||
return;
|
||||
}
|
||||
|
||||
if (robot.ticksToAngle(robot.liftDrive.getCurrentPosition()) >= 50) {
|
||||
robot.wrist.setPosition(robot.hardwareConfig("wrist_deposit_position").value());
|
||||
} else {
|
||||
robot.wrist.setPosition(robot.hardwareConfig("wrist_initial_position").value());
|
||||
}
|
||||
}
|
||||
|
||||
// NO-OP
|
||||
private void automaticAntiTip() {
|
||||
// TODO: Take over drivetrain if robot starts to tip past a preconfigured point
|
||||
// return control if past point of no-return or tipping is no longer a concern
|
||||
|
||||
// TODO: Calculate motion inverse to the normal of current direction
|
||||
}
|
||||
|
||||
private void automaticHardwareMonitor() {
|
||||
// Check that encoders are updating as expect, etc.
|
||||
|
||||
// NOTE: Robot should prevent/halt all movement in the event of a fault
|
||||
// robot.hardwareFault = true;
|
||||
|
||||
if (robot.hardwareFault) {
|
||||
robot.status = Robot.Status.DANGER;
|
||||
|
||||
stopDrive();
|
||||
stopLift();
|
||||
}
|
||||
}
|
||||
|
||||
private void automaticLEDStatus() {
|
||||
switch (robot.status) {
|
||||
case OKAY:
|
||||
robot.indicatorA.enableLed(false);
|
||||
robot.indicatorB.enableLed(false);
|
||||
break;
|
||||
|
||||
case MONITORING:
|
||||
robot.indicatorA.enableLed(true);
|
||||
robot.indicatorB.enableLed(true);
|
||||
break;
|
||||
|
||||
case WARNING:
|
||||
if (runTime() - lastLEDStatusAnimationTime >= 500){
|
||||
lastLEDStatusAnimationTime = runTime();
|
||||
LEDStatusToggle = !LEDStatusToggle;
|
||||
|
||||
robot.indicatorA.enableLed(LEDStatusToggle);
|
||||
robot.indicatorA.enableLed(!LEDStatusToggle);
|
||||
}
|
||||
break;
|
||||
|
||||
case DANGER:
|
||||
if (runTime() - lastLEDStatusAnimationTime >= 200){
|
||||
lastLEDStatusAnimationTime = runTime();
|
||||
LEDStatusToggle = !LEDStatusToggle;
|
||||
|
||||
robot.indicatorA.enableLed(LEDStatusToggle);
|
||||
robot.indicatorA.enableLed(LEDStatusToggle);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
private void liftPosition(Robot.LiftPosition position) {
|
||||
if (robot.hardwareFault) {
|
||||
return;
|
||||
}
|
||||
|
||||
robot.status = Robot.Status.WARNING;
|
||||
|
||||
switch (position) {
|
||||
case COLLECT:
|
||||
robot.liftDrive.setTargetPosition(robot.angleToTicks(120));
|
||||
break;
|
||||
|
||||
case GROUND:
|
||||
robot.liftDrive.setTargetPosition(robot.angleToTicks(100));
|
||||
break;
|
||||
|
||||
case LOW:
|
||||
robot.liftDrive.setTargetPosition(robot.angleToTicks(80));
|
||||
break;
|
||||
|
||||
case MEDIUM:
|
||||
robot.liftDrive.setTargetPosition(robot.angleToTicks(35));
|
||||
break;
|
||||
|
||||
case HIGH:
|
||||
robot.liftDrive.setTargetPosition(robot.angleToTicks(15));
|
||||
break;
|
||||
|
||||
default:
|
||||
throw new RuntimeException("Unexpected lift position!");
|
||||
}
|
||||
}
|
||||
|
||||
private void gripperOpen() {
|
||||
robot.gripper.setPosition(robot.hardwareConfig("gripper_open_position").value());
|
||||
}
|
||||
|
||||
private void gripperClosed() {
|
||||
robot.gripper.setPosition(robot.hardwareConfig("gripper_closed_position").value());
|
||||
}
|
||||
|
||||
@Override
|
||||
public void buttonDown(Gamepad gamepad, String button) {
|
||||
if (gamepad != engine.gamepad1) {
|
||||
return;
|
||||
}
|
||||
|
||||
// Gripper Control
|
||||
if (button.equals("left_bumper")) {
|
||||
gripperOpen();
|
||||
} else if (button.equals("right_bumper")) {
|
||||
gripperClosed();
|
||||
}
|
||||
|
||||
// Wrist Control
|
||||
if (button.equals("dpad_down")) {
|
||||
robot.wristManuallyControlled = false;
|
||||
|
||||
robot.wrist.setPosition(robot.hardwareConfig("wrist_deposit_position").value());
|
||||
} else if (button.equals("dpad_up")) {
|
||||
robot.wristManuallyControlled = false;
|
||||
|
||||
robot.wrist.setPosition(robot.hardwareConfig("wrist_initial_position").value());
|
||||
}
|
||||
|
||||
// Automatic Lift Control
|
||||
if (button.equals("a")) {
|
||||
liftPosition(Robot.LiftPosition.COLLECT);
|
||||
} else if (button.equals("x")) {
|
||||
liftPosition(Robot.LiftPosition.GROUND);
|
||||
} else if (button.equals("b")) {
|
||||
liftPosition(Robot.LiftPosition.LOW);
|
||||
} else if (button.equals("y")) {
|
||||
liftPosition(Robot.LiftPosition.MEDIUM);
|
||||
}
|
||||
}
|
||||
|
||||
@Override
|
||||
public void buttonUp(Gamepad gamepad, String button) {
|
||||
if (gamepad != engine.gamepad1) {
|
||||
return;
|
||||
}
|
||||
}
|
||||
}
|
||||
@@ -1,4 +0,0 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
public class BlitzkriegState {
|
||||
}
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
@@ -1,11 +1,10 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.states.FieldOrientedDrive;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.states.FieldOrientedDrive;
|
||||
import org.timecrafters.minibots.states.MecanumRobot;
|
||||
|
||||
@TeleOp(name = "Field Oriented Drive")
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.minibots.cyberarm.MecanumMinibot;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumMinibotTeleOpState;
|
||||
import org.timecrafters.minibots.MecanumMinibot;
|
||||
import org.timecrafters.minibots.states.MecanumMinibotTeleOpState;
|
||||
|
||||
@TeleOp(name = "MecanumMinibot TeleOp", group = "minibot")
|
||||
public class MecanumMinibotTeleOpEngine extends CyberarmEngine {
|
||||
@@ -1,10 +1,10 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.cyberarm.states.Mecanum_Robot_State;
|
||||
import org.timecrafters.minibots.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.states.Mecanum_Robot_State;
|
||||
|
||||
@TeleOp(name = "Mecanum Robot TeleOp")
|
||||
|
||||
@@ -1,11 +1,11 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.Disabled;
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.cyberarm.states.Mecanum_Fancy_Drive_State;
|
||||
import org.timecrafters.minibots.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.states.Mecanum_Fancy_Drive_State;
|
||||
@Disabled
|
||||
@TeleOp(name = "Fancy Drive TeleOp")
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.minibots.cyberarm.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.cyberarm.states.PingPongState;
|
||||
import org.timecrafters.minibots.states.MecanumRobot;
|
||||
import org.timecrafters.minibots.states.PingPongState;
|
||||
|
||||
@TeleOp (name = "Sodi PingPong")
|
||||
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
@@ -1,10 +1,10 @@
|
||||
package org.timecrafters.minibots.cyberarm.engines;
|
||||
package org.timecrafters.minibots.engines;
|
||||
|
||||
import com.qualcomm.robotcore.eventloop.opmode.TeleOp;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
import org.timecrafters.minibots.cyberarm.pickle_minibot_general;
|
||||
import org.timecrafters.minibots.cyberarm.states.pickle_teleop_state;
|
||||
import org.timecrafters.minibots.pickle_minibot_general;
|
||||
import org.timecrafters.minibots.states.pickle_teleop_state;
|
||||
|
||||
@TeleOp (name = "pickle_minibot teleop", group = "minibot")
|
||||
public class pickle_engine extends CyberarmEngine {
|
||||
@@ -1,4 +1,4 @@
|
||||
package org.timecrafters.minibots.cyberarm;
|
||||
package org.timecrafters.minibots;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
@@ -1,22 +1,22 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class AutonomousReversalExperiment extends CyberarmState {
|
||||
|
||||
MecanumRobot robot;
|
||||
public AutonomousReversalExperiment (MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
if (engine.gamepad1.dpad_up) {
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class AutonomousReversalExperiment extends CyberarmState {
|
||||
|
||||
MecanumRobot robot;
|
||||
public AutonomousReversalExperiment (MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
if (engine.gamepad1.dpad_up) {
|
||||
|
||||
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -0,0 +1,4 @@
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
public class BlitzkriegState {
|
||||
}
|
||||
@@ -1,67 +1,67 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
//adb connect 192.168.43.1
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class FieldOrientedDrive extends CyberarmState {
|
||||
|
||||
MecanumRobot robot;
|
||||
BNO055IMU imu;
|
||||
|
||||
public FieldOrientedDrive(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void init() {
|
||||
|
||||
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
|
||||
// parameters.loggingEnabled = true;
|
||||
// parameters.loggingTag = "IMU";
|
||||
imu = engine.hardwareMap.get(BNO055IMU.class, "imu");
|
||||
imu.initialize(parameters);
|
||||
|
||||
parameters.angleUnit = BNO055IMU.AngleUnit.RADIANS;
|
||||
|
||||
imu.initialize(parameters);
|
||||
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.GREEN);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.LIGHT_CHASE_BLUE);
|
||||
|
||||
double y = -engine.gamepad1.left_stick_y; // Remember, this is reversed!
|
||||
double x = engine.gamepad1.left_stick_x * 1.1; // Counteract imperfect strafing
|
||||
double rx = engine.gamepad1.right_stick_x;
|
||||
|
||||
// Read inverse IMU heading, as the IMU heading is CW positive
|
||||
|
||||
double botHeading = -imu.getAngularOrientation().firstAngle;
|
||||
|
||||
double rotX = x * Math.cos(botHeading) - y * Math.sin(botHeading);
|
||||
double rotY = x * Math.sin(botHeading) + y * Math.cos(botHeading);
|
||||
|
||||
// Denominator is the largest motor power (absolute value) or 1
|
||||
// This ensures all the powers maintain the same ratio, but only when
|
||||
// at least one is out of the range [-1, 1]
|
||||
|
||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||
double frontLeftPower = (rotY + rotX + rx) / denominator;
|
||||
double backLeftPower = (rotY - rotX + rx) / denominator;
|
||||
double frontRightPower = (rotY - rotX - rx) / denominator;
|
||||
double backRightPower = (rotY + rotX - rx) / denominator;
|
||||
|
||||
robot.frontLeftDrive.setPower(frontLeftPower * .95);
|
||||
robot.backRightDrive.setPower(backLeftPower * .95);
|
||||
robot.frontRightDrive.setPower(frontRightPower * 1);
|
||||
robot.backRightDrive.setPower(backRightPower * 1);
|
||||
|
||||
}
|
||||
}
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
//adb connect 192.168.43.1
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class FieldOrientedDrive extends CyberarmState {
|
||||
|
||||
MecanumRobot robot;
|
||||
BNO055IMU imu;
|
||||
|
||||
public FieldOrientedDrive(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void init() {
|
||||
|
||||
BNO055IMU.Parameters parameters = new BNO055IMU.Parameters();
|
||||
// parameters.loggingEnabled = true;
|
||||
// parameters.loggingTag = "IMU";
|
||||
imu = engine.hardwareMap.get(BNO055IMU.class, "imu");
|
||||
imu.initialize(parameters);
|
||||
|
||||
parameters.angleUnit = BNO055IMU.AngleUnit.RADIANS;
|
||||
|
||||
imu.initialize(parameters);
|
||||
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.GREEN);
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.LIGHT_CHASE_BLUE);
|
||||
|
||||
double y = -engine.gamepad1.left_stick_y; // Remember, this is reversed!
|
||||
double x = engine.gamepad1.left_stick_x * 1.1; // Counteract imperfect strafing
|
||||
double rx = engine.gamepad1.right_stick_x;
|
||||
|
||||
// Read inverse IMU heading, as the IMU heading is CW positive
|
||||
|
||||
double botHeading = -imu.getAngularOrientation().firstAngle;
|
||||
|
||||
double rotX = x * Math.cos(botHeading) - y * Math.sin(botHeading);
|
||||
double rotY = x * Math.sin(botHeading) + y * Math.cos(botHeading);
|
||||
|
||||
// Denominator is the largest motor power (absolute value) or 1
|
||||
// This ensures all the powers maintain the same ratio, but only when
|
||||
// at least one is out of the range [-1, 1]
|
||||
|
||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||
double frontLeftPower = (rotY + rotX + rx) / denominator;
|
||||
double backLeftPower = (rotY - rotX + rx) / denominator;
|
||||
double frontRightPower = (rotY - rotX - rx) / denominator;
|
||||
double backRightPower = (rotY + rotX - rx) / denominator;
|
||||
|
||||
robot.frontLeftDrive.setPower(frontLeftPower * .95);
|
||||
robot.backRightDrive.setPower(backLeftPower * .95);
|
||||
robot.frontRightDrive.setPower(frontRightPower * 1);
|
||||
robot.backRightDrive.setPower(backRightPower * 1);
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1,10 +1,10 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import com.qualcomm.robotcore.hardware.Gamepad;
|
||||
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.MecanumMinibot;
|
||||
import org.timecrafters.minibots.MecanumMinibot;
|
||||
|
||||
|
||||
public class MecanumMinibotTeleOpState extends CyberarmState {
|
||||
@@ -1,50 +1,50 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.hardware.rev.Rev2mDistanceSensor;
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
|
||||
public class MecanumRobot {
|
||||
|
||||
private CyberarmEngine engine;
|
||||
|
||||
public DcMotor frontLeftDrive, frontRightDrive, backLeftDrive, backRightDrive;
|
||||
|
||||
public RevBlinkinLedDriver ledDriver;
|
||||
|
||||
public MecanumRobot(CyberarmEngine engine) {
|
||||
this.engine = engine;
|
||||
|
||||
setupRobot();
|
||||
}
|
||||
|
||||
private void setupRobot() {
|
||||
|
||||
//motors configuration
|
||||
frontLeftDrive = engine.hardwareMap.dcMotor.get("front left");
|
||||
frontRightDrive = engine.hardwareMap.dcMotor.get("front right");
|
||||
backRightDrive = engine.hardwareMap.dcMotor.get("back left");
|
||||
backLeftDrive = engine.hardwareMap.dcMotor.get("back right");
|
||||
ledDriver = engine.hardwareMap.get(RevBlinkinLedDriver.class, "lights");
|
||||
|
||||
//motors direction and encoders
|
||||
frontLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
frontLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
frontRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||
frontRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
backLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
backLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
backRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||
backRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
}
|
||||
}
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import com.qualcomm.hardware.bosch.BNO055IMU;
|
||||
import com.qualcomm.hardware.rev.Rev2mDistanceSensor;
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
import com.qualcomm.robotcore.hardware.CRServo;
|
||||
import com.qualcomm.robotcore.hardware.DcMotor;
|
||||
import com.qualcomm.robotcore.hardware.DcMotorSimple;
|
||||
import com.qualcomm.robotcore.hardware.Servo;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmEngine;
|
||||
|
||||
public class MecanumRobot {
|
||||
|
||||
private CyberarmEngine engine;
|
||||
|
||||
public DcMotor frontLeftDrive, frontRightDrive, backLeftDrive, backRightDrive;
|
||||
|
||||
public RevBlinkinLedDriver ledDriver;
|
||||
|
||||
public MecanumRobot(CyberarmEngine engine) {
|
||||
this.engine = engine;
|
||||
|
||||
setupRobot();
|
||||
}
|
||||
|
||||
private void setupRobot() {
|
||||
|
||||
//motors configuration
|
||||
frontLeftDrive = engine.hardwareMap.dcMotor.get("front left");
|
||||
frontRightDrive = engine.hardwareMap.dcMotor.get("front right");
|
||||
backRightDrive = engine.hardwareMap.dcMotor.get("back left");
|
||||
backLeftDrive = engine.hardwareMap.dcMotor.get("back right");
|
||||
ledDriver = engine.hardwareMap.get(RevBlinkinLedDriver.class, "lights");
|
||||
|
||||
//motors direction and encoders
|
||||
frontLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
frontLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
frontRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||
frontRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
backLeftDrive.setDirection(DcMotorSimple.Direction.REVERSE);
|
||||
backLeftDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
backRightDrive.setDirection(DcMotorSimple.Direction.FORWARD);
|
||||
backRightDrive.setMode(DcMotor.RunMode.RUN_USING_ENCODER);
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1,105 +1,104 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.firstinspires.ftc.robotcore.external.navigation.DistanceUnit;
|
||||
|
||||
|
||||
public class Mecanum_Fancy_Drive_State extends CyberarmState {
|
||||
|
||||
private final MecanumRobot robot;
|
||||
public boolean A;
|
||||
public boolean X;
|
||||
public boolean Y;
|
||||
private double drivePower = 1;
|
||||
private boolean bprev;
|
||||
|
||||
|
||||
public Mecanum_Fancy_Drive_State(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
@Override
|
||||
public void init() {
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.GREEN);
|
||||
}
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
//Gamepad Read
|
||||
|
||||
A = engine.gamepad1.a;
|
||||
X = engine.gamepad1.x;
|
||||
Y = engine.gamepad1.y;
|
||||
|
||||
//Drivetrain Variables
|
||||
double y = -engine.gamepad1.left_stick_y; // Remember, this is reversed! because of the negative
|
||||
double x = engine.gamepad1.left_stick_x * 1.1; // Counteract imperfect strafing
|
||||
double rx = engine.gamepad1.right_stick_x;
|
||||
|
||||
//toggle for drive speed
|
||||
boolean b = engine.gamepad1.b;
|
||||
if (b && !bprev) {
|
||||
if (drivePower == 1) {
|
||||
drivePower = 0.5;
|
||||
} else {
|
||||
drivePower = 1;
|
||||
}
|
||||
}
|
||||
bprev = b;
|
||||
|
||||
// Denominator is the largest motor power (absolute value) or 1
|
||||
// This ensures all the powers maintain the same ratio, but only when
|
||||
// at least one is out of the range [-1, 1]
|
||||
|
||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||
double frontLeftPower = (y + x + rx) / denominator;
|
||||
double backLeftPower = (y - x + rx) / denominator;
|
||||
double frontRightPower = (y - x - rx) / denominator;
|
||||
double backRightPower = (y + x - rx) / denominator;
|
||||
|
||||
// As I programed this and ran it, I realized everything was backwards
|
||||
// in direction so to fix that i either went in the robot object state and reversed
|
||||
// directions on drive motors or put a negative in behind the joystick power to reverse it.
|
||||
// I put negatives in to reverse it because it was the easiest at the moment.
|
||||
|
||||
robot.frontLeftDrive.setPower(frontLeftPower * drivePower);
|
||||
robot.backLeftDrive.setPower(backLeftPower * drivePower);
|
||||
robot.frontRightDrive.setPower(frontRightPower * drivePower);
|
||||
robot.backRightDrive.setPower(backRightPower * drivePower);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//-------------------------------------------------------------------------------------------------------------------
|
||||
// LIGHT CONTROLS
|
||||
|
||||
|
||||
if (drivePower == 1) {
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.LIGHT_CHASE_BLUE);
|
||||
}
|
||||
|
||||
else if (drivePower == 0.5){
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.YELLOW);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//------------------------------------------------------------------------------------------------------------------------------------
|
||||
// Telemetry Data
|
||||
|
||||
|
||||
@Override
|
||||
public void telemetry() {
|
||||
engine.telemetry.addData("Speed", drivePower);
|
||||
engine.telemetry.addData("FrontLeftEncoder", robot.frontLeftDrive.getCurrentPosition());
|
||||
engine.telemetry.addData("FrontRightEncoder", robot.frontRightDrive.getCurrentPosition());
|
||||
engine.telemetry.addData("BackLeftEncoder", robot.backLeftDrive.getCurrentPosition());
|
||||
engine.telemetry.addData("BackRightEncoder", robot.backRightDrive.getCurrentPosition());
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import com.qualcomm.hardware.rev.RevBlinkinLedDriver;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
|
||||
public class Mecanum_Fancy_Drive_State extends CyberarmState {
|
||||
|
||||
private final MecanumRobot robot;
|
||||
public boolean A;
|
||||
public boolean X;
|
||||
public boolean Y;
|
||||
private double drivePower = 1;
|
||||
private boolean bprev;
|
||||
|
||||
|
||||
public Mecanum_Fancy_Drive_State(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
@Override
|
||||
public void init() {
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.GREEN);
|
||||
}
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
//Gamepad Read
|
||||
|
||||
A = engine.gamepad1.a;
|
||||
X = engine.gamepad1.x;
|
||||
Y = engine.gamepad1.y;
|
||||
|
||||
//Drivetrain Variables
|
||||
double y = -engine.gamepad1.left_stick_y; // Remember, this is reversed! because of the negative
|
||||
double x = engine.gamepad1.left_stick_x * 1.1; // Counteract imperfect strafing
|
||||
double rx = engine.gamepad1.right_stick_x;
|
||||
|
||||
//toggle for drive speed
|
||||
boolean b = engine.gamepad1.b;
|
||||
if (b && !bprev) {
|
||||
if (drivePower == 1) {
|
||||
drivePower = 0.5;
|
||||
} else {
|
||||
drivePower = 1;
|
||||
}
|
||||
}
|
||||
bprev = b;
|
||||
|
||||
// Denominator is the largest motor power (absolute value) or 1
|
||||
// This ensures all the powers maintain the same ratio, but only when
|
||||
// at least one is out of the range [-1, 1]
|
||||
|
||||
double denominator = Math.max(Math.abs(y) + Math.abs(x) + Math.abs(rx), 1);
|
||||
double frontLeftPower = (y + x + rx) / denominator;
|
||||
double backLeftPower = (y - x + rx) / denominator;
|
||||
double frontRightPower = (y - x - rx) / denominator;
|
||||
double backRightPower = (y + x - rx) / denominator;
|
||||
|
||||
// As I programed this and ran it, I realized everything was backwards
|
||||
// in direction so to fix that i either went in the robot object state and reversed
|
||||
// directions on drive motors or put a negative in behind the joystick power to reverse it.
|
||||
// I put negatives in to reverse it because it was the easiest at the moment.
|
||||
|
||||
robot.frontLeftDrive.setPower(frontLeftPower * drivePower);
|
||||
robot.backLeftDrive.setPower(backLeftPower * drivePower);
|
||||
robot.frontRightDrive.setPower(frontRightPower * drivePower);
|
||||
robot.backRightDrive.setPower(backRightPower * drivePower);
|
||||
|
||||
|
||||
|
||||
|
||||
|
||||
//-------------------------------------------------------------------------------------------------------------------
|
||||
// LIGHT CONTROLS
|
||||
|
||||
|
||||
if (drivePower == 1) {
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.LIGHT_CHASE_BLUE);
|
||||
}
|
||||
|
||||
else if (drivePower == 0.5){
|
||||
robot.ledDriver.setPattern(RevBlinkinLedDriver.BlinkinPattern.YELLOW);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
//------------------------------------------------------------------------------------------------------------------------------------
|
||||
// Telemetry Data
|
||||
|
||||
|
||||
@Override
|
||||
public void telemetry() {
|
||||
engine.telemetry.addData("Speed", drivePower);
|
||||
engine.telemetry.addData("FrontLeftEncoder", robot.frontLeftDrive.getCurrentPosition());
|
||||
engine.telemetry.addData("FrontRightEncoder", robot.frontRightDrive.getCurrentPosition());
|
||||
engine.telemetry.addData("BackLeftEncoder", robot.backLeftDrive.getCurrentPosition());
|
||||
engine.telemetry.addData("BackRightEncoder", robot.backRightDrive.getCurrentPosition());
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
@@ -1,117 +1,117 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class Mecanum_Robot_State extends CyberarmState {
|
||||
|
||||
// adb connect 192.168.43.1
|
||||
|
||||
private final MecanumRobot robot;
|
||||
private float maxSpeed = 1;
|
||||
private double halfSpeed = 0.5;
|
||||
|
||||
public Mecanum_Robot_State(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
if (engine.gamepad1.left_trigger > 0.5){
|
||||
|
||||
if (engine.gamepad1.left_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(halfSpeed);
|
||||
robot.frontRightDrive.setPower(-halfSpeed);
|
||||
robot.backLeftDrive.setPower(-halfSpeed);
|
||||
robot.frontLeftDrive.setPower(halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.right_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(-halfSpeed);
|
||||
robot.frontRightDrive.setPower(halfSpeed);
|
||||
robot.backLeftDrive.setPower(halfSpeed);
|
||||
robot.frontLeftDrive.setPower(-halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontLeftDrive.setPower(-halfSpeed);
|
||||
robot.backRightDrive.setPower(-halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontRightDrive.setPower(-halfSpeed);
|
||||
robot.backLeftDrive.setPower(-halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backLeftDrive.setPower(halfSpeed);
|
||||
robot.frontRightDrive.setPower(halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backRightDrive.setPower(halfSpeed);
|
||||
robot.frontLeftDrive.setPower(halfSpeed);
|
||||
|
||||
}
|
||||
|
||||
else {
|
||||
|
||||
robot.backRightDrive.setPower(engine.gamepad1.right_stick_y * halfSpeed) ;
|
||||
robot.frontRightDrive.setPower(engine.gamepad1.right_stick_y * halfSpeed);
|
||||
robot.backLeftDrive.setPower(engine.gamepad1.left_stick_y * halfSpeed);
|
||||
robot.frontLeftDrive.setPower(engine.gamepad1.left_stick_y * halfSpeed);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
else {
|
||||
|
||||
if (engine.gamepad1.left_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(maxSpeed);
|
||||
robot.frontRightDrive.setPower(-maxSpeed);
|
||||
robot.backLeftDrive.setPower(-maxSpeed);
|
||||
robot.frontLeftDrive.setPower(maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.right_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(-maxSpeed);
|
||||
robot.frontRightDrive.setPower(maxSpeed);
|
||||
robot.backLeftDrive.setPower(maxSpeed);
|
||||
robot.frontLeftDrive.setPower(-maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontLeftDrive.setPower(-maxSpeed);
|
||||
robot.backRightDrive.setPower(-maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontRightDrive.setPower(-maxSpeed);
|
||||
robot.backLeftDrive.setPower(-maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backLeftDrive.setPower(maxSpeed);
|
||||
robot.frontRightDrive.setPower(maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backRightDrive.setPower(maxSpeed);
|
||||
robot.frontLeftDrive.setPower(maxSpeed);
|
||||
|
||||
} else {
|
||||
|
||||
robot.backRightDrive.setPower(engine.gamepad1.right_stick_y * maxSpeed) ;
|
||||
robot.frontRightDrive.setPower(engine.gamepad1.right_stick_y * maxSpeed);
|
||||
robot.backLeftDrive.setPower(engine.gamepad1.left_stick_y * maxSpeed);
|
||||
robot.frontLeftDrive.setPower(engine.gamepad1.left_stick_y * maxSpeed);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class Mecanum_Robot_State extends CyberarmState {
|
||||
|
||||
// adb connect 192.168.43.1
|
||||
|
||||
private final MecanumRobot robot;
|
||||
private float maxSpeed = 1;
|
||||
private double halfSpeed = 0.5;
|
||||
|
||||
public Mecanum_Robot_State(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
if (engine.gamepad1.left_trigger > 0.5){
|
||||
|
||||
if (engine.gamepad1.left_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(halfSpeed);
|
||||
robot.frontRightDrive.setPower(-halfSpeed);
|
||||
robot.backLeftDrive.setPower(-halfSpeed);
|
||||
robot.frontLeftDrive.setPower(halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.right_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(-halfSpeed);
|
||||
robot.frontRightDrive.setPower(halfSpeed);
|
||||
robot.backLeftDrive.setPower(halfSpeed);
|
||||
robot.frontLeftDrive.setPower(-halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontLeftDrive.setPower(-halfSpeed);
|
||||
robot.backRightDrive.setPower(-halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontRightDrive.setPower(-halfSpeed);
|
||||
robot.backLeftDrive.setPower(-halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backLeftDrive.setPower(halfSpeed);
|
||||
robot.frontRightDrive.setPower(halfSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backRightDrive.setPower(halfSpeed);
|
||||
robot.frontLeftDrive.setPower(halfSpeed);
|
||||
|
||||
}
|
||||
|
||||
else {
|
||||
|
||||
robot.backRightDrive.setPower(engine.gamepad1.right_stick_y * halfSpeed) ;
|
||||
robot.frontRightDrive.setPower(engine.gamepad1.right_stick_y * halfSpeed);
|
||||
robot.backLeftDrive.setPower(engine.gamepad1.left_stick_y * halfSpeed);
|
||||
robot.frontLeftDrive.setPower(engine.gamepad1.left_stick_y * halfSpeed);
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
else {
|
||||
|
||||
if (engine.gamepad1.left_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(maxSpeed);
|
||||
robot.frontRightDrive.setPower(-maxSpeed);
|
||||
robot.backLeftDrive.setPower(-maxSpeed);
|
||||
robot.frontLeftDrive.setPower(maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.right_bumper) {
|
||||
|
||||
robot.backRightDrive.setPower(-maxSpeed);
|
||||
robot.frontRightDrive.setPower(maxSpeed);
|
||||
robot.backLeftDrive.setPower(maxSpeed);
|
||||
robot.frontLeftDrive.setPower(-maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontLeftDrive.setPower(-maxSpeed);
|
||||
robot.backRightDrive.setPower(-maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_up) {
|
||||
|
||||
robot.frontRightDrive.setPower(-maxSpeed);
|
||||
robot.backLeftDrive.setPower(-maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_right && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backLeftDrive.setPower(maxSpeed);
|
||||
robot.frontRightDrive.setPower(maxSpeed);
|
||||
|
||||
} else if (engine.gamepad1.dpad_left && engine.gamepad1.dpad_down) {
|
||||
|
||||
robot.backRightDrive.setPower(maxSpeed);
|
||||
robot.frontLeftDrive.setPower(maxSpeed);
|
||||
|
||||
} else {
|
||||
|
||||
robot.backRightDrive.setPower(engine.gamepad1.right_stick_y * maxSpeed) ;
|
||||
robot.frontRightDrive.setPower(engine.gamepad1.right_stick_y * maxSpeed);
|
||||
robot.backLeftDrive.setPower(engine.gamepad1.left_stick_y * maxSpeed);
|
||||
robot.frontLeftDrive.setPower(engine.gamepad1.left_stick_y * maxSpeed);
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
|
||||
@@ -1,35 +1,35 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class PingPongState extends CyberarmState {
|
||||
|
||||
private final MecanumRobot robot;
|
||||
public PingPongState(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
if (engine.gamepad1.left_bumper) {
|
||||
robot.frontLeftDrive.setPower(1);
|
||||
robot.backLeftDrive.setPower(-1);
|
||||
robot.backRightDrive.setPower(1);
|
||||
robot.frontRightDrive.setPower(-1);
|
||||
}
|
||||
else if (engine.gamepad1.right_bumper) {
|
||||
robot.frontLeftDrive.setPower(-1);
|
||||
robot.backLeftDrive.setPower(1);
|
||||
robot.frontRightDrive.setPower(1);
|
||||
robot.backRightDrive.setPower(-1);
|
||||
}
|
||||
|
||||
else {
|
||||
robot.backLeftDrive.setPower(engine.gamepad1.left_stick_y);
|
||||
robot.frontLeftDrive.setPower(engine.gamepad1.left_stick_y);
|
||||
robot.backRightDrive.setPower(engine.gamepad1.right_stick_y);
|
||||
robot.frontRightDrive.setPower(engine.gamepad1.right_stick_y);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
|
||||
public class PingPongState extends CyberarmState {
|
||||
|
||||
private final MecanumRobot robot;
|
||||
public PingPongState(MecanumRobot robot) {
|
||||
this.robot = robot;
|
||||
}
|
||||
@Override
|
||||
public void exec() {
|
||||
|
||||
if (engine.gamepad1.left_bumper) {
|
||||
robot.frontLeftDrive.setPower(1);
|
||||
robot.backLeftDrive.setPower(-1);
|
||||
robot.backRightDrive.setPower(1);
|
||||
robot.frontRightDrive.setPower(-1);
|
||||
}
|
||||
else if (engine.gamepad1.right_bumper) {
|
||||
robot.frontLeftDrive.setPower(-1);
|
||||
robot.backLeftDrive.setPower(1);
|
||||
robot.frontRightDrive.setPower(1);
|
||||
robot.backRightDrive.setPower(-1);
|
||||
}
|
||||
|
||||
else {
|
||||
robot.backLeftDrive.setPower(engine.gamepad1.left_stick_y);
|
||||
robot.frontLeftDrive.setPower(engine.gamepad1.left_stick_y);
|
||||
robot.backRightDrive.setPower(engine.gamepad1.right_stick_y);
|
||||
robot.frontRightDrive.setPower(engine.gamepad1.right_stick_y);
|
||||
}
|
||||
|
||||
}
|
||||
}
|
||||
@@ -1,7 +1,7 @@
|
||||
package org.timecrafters.minibots.cyberarm.states;
|
||||
package org.timecrafters.minibots.states;
|
||||
|
||||
import org.cyberarm.engine.V2.CyberarmState;
|
||||
import org.timecrafters.minibots.cyberarm.pickle_minibot_general;
|
||||
import org.timecrafters.minibots.pickle_minibot_general;
|
||||
|
||||
public class pickle_teleop_state extends CyberarmState {
|
||||
private final pickle_minibot_general robot;
|
||||
@@ -47,9 +47,6 @@ android {
|
||||
}
|
||||
}
|
||||
|
||||
aaptOptions {
|
||||
noCompress "tflite"
|
||||
}
|
||||
|
||||
defaultConfig {
|
||||
signingConfig signingConfigs.debug
|
||||
@@ -111,9 +108,6 @@ android {
|
||||
targetCompatibility JavaVersion.VERSION_1_8
|
||||
}
|
||||
|
||||
packagingOptions {
|
||||
pickFirst '**/*.so'
|
||||
}
|
||||
sourceSets.main {
|
||||
jni.srcDirs = []
|
||||
jniLibs.srcDir rootProject.file('libs')
|
||||
|
||||
@@ -4,6 +4,7 @@ repositories {
|
||||
flatDir {
|
||||
dirs rootProject.file('libs')
|
||||
}
|
||||
maven { url = 'https://maven.brott.dev/' }
|
||||
}
|
||||
|
||||
dependencies {
|
||||
|
||||
@@ -10,7 +10,7 @@ buildscript {
|
||||
google()
|
||||
}
|
||||
dependencies {
|
||||
classpath 'com.android.tools.build:gradle:7.3.0'
|
||||
classpath 'com.android.tools.build:gradle:7.3.1'
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
Reference in New Issue
Block a user