Skip to content

Commit

Permalink
update CI
Browse files Browse the repository at this point in the history
  • Loading branch information
makeecat committed Oct 29, 2024
1 parent 5d291f8 commit d9e0202
Show file tree
Hide file tree
Showing 4 changed files with 14 additions and 10 deletions.
4 changes: 4 additions & 0 deletions .github/workflows/CI.yml
Original file line number Diff line number Diff line change
Expand Up @@ -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
2 changes: 1 addition & 1 deletion src/config.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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)]
Expand Down
15 changes: 8 additions & 7 deletions src/lib.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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<f32>,
cam_orientation: UnitQuaternion<f32>,
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))),
Expand Down
3 changes: 1 addition & 2 deletions src/main.rs
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand Down

0 comments on commit d9e0202

Please sign in to comment.