Skip to content

Commit

Permalink
Update 1.4
Browse files Browse the repository at this point in the history
Potentially breaking changes to better match original C++ Pixy API
Update to WPILib 2020.2.2
Renamed cache getter methods to differentiate them from the Pixy request
methods
Added default parameters for methods to better match original C++ Pixy
API
Made data holder classes static for more convenient use
Made getFeatures() from Pixy2Line private, forcing users to use
getMainFeatures() or getAllFeatures() like in the original C++ Pixy API
  • Loading branch information
PseudoResonance committed Feb 23, 2020
1 parent 3f71f28 commit c49e29d
Show file tree
Hide file tree
Showing 6 changed files with 150 additions and 28 deletions.
5 changes: 2 additions & 3 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -21,20 +21,19 @@ The maven repository is located at: https://nexus.otake.pw/repository/maven-publ

Add `maven { url 'https://nexus.otake.pw/repository/maven-public/' }` under `repositories`

Add `implementation 'pw.otake.pseudoresonance:pixy2-java-api:1.3.5'` under `dependencies` Replace `1.3.5` with the current version of the API.
Add `implementation 'pw.otake.pseudoresonance:pixy2-java-api:1.4'` under `dependencies` Replace `1.4` with the current version of the API.

Your `build.gradle` should resemble this:

```gradle
// Maven central needed for JUnit
repositories {
maven { url 'https://nexus.otake.pw/repository/maven-public/' }
}
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
// Also defines JUnit 4.
dependencies {
implementation 'pw.otake.pseudoresonance:pixy2-java-api:1.3.5'
implementation 'pw.otake.pseudoresonance:pixy2-java-api:1.4'
implementation wpi.deps.wpilib()
nativeZip wpi.deps.wpilibJni(wpi.platforms.roborio)
nativeDesktopZip wpi.deps.wpilibJni(wpi.platforms.desktop)
Expand Down
4 changes: 2 additions & 2 deletions build.gradle
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
plugins {
id "java"
id "edu.wpi.first.GradleRIO" version "2020.1.2"
id "edu.wpi.first.GradleRIO" version "2020.2.2"
id "maven-publish"
}

Expand Down Expand Up @@ -49,7 +49,7 @@ publishing {
artifact javadocJar
groupId = 'pw.otake.pseudoresonance'
artifactId = 'pixy2-java-api'
version = '1.3.5'
version = '1.4'
pom {
name = 'Pixy2JavaAPI'
description = 'Java port of Pixy2 API for FIRST Robotics'
Expand Down
4 changes: 2 additions & 2 deletions src/main/java/io/github/pseudoresonance/pixy2api/Pixy2.java
Original file line number Diff line number Diff line change
Expand Up @@ -221,7 +221,7 @@ public Pixy2Video getVideo() {
return this.video;
}

public class Version {
public static class Version {

protected int hardware = 0;
protected int firmwareMajor = 0;
Expand Down Expand Up @@ -692,7 +692,7 @@ public byte getFPS() {
}

// Checksum holder class
public class Checksum {
public static class Checksum {

int cs = 0;

Expand Down
52 changes: 48 additions & 4 deletions src/main/java/io/github/pseudoresonance/pixy2api/Pixy2CCC.java
Original file line number Diff line number Diff line change
Expand Up @@ -73,7 +73,51 @@ protected Pixy2CCC(Pixy2 pixy) {
/**
* <p>Gets signature {@link Block}s from Pixy2</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getBlocks()}</p>
* <p>Defaults to waiting for a response, getting blocks from all signatures and a maximum of all 256 blocks</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
*
* @return Pixy2 error code
*/
public int getBlocks() {
return getBlocks(true, CCC_SIG_ALL, 0xff);
}

/**
* <p>Gets signature {@link Block}s from Pixy2</p>
*
* <p>Defaults to getting blocks from all signatures and a maximum of all 256 blocks</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
*
* @param wait Whether to wait for Pixy2 if data is not available
*
* @return Pixy2 error code
*/
public int getBlocks(boolean wait) {
return getBlocks(wait, CCC_SIG_ALL, 0xff);
}

/**
* <p>Gets signature {@link Block}s from Pixy2</p>
*
* <p>Defaults to getting a maximum of all 256 blocks</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
*
* @param wait Whether to wait for Pixy2 if data is not available
* @param sigmap Sigmap to look for
*
* @return Pixy2 error code
*/
public int getBlocks(boolean wait, int sigmap) {
return getBlocks(wait, sigmap, 0xff);
}

/**
* <p>Gets signature {@link Block}s from Pixy2</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
*
* @param wait Whether to wait for Pixy2 if data is not available
* @param sigmap Sigmap to look for
Expand Down Expand Up @@ -141,13 +185,13 @@ public int getBlocks(boolean wait, int sigmap, int maxBlocks) {
*
* @return Pixy2 signature Blocks
*/
public ArrayList<Block> getBlocks() {
public ArrayList<Block> getBlockCache() {
return blocks;
}

public class Block {
public static class Block {

private int signature, x, y, width, height, angle, index, age = 0;
private int signature, x, y, width, height, angle, index, age;

/**
* Constructs signature block instance
Expand Down
96 changes: 80 additions & 16 deletions src/main/java/io/github/pseudoresonance/pixy2api/Pixy2Line.java
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,9 @@ protected Pixy2Line(Pixy2 pixy) {
/**
* <p>Gets all features from Pixy2</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectors()}, {@link #getIntersections()} or {@link #getBarcodes()}</p>
* <p>Defaults to getting all available features and waiting for a response</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @return Pixy2 error code
*/
Expand All @@ -93,26 +95,88 @@ public byte getAllFeatures() {
* <p>Gets the main features from the Pixy2. This is a more constrained line
* tracking algorithm.</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectors()}, {@link #getIntersections()} or {@link #getBarcodes()}</p>
* <p>Defaults to getting all available features and waiting for a response</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @return Pixy2 error code
*/
public byte getMainFeatures() {
return getFeatures(LINE_GET_MAIN_FEATURES, LINE_ALL_FEATURES, true);
}

/**
* <p>Gets all features from Pixy2</p>
*
* <p>Defaults to waiting for a response</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @param features Features to get
*
* @return Pixy2 error code
*/
public byte getAllFeatures(byte features) {
return getFeatures(LINE_GET_ALL_FEATURES, features, true);
}

/**
* <p>Gets the main features from the Pixy2. This is a more constrained line
* tracking algorithm.</p>
*
* <p>Defaults to waiting for a response</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @param features Features to get
*
* @return Pixy2 error code
*/
public byte getMainFeatures(byte features) {
return getFeatures(LINE_GET_MAIN_FEATURES, features, true);
}

/**
* <p>Gets all features from Pixy2</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @param features Features to get
* @param wait Wait for response
*
* @return Pixy2 error code
*/
public byte getAllFeatures(byte features, boolean wait) {
return getFeatures(LINE_GET_ALL_FEATURES, features, wait);
}

/**
* <p>Gets the main features from the Pixy2. This is a more constrained line
* tracking algorithm.</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @param features Features to get
* @param wait Wait for response
*
* @return Pixy2 error code
*/
public byte getMainFeatures(byte features, boolean wait) {
return getFeatures(LINE_GET_MAIN_FEATURES, features, wait);
}

/**
* <p>Gets specified features from Pixy2</p>
*
* <p>Returned data should be retrieved from the cache with {@link #getVectors()}, {@link #getIntersections()} or {@link #getBarcodes()}</p>
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
*
* @param type Type of features to get
* @param features Features to get
* @param wait Wait for response
*
* @return Pixy2 error code
*/
public byte getFeatures(byte type, byte features, boolean wait) {
private byte getFeatures(byte type, byte features, boolean wait) {
byte res;
int offset, fsize, ftype;
byte[] fdata;
Expand Down Expand Up @@ -210,7 +274,7 @@ else if (!wait) // We're busy
*
* @return Pixy2 Lines
*/
public Vector[] getVectors() {
public Vector[] getVectorCache() {
return vectors;
}

Expand All @@ -221,7 +285,7 @@ public Vector[] getVectors() {
*
* @return Pixy2 Intersectionss
*/
public Intersection[] getIntersections() {
public Intersection[] getIntersectionCache() {
return intersections;
}

Expand All @@ -232,7 +296,7 @@ public Intersection[] getIntersections() {
*
* @return Pixy2 Barcodes
*/
public Barcode[] getBarcodes() {
public Barcode[] getBarcodeCache() {
return barcodes;
}

Expand Down Expand Up @@ -348,9 +412,9 @@ public byte reverseVector() {
return Pixy2.PIXY_RESULT_ERROR; // Some kind of bitstream error
}

public class Vector {
public static class Vector {

private int x0, y0, x1, y1, index, flags = 0;
private int x0, y0, x1, y1, index, flags;

/**
* Constructs Vector instance
Expand Down Expand Up @@ -431,10 +495,10 @@ public int getFlags() {

}

public class IntersectionLine {
public static class IntersectionLine {

private int index, reserved = 0;
private short angle = 0;
private int index, reserved;
private short angle;

/**
* Constructs IntersectionLine object
Expand Down Expand Up @@ -488,9 +552,9 @@ public short getAngle() {

}

public class Intersection {
public static class Intersection {

private int x, y, number, reserved = 0;
private int x, y, number, reserved;
private IntersectionLine[] lines = new IntersectionLine[LINE_MAX_INTERSECTION_LINES];

/**
Expand Down Expand Up @@ -572,9 +636,9 @@ public IntersectionLine[] getLines() {

}

public class Barcode {
public static class Barcode {

private int x, y, flags, code = 0;
private int x, y, flags, code;

/**
* Constructs barcode object
Expand Down
17 changes: 16 additions & 1 deletion src/main/java/io/github/pseudoresonance/pixy2api/Pixy2Video.java
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,21 @@ protected Pixy2Video(Pixy2 pixy) {
this.pixy = pixy;
}

/**
* Gets average RGB value at 5x5 area around specified coordinates in the image
*
* <p>Defaults to saturating response color</p>
*
* @param x X value
* @param y Y value
* @param rgb RGB container to return values in
*
* @return Pixy2 error code
*/
public int getRGB(int x, int y, RGB rgb) {
return getRGB(x, y, rgb, true);
}

/**
* Gets average RGB value at 5x5 area around specified coordinates in the image
*
Expand Down Expand Up @@ -92,7 +107,7 @@ public int getRGB(int x, int y, RGB rgb, boolean saturate) {
}
}

public class RGB {
public static class RGB {

int r, g, b;

Expand Down

0 comments on commit c49e29d

Please sign in to comment.