Skip to content

Commit

Permalink
Merge pull request #10 from ThePinkAlliance/develop
Browse files Browse the repository at this point in the history
  • Loading branch information
devsamuelv authored Jul 11, 2022
2 parents a8803f5 + 980fe95 commit d2ab1fd
Show file tree
Hide file tree
Showing 5 changed files with 147 additions and 18 deletions.
4 changes: 2 additions & 2 deletions ThePinkAlliance.json
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
{
"fileName": "ThePinkAlliance.json",
"name": "ThePinkAlliance",
"version": "2.0.14",
"version": "2.0.15",
"uuid": "9619F7EA-7F96-4236-9D94-02338DFED572",
"mavenUrls": [
"https://jitpack.io",
Expand All @@ -13,7 +13,7 @@
{
"groupId": "com.github.ThePinkAlliance",
"artifactId": "core",
"version": "2.0.14"
"version": "2.0.15"
}
],
"jniDependencies": [],
Expand Down
2 changes: 1 addition & 1 deletion build.gradle
Original file line number Diff line number Diff line change
Expand Up @@ -2,7 +2,7 @@ apply plugin: 'java-library'
apply plugin: 'maven-publish'

group = 'com.ThePinkAlliance.core'
version = '2.0.14'
version = '2.0.15'

sourceCompatibility = JavaVersion.VERSION_11 // java 11
targetCompatibility = JavaVersion.VERSION_11
Expand Down
6 changes: 3 additions & 3 deletions src/main/java/com/ThePinkAlliance/core/joystick/Joystick.java
Original file line number Diff line number Diff line change
Expand Up @@ -27,15 +27,15 @@ public enum Buttons {
}
}

public enum POV_TYPE {
public enum PovType {
NORTH(0),
EAST(90),
WEST(270),
SOUTH(180);

int id = 0;

POV_TYPE(int id) {
PovType(int id) {
this.id = id;
}
}
Expand Down Expand Up @@ -69,7 +69,7 @@ public JoystickAxis getAxis(Axis axis) {
return new JoystickAxis(this, axis);
}

public boolean povActivated(POV_TYPE type) {
public boolean povActivated(PovType type) {
int pov = this.joy.getPOV();

if (pov == type.id) {
Expand Down
56 changes: 45 additions & 11 deletions src/main/java/com/ThePinkAlliance/core/limelight/Limelight.java
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,8 @@ public double get() {

/**
* @param height_from_floor The limelight lens height from the floor in inches.
* @param mounted_angle The current pitch angle of the limelight on its mount.
* @param mounted_angle The current pitch angle of the limelight on its
* mount.
*/
public Limelight(double height_from_floor, double mounted_angle) {
this.HEIGHT_FROM_FLOOR = height_from_floor;
Expand All @@ -65,14 +66,15 @@ public Limelight(double height_from_floor, double mounted_angle) {

/**
* @param height_from_floor The limelight lens height from the floor in inches.
* @param mounted_angle The current pitch angle of the limelight on its mount.
* @param horizontal_offset The angluar offset of the limelight from the center of the robot.
* @param mounted_angle The current pitch angle of the limelight on its
* mount.
* @param horizontal_offset The angluar offset of the limelight from the center
* of the robot.
*/
public Limelight(
double height_from_floor,
double mounted_angle,
double horizontal_offset
) {
double height_from_floor,
double mounted_angle,
double horizontal_offset) {
this.HEIGHT_FROM_FLOOR = height_from_floor;
this.MOUNTED_ANGLE = mounted_angle;
this.REFLECTED_TAPE_HEIGHT = GAME_TARGET_HEIGHTS.RAPID_REACT_TOP_HUB.get();
Expand All @@ -81,6 +83,18 @@ public Limelight(
configureLimelight();
}

/**
* @param constants Constants for the limelight.
*/
public Limelight(LimelightConstants constants) {
this.HEIGHT_FROM_FLOOR = constants.getHeightFromFloor();
this.MOUNTED_ANGLE = constants.getMountedAngle();
this.REFLECTED_TAPE_HEIGHT = constants.getTargetHeight();
this.HORIZONTAL_OFFSET = constants.getHorizontalOffset();

configureLimelight();
}

private void configureLimelight() {
this.CURRENT_LED_MODE = LED_MODE.OFF;

Expand All @@ -105,6 +119,20 @@ public void configureTargetHeight(double targetHeight) {
this.REFLECTED_TAPE_HEIGHT = targetHeight;
}

/**
* This will reconfigure the limelight with the passed parameters.
*
* @param constants LimelightConstants
*/
public void reconfigureLimelight(LimelightConstants constants) {
this.HEIGHT_FROM_FLOOR = constants.getHeightFromFloor();
this.MOUNTED_ANGLE = constants.getMountedAngle();
this.REFLECTED_TAPE_HEIGHT = constants.getTargetHeight();
this.HORIZONTAL_OFFSET = constants.getHorizontalOffset();

configureLimelight();
}

/**
*
* @param targetHeight The height of the reflective tape in inches.
Expand Down Expand Up @@ -135,18 +163,24 @@ public double foundTargets() {

/**
* Returns the horizontal difference from the center of the detected target.
*
* @return The offset in degress, range of (27 <-> -27)
*/
public double getHorizontalDiff() {
return this.tx.getDouble(0);
}

/**
* In order to get accurate target info you need to run the limelight's onboard
* cross-hair calibration.
*
* @return The estimated distance in inches.
*/
public double calculateDistance() {
double verticalOffset = ty.getDouble(0);
double targetAngleDeg = MOUNTED_ANGLE + verticalOffset;

return (
(REFLECTED_TAPE_HEIGHT - HEIGHT_FROM_FLOOR) /
Math.tan(Math.toRadians(targetAngleDeg))
);
return ((REFLECTED_TAPE_HEIGHT - HEIGHT_FROM_FLOOR) /
Math.tan(Math.toRadians(targetAngleDeg)));
}
}
Original file line number Diff line number Diff line change
@@ -1,3 +1,98 @@
package com.ThePinkAlliance.core.limelight;

public class LimelightConstants {}
import com.ThePinkAlliance.core.limelight.Limelight.GAME_TARGET_HEIGHTS;

/**
* This store's information about the limelight and it's target.
*/
public class LimelightConstants {
private double HEIGHT_FROM_FLOOR;
private double MOUNTED_ANGLE;
private double REFLECTED_TAPE_HEIGHT;
private double HORIZONTAL_OFFSET;

/**
* @param HEIGHT_FROM_FLOOR The limelight lens height from the floor in
* inches.
* @param MOUNTED_ANGLE The current pitch angle of the limelight on its
* mount.
* @param REFLECTED_TAPE_HEIGHT The height of the reflective tape we are
* tracking.
*/
public LimelightConstants(double HEIGHT_FROM_FLOOR, double MOUNTED_ANGLE, double REFLECTED_TAPE_HEIGHT) {
this.HEIGHT_FROM_FLOOR = HEIGHT_FROM_FLOOR;
this.MOUNTED_ANGLE = MOUNTED_ANGLE;
this.REFLECTED_TAPE_HEIGHT = REFLECTED_TAPE_HEIGHT;
this.HORIZONTAL_OFFSET = 0;
}

/**
* @param HEIGHT_FROM_FLOOR The limelight lens height from the floor in
* inches.
* @param MOUNTED_ANGLE The current pitch angle of the limelight on its
* mount.
* @param REFLECTED_TAPE_HEIGHT The height of the reflective tape we are
* tracking.
* @param HORIZONTAL_OFFSET The angluar offset of the limelight from the
* center
* of the robot.
*/
public LimelightConstants(double HEIGHT_FROM_FLOOR, double MOUNTED_ANGLE, double REFLECTED_TAPE_HEIGHT,
double HORIZONTAL_OFFSET) {
this.HEIGHT_FROM_FLOOR = HEIGHT_FROM_FLOOR;
this.MOUNTED_ANGLE = MOUNTED_ANGLE;
this.HORIZONTAL_OFFSET = HORIZONTAL_OFFSET;
this.REFLECTED_TAPE_HEIGHT = REFLECTED_TAPE_HEIGHT;
}

/**
* @param HEIGHT_FROM_FLOOR The limelight lens height from the floor in
* inches.
* @param MOUNTED_ANGLE The current pitch angle of the limelight on its
* mount.
* @param TARGET The reflective tape target we are
* tracking.
*/
public LimelightConstants(double HEIGHT_FROM_FLOOR, double MOUNTED_ANGLE, GAME_TARGET_HEIGHTS TARGET) {
this.HEIGHT_FROM_FLOOR = HEIGHT_FROM_FLOOR;
this.MOUNTED_ANGLE = MOUNTED_ANGLE;
this.HORIZONTAL_OFFSET = 0;
this.REFLECTED_TAPE_HEIGHT = TARGET.get();
}

/**
* @param HEIGHT_FROM_FLOOR The limelight lens height from the floor in
* inches.
* @param MOUNTED_ANGLE The current pitch angle of the limelight on its
* mount.
* @param TARGET The reflective tape target we are
* tracking.
* @param HORIZONTAL_OFFSET The angluar offset of the
* limelight from the
* center
* of the robot.
*/
public LimelightConstants(double HEIGHT_FROM_FLOOR, double MOUNTED_ANGLE, GAME_TARGET_HEIGHTS TARGET,
double HORIZONTAL_OFFSET) {
this.HEIGHT_FROM_FLOOR = HEIGHT_FROM_FLOOR;
this.MOUNTED_ANGLE = MOUNTED_ANGLE;
this.HORIZONTAL_OFFSET = HORIZONTAL_OFFSET;
this.REFLECTED_TAPE_HEIGHT = TARGET.get();
}

public double getHeightFromFloor() {
return this.HEIGHT_FROM_FLOOR;
}

public double getMountedAngle() {
return this.MOUNTED_ANGLE;
}

public double getTargetHeight() {
return this.REFLECTED_TAPE_HEIGHT;
}

public double getHorizontalOffset() {
return this.HORIZONTAL_OFFSET;
}
}

0 comments on commit d2ab1fd

Please sign in to comment.