Skip to content

Commit

Permalink
Typos
Browse files Browse the repository at this point in the history
  • Loading branch information
srimanachanta committed Oct 10, 2023
1 parent fd3d649 commit 14cd3fc
Show file tree
Hide file tree
Showing 18 changed files with 32 additions and 32 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -226,7 +226,7 @@ public String taToLogFname(TemporalAccessor date) {
}

public Date logFnameToDate(String fname) throws ParseException {
// Strip away known unneded portions of the log file name
// Strip away known unneeded portions of the log file name
fname = fname.replace(LOG_PREFIX, "").replace(LOG_EXT, "");
DateFormat format = new SimpleDateFormat(LOG_DATE_TIME_FORMAT);
return format.parse(fname);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -370,7 +370,7 @@ public String taToLogFname(TemporalAccessor date) {
}

public Date logFnameToDate(String fname) throws ParseException {
// Strip away known unneded portions of the log file name
// Strip away known unneeded portions of the log file name
fname = fname.replace(LOG_PREFIX, "").replace(LOG_EXT, "");
DateFormat format = new SimpleDateFormat(LOG_DATE_TIME_FORMAT);
return format.parse(fname);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -419,7 +419,7 @@ public boolean saveUploadedNetworkConfig(Path uploadPath) {
private HashMap<String, CameraConfiguration> loadCameraConfigs(Connection conn) {
HashMap<String, CameraConfiguration> loadedConfigurations = new HashMap<>();

// Querry every single row of the cameras db
// Query every single row of the cameras db
PreparedStatement query = null;
try {
query =
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -128,7 +128,7 @@ public static void cleanLogs(Path folderToClean) {
HashMap<File, Date> logFileStartDateMap = new HashMap<>();

// Remove any files from the list for which we can't parse a start date from their name.
// Simultaneously populate our HashMap with Date objects repeseting the file-name
// Simultaneously populate our HashMap with Date objects representing the file-name
// indicated log start time.
logFileList.removeIf(
(File arg0) -> {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -42,7 +42,7 @@ public static RoborioFinder getInstance() {
public void findRios() {
HashMap<String, Object> map = new HashMap<>();
var subMap = new HashMap<String, Object>();
// Seperate from the above so we don't hold stuff up
// Separate from the above so we don't hold stuff up
System.setProperty("java.net.preferIPv4Stack", "true");
subMap.put(
"deviceips",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -120,7 +120,7 @@ public static boolean isSupported() {

/**
* Starts the camera thresholder and display threads running. Make sure that this function is
* called syncronously with stopCamera and returnFrame!
* called synchronously with stopCamera and returnFrame!
*/
public static native boolean startCamera();

Expand All @@ -141,7 +141,7 @@ public static native boolean setThresholds(
// Exposure time, in microseconds
public static native boolean setExposure(int exposureUs);

// Set brighness on [-1, 1]
// Set brightness on [-1, 1]
public static native boolean setBrightness(double brightness);

// Unknown ranges for red and blue AWB gain
Expand All @@ -164,18 +164,18 @@ public static native boolean setThresholds(
// Analog gain multiplier to apply to all color channels, on [1, Big Number]
public static native boolean setAnalogGain(double analog);

/** Block until a new frame is avaliable from native code. */
/** Block until a new frame is available from native code. */
public static native boolean awaitNewFrame();

/**
* Get a pointer to the most recent color mat generated. Call this immediatly after awaitNewFrame,
* and call onlly once per new frame!
* Get a pointer to the most recent color mat generated. Call this immediately after awaitNewFrame,
* and call only once per new frame!
*/
public static native long takeColorFrame();

/**
* Get a pointer to the most recent processed mat generated. Call this immediatly after
* awaitNewFrame, and call onlly once per new frame!
* Get a pointer to the most recent processed mat generated. Call this immediately after
* awaitNewFrame, and call only once per new frame!
*/
public static native long takeProcessedFrame();

Expand All @@ -186,6 +186,6 @@ public static native boolean setThresholds(

public static native int getGpuProcessType();

// /** Release a frame pointer back to the libcamera driver code to be filled again */
// Release a frame pointer back to the libcamera driver code to be filled again */
// public static native long returnFrame(long frame);
}
Original file line number Diff line number Diff line change
Expand Up @@ -47,7 +47,7 @@ public void setDecimation(float decimate) {

logger.info("Setting decimation from " + m_decimate + " to " + decimate);

// We only need to mutate the parameters -- the detector keeps a poitner to the parameters
// We only need to mutate the parameters -- the detector keeps a pointer to the parameters
// object internally, so it should automatically update
parameters.set_aprilTagQuadDecimate(decimate);
m_decimate = decimate;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -123,16 +123,16 @@ public void setAutoExposure(boolean cameraAutoExposure) {
if (!cameraAutoExposure) {
// Pick a bunch of reasonable setting defaults for vision processing retroreflective
camera.getProperty("auto_exposure_bias").set(0);
camera.getProperty("iso_sensitivity_auto").set(0); // Disable auto ISO adjustement
camera.getProperty("iso_sensitivity").set(0); // Manual ISO adjustement
camera.getProperty("iso_sensitivity_auto").set(0); // Disable auto ISO adjustment
camera.getProperty("iso_sensitivity").set(0); // Manual ISO adjustment
camera.getProperty("white_balance_auto_preset").set(2); // Auto white-balance disabled
camera.getProperty("auto_exposure").set(1); // auto exposure disabled
} else {
// Pick a bunch of reasonable setting defaults for driver, fiducials, or otherwise
// nice-for-humans
camera.getProperty("auto_exposure_bias").set(12);
camera.getProperty("iso_sensitivity_auto").set(1);
camera.getProperty("iso_sensitivity").set(1); // Manual ISO adjustement by default
camera.getProperty("iso_sensitivity").set(1); // Manual ISO adjustment by default
camera.getProperty("white_balance_auto_preset").set(1); // Auto white-balance enabled
camera.getProperty("auto_exposure").set(0); // auto exposure enabled
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -44,7 +44,7 @@ public class Calibrate3dPipe
// Stores the radical and tangential distortion in a 5x1 matrix
private final MatOfDouble distortionCoefficients = new MatOfDouble();

// For loggging
// For logging
private static final Logger logger = new Logger(Calibrate3dPipe.class, LogGroup.General);

// Translational and rotational matrices
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -151,7 +151,7 @@ private List<Point> detectExtremeCornersByApproxPolyDp(TrackedTarget target, boo
var distanceToTrComparator =
Comparator.comparingDouble((Point p) -> distanceBetween(p, boundingBoxCorners.get(3)));

// top left and top right are the poly corners closest to the bouding box tl and tr
// top left and top right are the poly corners closest to the bounding box tl and tr
pointList.sort(distanceToTlComparator);
var tl = pointList.get(0);
pointList.remove(tl);
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -115,7 +115,7 @@ protected Void process(Pair<Mat, List<TrackedTarget>> in) {
dividePointList(bottomPoints);
dividePointList(topPoints);

// floor, then pillers, then top
// floor, then pillars, then top
for (int i = 0; i < bottomPoints.size(); i++) {
Imgproc.line(
in.getLeft(),
Expand Down Expand Up @@ -237,11 +237,11 @@ private void distortPoints(MatOfPoint2f src, MatOfPoint2f dst) {

double r2 = x * x + y * y; // square of the radius from center

// Radial distorsion
// Radial distortion
double xDistort = x * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2);
double yDistort = y * (1 + k1 * r2 + k2 * r2 * r2 + k3 * r2 * r2 * r2);

// Tangential distorsion
// Tangential distortion
xDistort = xDistort + (2 * p1 * x * y + p2 * (r2 + 2 * x * x));
yDistort = yDistort + (p1 * (r2 + 2 * y * y) + 2 * p2 * x * y);

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,7 @@ public class FindBoardCornersPipe

private final MatOfPoint2f boardCorners = new MatOfPoint2f();

// Intermedeate result mat's
// Intermediate result mat's
Mat smallerInFrame = new Mat();
MatOfPoint2f smallerBoardCorners = new MatOfPoint2f();

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -121,7 +121,7 @@ public static class FindCirclePipeParams {
* If the parameter is too small, multiple neighbor circles may be falsely detected in addition to a true one. If it is too large, some circles may be missed.
*
* @param maxCannyThresh -First method-specific parameter. In case of #HOUGH_GRADIENT and #HOUGH_GRADIENT_ALT, it is the higher threshold of the two passed to the Canny edge detector (the lower one is twice smaller).
* Note that #HOUGH_GRADIENT_ALT uses #Scharr algorithm to compute image derivatives, so the threshold value shough normally be higher, such as 300 or normally exposed and contrasty images.
* Note that #HOUGH_GRADIENT_ALT uses #Scharr algorithm to compute image derivatives, so the threshold value should normally be higher, such as 300 or normally exposed and contrasty images.
*
*
* @param allowableThreshold - When finding the corresponding contour, this is used to see how close a center should be to a contour for it to be considered THAT contour.
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -46,7 +46,7 @@

public class Calibrate3dPipeline
extends CVPipeline<CVPipelineResult, Calibration3dPipelineSettings> {
// For loggging
// For logging
private static final Logger logger = new Logger(Calibrate3dPipeline.class, LogGroup.General);

// Only 2 pipes needed, one for finding the board corners and one for actually calibrating
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -204,7 +204,7 @@ public double getPoseAmbiguity() {
}

/**
* Set the approximate bouding polygon.
* Set the approximate bounding polygon.
*
* @param boundingPolygon List of points to copy. Not modified.
*/
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -35,7 +35,7 @@ public class SocketVideoStream implements Consumer<CVMat> {

// Gets set to true when another class reads out valid jpeg bytes at least once
// Set back to false when another frame is freshly converted
// Should eliminate synchronization issues of differeing rates of putting frames in
// Should eliminate synchronization issues of differing rates of putting frames in
// and taking them back out
boolean frameWasConsumed = false;

Expand Down Expand Up @@ -64,7 +64,7 @@ public void accept(CVMat image) {
.tryLock()) { // we assume frames are coming in frequently. Just skip this frame if we're
// locked doing something else.
try {
// Does a single-shot frame recieve and convert to JPEG for efficency
// Does a single-shot frame receive and convert to JPEG for efficiency
// Will not capture/convert again until convertNextFrame() is called
if (image != null && !image.getMat().empty() && jpegBytes == null) {
frameWasConsumed = false;
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,7 @@ public ByteBuffer getSendFrame(WsContext user) {
}
}

// Causes all streams to "re-trigger" and recieve and convert their next mjpeg frame
// Causes all streams to "re-trigger" and receive and convert their next mjpeg frame
// Only invoke this after all returned jpeg Strings have been used.
public void allStreamConvertNextFrame() {
for (SocketVideoStream stream : streams.values()) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -107,13 +107,13 @@ public void deserializeConfig() {

Assertions.assertTrue(
reflectivePipelineSettings instanceof ReflectivePipelineSettings,
"Conig loaded pipeline settings for index 0 not of expected type ReflectivePipelineSettings!");
"Config loaded pipeline settings for index 0 not of expected type ReflectivePipelineSettings!");
Assertions.assertTrue(
coloredShapePipelineSettings instanceof ColoredShapePipelineSettings,
"Conig loaded pipeline settings for index 1 not of expected type ColoredShapePipelineSettings!");
"Config loaded pipeline settings for index 1 not of expected type ColoredShapePipelineSettings!");
Assertions.assertTrue(
apriltagPipelineSettings instanceof AprilTagPipelineSettings,
"Conig loaded pipeline settings for index 2 not of expected type AprilTagPipelineSettings!");
"Config loaded pipeline settings for index 2 not of expected type AprilTagPipelineSettings!");
}

@AfterAll
Expand Down

0 comments on commit 14cd3fc

Please sign in to comment.