#computer-vision #computer #vision #photogrammetry #operating-system

no-std opencv-ros-camera

Geometric models of OpenCV/ROS cameras for photogrammetry

23 releases (14 breaking)

0.15.1 Dec 2, 2024
0.15.0 Aug 4, 2024
0.14.1 Jun 19, 2023
0.14.0 Jan 16, 2023
0.2.1 Mar 18, 2020

#6 in Robotics

Download history 117/week @ 2024-08-25 115/week @ 2024-09-01 164/week @ 2024-09-08 140/week @ 2024-09-15 201/week @ 2024-09-22 238/week @ 2024-09-29 323/week @ 2024-10-06 287/week @ 2024-10-13 499/week @ 2024-10-20 586/week @ 2024-10-27 431/week @ 2024-11-03 363/week @ 2024-11-10 315/week @ 2024-11-17 198/week @ 2024-11-24 1001/week @ 2024-12-01 894/week @ 2024-12-08

2,442 downloads per month

MIT/Apache

53KB
790 lines

Crate opencv_ros_camera for the Rust language

Crates.io Documentation Crate License Dependency status build

Geometric models of OpenCV/ROS cameras for photogrammetry

About

This crate provides a geometric model of a camera compatible with OpenCV as used by ROS (the Robot Operating System). The crate is in pure Rust, can be compiled in no_std mode, implements the IntrinsicParameters trait from the cam-geom and provides support to read and write camera models in various formats.

In greater detail:

Example - read a ROS YAML file and create a cam_geom::Camera from it.

Let's say we have YAML file saved by the ROS camera_calibration/cameracalibrator.py node. How can we create a cam_geom::Camera from this?

use nalgebra::{Matrix2x3, Unit, Vector3};

// Here we have the YAML file contents hardcoded in a string. Ordinarily, you
// would read this from a file such as `~/.ros/camera_info/camera_name.yaml`, but
// for this example, it is hardcoded here.
let yaml_buf = b"image_width: 659
image_height: 494
camera_name: Basler_21029382
camera_matrix:
  rows: 3
  cols: 3
  data: [516.385667640757, 0, 339.167079537312, 0, 516.125799367807, 227.37993524141, 0, 0, 1]
distortion_model: plumb_bob
distortion_coefficients:
  rows: 1
  cols: 5
  data: [-0.331416226762003, 0.143584747015566, 0.00314558656668844, -0.00393597842852019, 0]
rectification_matrix:
  rows: 3
  cols: 3
  data: [1, 0, 0, 0, 1, 0, 0, 0, 1]
projection_matrix:
  rows: 3
  cols: 4
  data: [444.369750976562, 0, 337.107817516087, 0, 0, 474.186859130859, 225.062742824321, 0, 0, 0, 1, 0]";

// The ROS YAML file does not contain the pose (no extrinsic parameters). Here we
// specify them directly. The camera is at (10,0,0), looing at (0,0,0), with up (0,0,1).
let camcenter = Vector3::new(10.0, 0.0, 0.0);
let lookat = Vector3::new(0.0, 0.0, 0.0);
let up = Unit::new_normalize(Vector3::new(0.0, 0.0, 1.0));
let pose = cam_geom::ExtrinsicParameters::from_view(&camcenter, &lookat, &up);

// We need the `serde-serialize` feature for the `from_ros_yaml` function.
#[cfg(feature = "serde-serialize")]
{
    let from_ros = opencv_ros_camera::from_ros_yaml(&yaml_buf[..]).unwrap();

    // Finally, create camera from intrinsic and extrinsic parameters.
    let camera = cam_geom::Camera::new(from_ros.intrinsics, pose);
}

testing

Test no_std compilation with:

# install target with: "rustup target add thumbv7em-none-eabihf"
cargo check --no-default-features --target thumbv7em-none-eabihf

Run unit tests with:

cargo test
cargo test --features serde-serialize

serde support requires std.

re-render README.md

cargo install cargo-readme
cargo readme > README.md

==========================================================

Code of conduct

Anyone who interacts with this software in any space, including but not limited to this GitHub repository, must follow our code of conduct.

License

Licensed under either of these:

Dependencies

~4.5MB
~90K SLoC