Skip to content

Commit c49e29d

Browse files
Update 1.4
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
1 parent 3f71f28 commit c49e29d

6 files changed

Lines changed: 150 additions & 28 deletions

File tree

README.md

Lines changed: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -21,20 +21,19 @@ The maven repository is located at: https://nexus.otake.pw/repository/maven-publ
2121

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

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

2626
Your `build.gradle` should resemble this:
2727

2828
```gradle
29-
// Maven central needed for JUnit
3029
repositories {
3130
maven { url 'https://nexus.otake.pw/repository/maven-public/' }
3231
}
3332
3433
// Defining my dependencies. In this case, WPILib (+ friends), and vendor libraries.
3534
// Also defines JUnit 4.
3635
dependencies {
37-
implementation 'pw.otake.pseudoresonance:pixy2-java-api:1.3.5'
36+
implementation 'pw.otake.pseudoresonance:pixy2-java-api:1.4'
3837
implementation wpi.deps.wpilib()
3938
nativeZip wpi.deps.wpilibJni(wpi.platforms.roborio)
4039
nativeDesktopZip wpi.deps.wpilibJni(wpi.platforms.desktop)

build.gradle

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,6 @@
11
plugins {
22
id "java"
3-
id "edu.wpi.first.GradleRIO" version "2020.1.2"
3+
id "edu.wpi.first.GradleRIO" version "2020.2.2"
44
id "maven-publish"
55
}
66

@@ -49,7 +49,7 @@ publishing {
4949
artifact javadocJar
5050
groupId = 'pw.otake.pseudoresonance'
5151
artifactId = 'pixy2-java-api'
52-
version = '1.3.5'
52+
version = '1.4'
5353
pom {
5454
name = 'Pixy2JavaAPI'
5555
description = 'Java port of Pixy2 API for FIRST Robotics'

src/main/java/io/github/pseudoresonance/pixy2api/Pixy2.java

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -221,7 +221,7 @@ public Pixy2Video getVideo() {
221221
return this.video;
222222
}
223223

224-
public class Version {
224+
public static class Version {
225225

226226
protected int hardware = 0;
227227
protected int firmwareMajor = 0;
@@ -692,7 +692,7 @@ public byte getFPS() {
692692
}
693693

694694
// Checksum holder class
695-
public class Checksum {
695+
public static class Checksum {
696696

697697
int cs = 0;
698698

src/main/java/io/github/pseudoresonance/pixy2api/Pixy2CCC.java

Lines changed: 48 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -73,7 +73,51 @@ protected Pixy2CCC(Pixy2 pixy) {
7373
/**
7474
* <p>Gets signature {@link Block}s from Pixy2</p>
7575
*
76-
* <p>Returned data should be retrieved from the cache with {@link #getBlocks()}</p>
76+
* <p>Defaults to waiting for a response, getting blocks from all signatures and a maximum of all 256 blocks</p>
77+
*
78+
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
79+
*
80+
* @return Pixy2 error code
81+
*/
82+
public int getBlocks() {
83+
return getBlocks(true, CCC_SIG_ALL, 0xff);
84+
}
85+
86+
/**
87+
* <p>Gets signature {@link Block}s from Pixy2</p>
88+
*
89+
* <p>Defaults to getting blocks from all signatures and a maximum of all 256 blocks</p>
90+
*
91+
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
92+
*
93+
* @param wait Whether to wait for Pixy2 if data is not available
94+
*
95+
* @return Pixy2 error code
96+
*/
97+
public int getBlocks(boolean wait) {
98+
return getBlocks(wait, CCC_SIG_ALL, 0xff);
99+
}
100+
101+
/**
102+
* <p>Gets signature {@link Block}s from Pixy2</p>
103+
*
104+
* <p>Defaults to getting a maximum of all 256 blocks</p>
105+
*
106+
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
107+
*
108+
* @param wait Whether to wait for Pixy2 if data is not available
109+
* @param sigmap Sigmap to look for
110+
*
111+
* @return Pixy2 error code
112+
*/
113+
public int getBlocks(boolean wait, int sigmap) {
114+
return getBlocks(wait, sigmap, 0xff);
115+
}
116+
117+
/**
118+
* <p>Gets signature {@link Block}s from Pixy2</p>
119+
*
120+
* <p>Returned data should be retrieved from the cache with {@link #getBlockCache()}</p>
77121
*
78122
* @param wait Whether to wait for Pixy2 if data is not available
79123
* @param sigmap Sigmap to look for
@@ -141,13 +185,13 @@ public int getBlocks(boolean wait, int sigmap, int maxBlocks) {
141185
*
142186
* @return Pixy2 signature Blocks
143187
*/
144-
public ArrayList<Block> getBlocks() {
188+
public ArrayList<Block> getBlockCache() {
145189
return blocks;
146190
}
147191

148-
public class Block {
192+
public static class Block {
149193

150-
private int signature, x, y, width, height, angle, index, age = 0;
194+
private int signature, x, y, width, height, angle, index, age;
151195

152196
/**
153197
* Constructs signature block instance

src/main/java/io/github/pseudoresonance/pixy2api/Pixy2Line.java

Lines changed: 80 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,9 @@ protected Pixy2Line(Pixy2 pixy) {
8181
/**
8282
* <p>Gets all features from Pixy2</p>
8383
*
84-
* <p>Returned data should be retrieved from the cache with {@link #getVectors()}, {@link #getIntersections()} or {@link #getBarcodes()}</p>
84+
* <p>Defaults to getting all available features and waiting for a response</p>
85+
*
86+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
8587
*
8688
* @return Pixy2 error code
8789
*/
@@ -93,26 +95,88 @@ public byte getAllFeatures() {
9395
* <p>Gets the main features from the Pixy2. This is a more constrained line
9496
* tracking algorithm.</p>
9597
*
96-
* <p>Returned data should be retrieved from the cache with {@link #getVectors()}, {@link #getIntersections()} or {@link #getBarcodes()}</p>
98+
* <p>Defaults to getting all available features and waiting for a response</p>
99+
*
100+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
97101
*
98102
* @return Pixy2 error code
99103
*/
100104
public byte getMainFeatures() {
101105
return getFeatures(LINE_GET_MAIN_FEATURES, LINE_ALL_FEATURES, true);
102106
}
103107

108+
/**
109+
* <p>Gets all features from Pixy2</p>
110+
*
111+
* <p>Defaults to waiting for a response</p>
112+
*
113+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
114+
*
115+
* @param features Features to get
116+
*
117+
* @return Pixy2 error code
118+
*/
119+
public byte getAllFeatures(byte features) {
120+
return getFeatures(LINE_GET_ALL_FEATURES, features, true);
121+
}
122+
123+
/**
124+
* <p>Gets the main features from the Pixy2. This is a more constrained line
125+
* tracking algorithm.</p>
126+
*
127+
* <p>Defaults to waiting for a response</p>
128+
*
129+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
130+
*
131+
* @param features Features to get
132+
*
133+
* @return Pixy2 error code
134+
*/
135+
public byte getMainFeatures(byte features) {
136+
return getFeatures(LINE_GET_MAIN_FEATURES, features, true);
137+
}
138+
139+
/**
140+
* <p>Gets all features from Pixy2</p>
141+
*
142+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
143+
*
144+
* @param features Features to get
145+
* @param wait Wait for response
146+
*
147+
* @return Pixy2 error code
148+
*/
149+
public byte getAllFeatures(byte features, boolean wait) {
150+
return getFeatures(LINE_GET_ALL_FEATURES, features, wait);
151+
}
152+
153+
/**
154+
* <p>Gets the main features from the Pixy2. This is a more constrained line
155+
* tracking algorithm.</p>
156+
*
157+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
158+
*
159+
* @param features Features to get
160+
* @param wait Wait for response
161+
*
162+
* @return Pixy2 error code
163+
*/
164+
public byte getMainFeatures(byte features, boolean wait) {
165+
return getFeatures(LINE_GET_MAIN_FEATURES, features, wait);
166+
}
167+
104168
/**
105169
* <p>Gets specified features from Pixy2</p>
106170
*
107-
* <p>Returned data should be retrieved from the cache with {@link #getVectors()}, {@link #getIntersections()} or {@link #getBarcodes()}</p>
171+
* <p>Returned data should be retrieved from the cache with {@link #getVectorCache()}, {@link #getIntersectionCache()} or {@link #getBarcodeCache()}</p>
108172
*
109173
* @param type Type of features to get
110174
* @param features Features to get
111175
* @param wait Wait for response
112176
*
113177
* @return Pixy2 error code
114178
*/
115-
public byte getFeatures(byte type, byte features, boolean wait) {
179+
private byte getFeatures(byte type, byte features, boolean wait) {
116180
byte res;
117181
int offset, fsize, ftype;
118182
byte[] fdata;
@@ -210,7 +274,7 @@ else if (!wait) // We're busy
210274
*
211275
* @return Pixy2 Lines
212276
*/
213-
public Vector[] getVectors() {
277+
public Vector[] getVectorCache() {
214278
return vectors;
215279
}
216280

@@ -221,7 +285,7 @@ public Vector[] getVectors() {
221285
*
222286
* @return Pixy2 Intersectionss
223287
*/
224-
public Intersection[] getIntersections() {
288+
public Intersection[] getIntersectionCache() {
225289
return intersections;
226290
}
227291

@@ -232,7 +296,7 @@ public Intersection[] getIntersections() {
232296
*
233297
* @return Pixy2 Barcodes
234298
*/
235-
public Barcode[] getBarcodes() {
299+
public Barcode[] getBarcodeCache() {
236300
return barcodes;
237301
}
238302

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

351-
public class Vector {
415+
public static class Vector {
352416

353-
private int x0, y0, x1, y1, index, flags = 0;
417+
private int x0, y0, x1, y1, index, flags;
354418

355419
/**
356420
* Constructs Vector instance
@@ -431,10 +495,10 @@ public int getFlags() {
431495

432496
}
433497

434-
public class IntersectionLine {
498+
public static class IntersectionLine {
435499

436-
private int index, reserved = 0;
437-
private short angle = 0;
500+
private int index, reserved;
501+
private short angle;
438502

439503
/**
440504
* Constructs IntersectionLine object
@@ -488,9 +552,9 @@ public short getAngle() {
488552

489553
}
490554

491-
public class Intersection {
555+
public static class Intersection {
492556

493-
private int x, y, number, reserved = 0;
557+
private int x, y, number, reserved;
494558
private IntersectionLine[] lines = new IntersectionLine[LINE_MAX_INTERSECTION_LINES];
495559

496560
/**
@@ -572,9 +636,9 @@ public IntersectionLine[] getLines() {
572636

573637
}
574638

575-
public class Barcode {
639+
public static class Barcode {
576640

577-
private int x, y, flags, code = 0;
641+
private int x, y, flags, code;
578642

579643
/**
580644
* Constructs barcode object

src/main/java/io/github/pseudoresonance/pixy2api/Pixy2Video.java

Lines changed: 16 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,21 @@ protected Pixy2Video(Pixy2 pixy) {
4848
this.pixy = pixy;
4949
}
5050

51+
/**
52+
* Gets average RGB value at 5x5 area around specified coordinates in the image
53+
*
54+
* <p>Defaults to saturating response color</p>
55+
*
56+
* @param x X value
57+
* @param y Y value
58+
* @param rgb RGB container to return values in
59+
*
60+
* @return Pixy2 error code
61+
*/
62+
public int getRGB(int x, int y, RGB rgb) {
63+
return getRGB(x, y, rgb, true);
64+
}
65+
5166
/**
5267
* Gets average RGB value at 5x5 area around specified coordinates in the image
5368
*
@@ -92,7 +107,7 @@ public int getRGB(int x, int y, RGB rgb, boolean saturate) {
92107
}
93108
}
94109

95-
public class RGB {
110+
public static class RGB {
96111

97112
int r, g, b;
98113

0 commit comments

Comments
 (0)