Skip to content

Commit

Permalink
braid-april-cal: do not require opencv by default
Browse files Browse the repository at this point in the history
  • Loading branch information
astraw committed Jan 13, 2025
1 parent 95e7781 commit 552ff91
Show file tree
Hide file tree
Showing 5 changed files with 18 additions and 14 deletions.
2 changes: 0 additions & 2 deletions braid-april-cal/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,4 @@ anyhow.workspace = true
ads-webasm = { workspace = true, features = ["csv-widget"] }

[features]
default = ["solve-pnp"]

solve-pnp = ["opencv-calibrate"]
2 changes: 1 addition & 1 deletion braid-april-cal/braid-april-cal-webapp/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -26,6 +26,6 @@ wasm-logger.workspace = true
chrono.workspace = true

ads-webasm = { workspace = true, features = ["csv-widget"] }
braid-april-cal = { path = "..", default-features = false }
braid-april-cal.workspace = true

[features]
2 changes: 1 addition & 1 deletion braid-april-cal/flytrax-apriltags-calibration/Cargo.toml
Original file line number Diff line number Diff line change
Expand Up @@ -20,7 +20,7 @@ tracing.workspace = true

ads-webasm = { workspace = true, features = ["csv-widget"] }
ads-apriltag.workspace = true
braid-april-cal.workspace = true
braid-april-cal = { workspace = true, features = ["solve-pnp"] }
convert-image.workspace = true
flydra-types.workspace = true
flytrax-io.workspace = true
Expand Down
23 changes: 13 additions & 10 deletions braid-april-cal/src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -292,11 +292,11 @@ fn dlt(
Ok(linear_cam)
}

#[cfg(feature = "solve-pnp")]
fn solve_extrinsics(
points: Vec<AprilTagCorrespondingPoint<f64>>,
intrinsics: &NamedIntrinsicParameters<f64>,
) -> Result<CamSolution, MyError> {
#[cfg(feature = "solve-pnp")]
{
let cv_points: Vec<opencv_calibrate::CorrespondingPoint> = points
.iter()
Expand Down Expand Up @@ -361,13 +361,6 @@ fn solve_extrinsics(

Ok(CamSolution { final_cam, points })
}
#[cfg(not(feature = "solve-pnp"))]
{
let _ = (intrinsics, points);
Err(MyError {
msg: "'solve-pnp' feature must be enabled to solve extrinsics".into(),
})
}
}

fn dlt_then_distortion(
Expand Down Expand Up @@ -440,8 +433,18 @@ pub fn do_calibrate_system(src_data: &CalData) -> Result<CalibrationResult, MyEr
}

let sln = if let Some(kgi) = src_data.known_good_intrinsics.as_ref() {
let known_good_intrinsics = kgi.get(cam_name).unwrap();
solve_extrinsics(points, known_good_intrinsics)?
#[cfg(feature = "solve-pnp")]
{
let known_good_intrinsics = kgi.get(cam_name).unwrap();
solve_extrinsics(points, known_good_intrinsics)?
}
#[cfg(not(feature = "solve-pnp"))]
{
let _ = kgi;
return Err(MyError {
msg: "'solve-pnp' feature must be enabled to solve extrinsics when intrinsics provided".into(),
});
}
} else {
dlt_then_distortion(cfg, points)?
};
Expand Down
3 changes: 3 additions & 0 deletions braid-april-cal/tests/integration-test.rs
Original file line number Diff line number Diff line change
@@ -1,5 +1,7 @@
use ads_webasm::components::{parse_csv, MaybeCsvData};
use braid_april_cal::*;

#[cfg(feature = "solve-pnp")]
use opencv_ros_camera::{NamedIntrinsicParameters, RosCameraInfo};

fn gen_cal() -> CalibrationResult {
Expand Down Expand Up @@ -107,6 +109,7 @@ fn test_calibration_pymvg() {
}

#[test]
#[cfg(feature = "solve-pnp")]
fn solve_pnp_with_prior_intrinsics() -> anyhow::Result<()> {
let fiducial_3d_coords_buf = include_bytes!("data-single-cam/apriltags_coordinates.csv");
let fiducial_3d_coords = parse_csv::<Fiducial3DCoords>(
Expand Down

0 comments on commit 552ff91

Please sign in to comment.