diff --git a/.github/workflows/CI.yml b/.github/workflows/CI.yml index cebbe965..a15fdb32 100644 --- a/.github/workflows/CI.yml +++ b/.github/workflows/CI.yml @@ -21,3 +21,7 @@ jobs: run: cargo build --verbose - name: Run tests run: cargo test --verbose + - name: Check Formating + run: cargo fmt -- --check + - name: Run Clippy + run: cargo clippy -- -D warnings diff --git a/src/config.rs b/src/config.rs index 05de2abb..15078e0f 100644 --- a/src/config.rs +++ b/src/config.rs @@ -134,7 +134,7 @@ pub struct CameraConfig { /// Camera far clipping plane in meters pub far: f32, /// Camera transform matrix for depth - pub rotation_transform: [f32; 9] + pub rotation_transform: [f32; 9], } #[derive(serde::Deserialize)] diff --git a/src/lib.rs b/src/lib.rs index 2b8d7568..b2107959 100644 --- a/src/lib.rs +++ b/src/lib.rs @@ -2603,28 +2603,29 @@ pub fn log_depth_image( /// let cam_position = Vector3::new(0.0,0.0,0.0); /// let cam_orientation = UnitQuaternion::identity(); /// let cam_transform = [0.0, 0.0, 1.0, -1.0, 0.0, 0.0, 0.0, -1.0, 0.0]; -/// pinhole_depth(&rec, 128usize, 96usize, 90.0, cam_position, cam_orientation, cam_transform, &depth_image).unwrap(); +/// pinhole_depth(&rec, (128usize, 96usize), 90.0, cam_position, cam_orientation, cam_transform, &depth_image).unwrap(); pub fn pinhole_depth( rec: &rerun::RecordingStream, - width: usize, - height: usize, + resolution: (usize, usize), fov: f32, cam_position: Vector3, cam_orientation: UnitQuaternion, cam_transform: [f32; 9], depth_image: &[f32], ) -> Result<(), SimulationError> { + let width = resolution.0; + let height = resolution.1; let fov_x = (width as f32 / height as f32 * (fov / 2.0).tan()).atan() * 2.0; - let horizontal_focal_length = (width as f32 / 2.0) / ((fov_x/ 2.0).tan()); + let horizontal_focal_length = (width as f32 / 2.0) / ((fov_x / 2.0).tan()); let vertical_focal_length = (height as f32 / 2.0) / ((fov / 2.0).tan()); let pinhole_camera = rerun::Pinhole::from_focal_length_and_resolution( (horizontal_focal_length, vertical_focal_length), (width as f32, height as f32), ) - .with_camera_xyz(rerun::components::ViewCoordinates::RDF) - .with_resolution((width as f32, height as f32)) - .with_principal_point((width as f32 / 2.0, height as f32 / 2.0)); + .with_camera_xyz(rerun::components::ViewCoordinates::RDF) + .with_resolution((width as f32, height as f32)) + .with_principal_point((width as f32 / 2.0, height as f32 / 2.0)); let rotated_camera_orientation = UnitQuaternion::from_rotation_matrix( &(cam_orientation.to_rotation_matrix() * Rotation3::from_matrix_unchecked(Matrix3::from_row_slice(&cam_transform))), diff --git a/src/main.rs b/src/main.rs index b64afc1a..712ef54a 100644 --- a/src/main.rs +++ b/src/main.rs @@ -163,8 +163,7 @@ fn main() -> Result<(), SimulationError> { )?; pinhole_depth( rec, - camera.resolution.0, - camera.resolution.1, + camera.resolution, camera.fov, quad.position, quad.orientation,