Skip to content

Commit

Permalink
format
Browse files Browse the repository at this point in the history
  • Loading branch information
amquake committed Oct 20, 2023
1 parent 975519a commit 8fb104a
Show file tree
Hide file tree
Showing 4 changed files with 7 additions and 8 deletions.
4 changes: 2 additions & 2 deletions photon-client/src/components/dashboard/tabs/OutputTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,7 @@ const interactiveCols = computed(
<pv-switch
v-if="
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().isCurrentVideoFormatCalibrated
"
v-model="currentPipelineSettings.doMultiTarget"
Expand All @@ -100,7 +100,7 @@ const interactiveCols = computed(
<pv-switch
v-if="
(currentPipelineSettings.pipelineType === PipelineType.AprilTag ||
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
currentPipelineSettings.pipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().isCurrentVideoFormatCalibrated
"
v-model="currentPipelineSettings.doSingleTargetAlways"
Expand Down
2 changes: 1 addition & 1 deletion photon-client/src/components/dashboard/tabs/TargetsTab.vue
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,7 @@ import { useStateStore } from "@/stores/StateStore";
<v-row
v-if="
(useCameraSettingsStore().currentPipelineType === PipelineType.AprilTag ||
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().currentPipelineType === PipelineType.Aruco) &&
useCameraSettingsStore().currentPipelineSettings.doMultiTarget
"
align="start"
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -79,7 +79,7 @@ protected void setPipeParamsImpl() {
var params = new ArucoDetectionPipeParams();
// sanitize and record settings

switch(settings.tagFamily) {
switch (settings.tagFamily) {
case kTag36h11:
params.tagFamily = Objdetect.DICT_APRILTAG_36h11;
break;
Expand Down Expand Up @@ -196,7 +196,8 @@ protected CVPipelineResult process(Frame frame, ArucoPipelineSettings settings)
new Transform3d(
new Pose3d().plus(multiTagResult.estimatedPose.best), tagPose.get());
// match expected OpenCV coordinate system
camToTag = CoordinateSystem.convert(camToTag, CoordinateSystem.NWU(), CoordinateSystem.EDN());
camToTag =
CoordinateSystem.convert(camToTag, CoordinateSystem.NWU(), CoordinateSystem.EDN());

tagPoseEstimate = new AprilTagPoseEstimate(camToTag, camToTag, 0, 0);
}
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -17,8 +17,8 @@

package org.photonvision.vision.pipeline;

import edu.wpi.first.math.geometry.Translation3d;
import java.util.stream.Collectors;

import org.junit.jupiter.api.Assertions;
import org.junit.jupiter.api.BeforeEach;
import org.junit.jupiter.api.Test;
Expand All @@ -31,8 +31,6 @@
import org.photonvision.vision.target.TargetModel;
import org.photonvision.vision.target.TrackedTarget;

import edu.wpi.first.math.geometry.Translation3d;

public class ArucoPipelineTest {
@BeforeEach
public void setup() {
Expand Down

0 comments on commit 8fb104a

Please sign in to comment.