Created getAngleToTarget function

This commit is contained in:
Nathaniel Palme
2020-11-03 20:22:18 -06:00
parent 8ca11b3b25
commit 921660660d
3 changed files with 54 additions and 10 deletions

View File

@@ -9,15 +9,18 @@ import org.timecrafters.UltimateGoal.Robot;
public class LauncherTest extends CyberarmState { public class LauncherTest extends CyberarmState {
DcMotor LaunchMotor; DcMotor LaunchMotor;
DcMotor SuckMotor;
@Override @Override
public void init() { public void init() {
LaunchMotor = engine.hardwareMap.dcMotor.get("launcher"); LaunchMotor = engine.hardwareMap.dcMotor.get("launcher");
SuckMotor = engine.hardwareMap.dcMotor.get("collector");
} }
@Override @Override
public void exec() { public void exec() {
LaunchMotor.setPower(1); LaunchMotor.setPower(1);
SuckMotor.setPower(1);
} }
@Override @Override

View File

@@ -10,30 +10,38 @@ public class VuforiaNavTesting extends CyberarmState {
private float angle; private float angle;
private double X; private double X;
private double Y; private double Y;
private double targetX;
private double targetY;
public VuforiaNavTesting(Robot robot) { public VuforiaNavTesting(Robot robot) {
this.robot = robot; this.robot = robot;
} }
@Override
public void init() {
targetX = robot.inchesToTicks(24);
targetY = robot.inchesToTicks(24);
}
@Override @Override
public void exec() { public void exec() {
robot.setDrivePower(-0.2 * engine.gamepad1.left_stick_y, -0.2 * engine.gamepad1.right_stick_y); robot.setDrivePower(-0.5 * engine.gamepad1.left_stick_y, -0.5 * engine.gamepad1.right_stick_y);
robot.updateLocation(); robot.updateLocation();
X = robot.getLocationX(); X = robot.getLocationX();
Y = robot.getLocationY(); Y = robot.getLocationY();
angle = robot.getRotation(); angle = robot.getRotation();
} }
@Override @Override
public void telemetry() { public void telemetry() {
engine.telemetry.addData("Target Visible", robot.trackableVisible); engine.telemetry.addData("Target Visible", robot.trackableVisible);
engine.telemetry.addData("Odo X", robot.ticksToInches(X)); engine.telemetry.addData("Odo X", robot.ticksToInches(X));
engine.telemetry.addData("Odo Y", robot.ticksToInches(Y)); engine.telemetry.addData("Odo Y", robot.ticksToInches(Y));
engine.telemetry.addData("Vis X", robot.visionX); engine.telemetry.addData("Robot Angle", angle);
engine.telemetry.addData("Vis Y", robot.visionY); engine.telemetry.addData("Raw Angle", robot.rawAngle);
engine.telemetry.addData("Angle to Target", robot.getAngleToPosition(targetX,targetY));
engine.telemetry.addData("Angle", angle);
} }
} }

View File

@@ -28,7 +28,7 @@ import static org.firstinspires.ftc.robotcore.external.navigation.AxesOrder.XYZ;
import static org.firstinspires.ftc.robotcore.external.navigation.AxesOrder.YZX; import static org.firstinspires.ftc.robotcore.external.navigation.AxesOrder.YZX;
import static org.firstinspires.ftc.robotcore.external.navigation.AxesReference.EXTRINSIC; import static org.firstinspires.ftc.robotcore.external.navigation.AxesReference.EXTRINSIC;
public class Robot { public class Robot {
private HardwareMap hardwareMap; private HardwareMap hardwareMap;
@@ -63,13 +63,14 @@ public class Robot {
// Inches Left of axis of rotation // Inches Left of axis of rotation
static final float CAMERA_LEFT_DISPLACEMENT = 2f; static final float CAMERA_LEFT_DISPLACEMENT = 2f;
//Robot Localizatoin //Robot Localization
private double locationX; private double locationX;
private double locationY; private double locationY;
private float rotation; private float rotation;
public double visionX; public double visionX;
public double visionY; public double visionY;
public float rawAngle;
public double traveledLeft; public double traveledLeft;
@@ -171,6 +172,8 @@ public class Robot {
targetsUltimateGoal.activate(); targetsUltimateGoal.activate();
} }
//TODO : Test range of Tensor Object identification.
private void initTensorFlow() { private void initTensorFlow() {
int tfodMonitorViewId = hardwareMap.appContext.getResources().getIdentifier( int tfodMonitorViewId = hardwareMap.appContext.getResources().getIdentifier(
"tfodMonitorViewId", "id", hardwareMap.appContext.getPackageName()); "tfodMonitorViewId", "id", hardwareMap.appContext.getPackageName());
@@ -189,8 +192,15 @@ public class Robot {
public void updateLocation(){ public void updateLocation(){
// orientation is inverted to have clockwise be positive. // orientation is inverted to have clockwise be positive.
float imuAngle = -imu.getAngularOrientation().firstAngle; float imuAngle = -imu.getAngularOrientation().firstAngle;
float rotationChange = imuAngle - rotationPrevious; float rotationChange = imuAngle - rotationPrevious;
if (rotationChange > 180) {
rotationChange -= 360;
}
if (rotationChange < -180) {
rotationChange += 360;
}
int encoderLeftCurrent = encoderLeft.getCurrentPosition(); int encoderLeftCurrent = encoderLeft.getCurrentPosition();
int encoderRightCurrent = encoderRight.getCurrentPosition(); int encoderRightCurrent = encoderRight.getCurrentPosition();
double encoderLeftChange = encoderLeftCurrent - encoderLeftPrevious; double encoderLeftChange = encoderLeftCurrent - encoderLeftPrevious;
@@ -212,6 +222,10 @@ public class Robot {
locationX += xChange; locationX += xChange;
locationY += yChange; locationY += yChange;
//TODO : add separate odometer and vision coordinates.
//TODO : make Odometer Coordinates set to vision coordinates on button push.
trackableVisible = false; trackableVisible = false;
for (VuforiaTrackable trackable : trackables) { for (VuforiaTrackable trackable : trackables) {
if (((VuforiaTrackableDefaultListener)trackable.getListener()).isVisible()) { if (((VuforiaTrackableDefaultListener)trackable.getListener()).isVisible()) {
@@ -234,7 +248,8 @@ public class Robot {
// visionY = translation.get(0) / mmPerInch; // visionY = translation.get(0) / mmPerInch;
//For our tornament, it makes sence to make zero degrees towards the goal, orientation is inverted to have clockwise be positive. //For our tournament, it makes sense to make zero degrees towards the goal.
//Orientation is inverted to have clockwise be positive.
Orientation rotation = Orientation.getOrientation(lastConfirmendLocation, EXTRINSIC, XYZ, DEGREES); Orientation rotation = Orientation.getOrientation(lastConfirmendLocation, EXTRINSIC, XYZ, DEGREES);
this.rotation = 90-rotation.thirdAngle; this.rotation = 90-rotation.thirdAngle;
@@ -245,6 +260,14 @@ public class Robot {
break; break;
} }
} }
if (rotation > 180) {
rotation -= 360;
}
if (rotation < -180) {
rotation += 360;
}
} }
public float getRotation() { public float getRotation() {
@@ -259,12 +282,22 @@ public class Robot {
return locationY; return locationY;
} }
public float getAngleToPosition (double x, double y) {
double differenceX = x- getLocationX();
double differenceY = y- getLocationY();
double angle = Math.toDegrees(Math.atan2(differenceX, differenceY ));
return (float) angle;
}
public double ticksToInches(double ticks) { public double ticksToInches(double ticks) {
return ticks * (ENCODER_CIRCUMFERENCE / COUNTS_PER_REVOLUTION); return ticks * (ENCODER_CIRCUMFERENCE / COUNTS_PER_REVOLUTION);
} }
public double inchesToTicks(double inches) { public double inchesToTicks(double inches) {
return inches * (COUNTS_PER_REVOLUTION / ENCODER_CIRCUMFERENCE); return inches * (COUNTS_PER_REVOLUTION / ENCODER_CIRCUMFERENCE);
} }
public float getRelativeAngle(float reference, float current) { public float getRelativeAngle(float reference, float current) {