From b811d18ac735dab5b9877298971f2b2e61aa8fcb Mon Sep 17 00:00:00 2001 From: Andrew Straw Date: Mon, 13 Jan 2025 14:10:05 +0100 Subject: [PATCH] braid-april-cal: minor refactoring --- braid-april-cal/braid-april-cal-webapp/src/lib.rs | 6 +++--- .../flytrax-apriltags-calibration/src/lib.rs | 2 +- braid-april-cal/src/lib.rs | 13 ++++++++----- braid-april-cal/tests/integration-test.rs | 4 ++-- 4 files changed, 14 insertions(+), 11 deletions(-) diff --git a/braid-april-cal/braid-april-cal-webapp/src/lib.rs b/braid-april-cal/braid-april-cal-webapp/src/lib.rs index 6b266f91e..900ef9102 100644 --- a/braid-april-cal/braid-april-cal-webapp/src/lib.rs +++ b/braid-april-cal/braid-april-cal-webapp/src/lib.rs @@ -14,13 +14,13 @@ use braid_april_cal::*; pub struct Model { fiducial_3d_coords: MaybeCsvData, - per_camera_2d: BTreeMap)>, + per_camera_2d: BTreeMap)>, computed_calibration: Option, } pub enum Msg { Fiducial3dCoordsData(MaybeCsvData), - DetectionSerializerData(MaybeCsvData), + DetectionSerializerData(MaybeCsvData), RemoveCamera(String), ComputeCal, DownloadXmlCal, @@ -133,7 +133,7 @@ impl Component for Model {

{"Input: Automatically detected camera coordinates of April Tag fiducial markers"}

{"The file must be a CSV file saved by the April Tag detector of Strand Cam. (Required \ columns: id, h02, h12 where (h02,h12) is tag center.)"}

- + button_text={"Upload a camera coordinate CSV file."} onfile={ctx.link().callback(Msg::DetectionSerializerData)} /> diff --git a/braid-april-cal/flytrax-apriltags-calibration/src/lib.rs b/braid-april-cal/flytrax-apriltags-calibration/src/lib.rs index 23cc04be2..3075227dd 100644 --- a/braid-april-cal/flytrax-apriltags-calibration/src/lib.rs +++ b/braid-april-cal/flytrax-apriltags-calibration/src/lib.rs @@ -187,7 +187,7 @@ pub fn compute_extrinsics(cli: &ComputeExtrinsicsArgs) -> anyhow::Result = detections .iter() - .map(|d| DetectionSerializer { + .map(|d| AprilDetection { id: d.id, h02: d.x, h12: d.y, diff --git a/braid-april-cal/src/lib.rs b/braid-april-cal/src/lib.rs index 788fca5a0..4a5ea9803 100644 --- a/braid-april-cal/src/lib.rs +++ b/braid-april-cal/src/lib.rs @@ -123,9 +123,12 @@ pub struct Fiducial3DCoords { pub z: f64, } -// The center pixel of the detection is (h02,h12) -#[derive(Serialize, Deserialize, Debug, Clone, PartialEq)] -pub struct DetectionSerializer { +/// For deserializing a detection. +/// +/// Note that other fields are likely saved (e.g. `h00`), but we just ignore +/// those as they are not necessary for our purposes here. +#[derive(Deserialize, Debug, Clone, PartialEq)] +pub struct AprilDetection { pub id: i32, pub h02: f64, pub h12: f64, @@ -199,7 +202,7 @@ pub fn get_apriltag_cfg(rdr: R) -> Result, - pub per_camera_2d: BTreeMap)>, + pub per_camera_2d: BTreeMap)>, pub known_good_intrinsics: Option>>, } @@ -230,7 +233,7 @@ impl CalibrationResult { fn gather_points_per_cam( object_points: &BTreeMap, - cam_data: &[DetectionSerializer], + cam_data: &[AprilDetection], ) -> Result>, MyError> { // Iterate through all rows of detection data to collect all detections // per marker. diff --git a/braid-april-cal/tests/integration-test.rs b/braid-april-cal/tests/integration-test.rs index 55e6e4ad8..02df7147a 100644 --- a/braid-april-cal/tests/integration-test.rs +++ b/braid-april-cal/tests/integration-test.rs @@ -22,7 +22,7 @@ fn gen_cal() -> CalibrationResult { let per_camera_2d = cams_bufs .into_iter() .map(|buf| { - let detections = parse_csv::("camera-detections.csv".into(), &buf); + let detections = parse_csv::("camera-detections.csv".into(), &buf); match detections { MaybeCsvData::Valid(csv_data) => { let datavec = csv_data.rows().to_vec(); @@ -127,7 +127,7 @@ fn solve_pnp_with_prior_intrinsics() -> anyhow::Result<()> { let per_camera_2d = cams_bufs .into_iter() .map(|buf| { - let detections = parse_csv::("camera-detections.csv".into(), &buf); + let detections = parse_csv::("camera-detections.csv".into(), &buf); match detections { MaybeCsvData::Valid(csv_data) => { let datavec = csv_data.rows().to_vec();