pub fn from_struct_array(
array: &StructArray,
) -> Result<CameraInfoOwned, ArrowError>Expand description
Decode the first row of a StructArray into a heap-owned CameraInfoOwned.
ยงExample
use arrow::array::StructArray;
use isaac_sim_arrow::camera::info::{CameraInfo, to_record_batch, from_struct_array};
let k = [500.0_f64, 0.0, 320.0, 0.0, 500.0, 240.0, 0.0, 0.0, 1.0];
let r = [1.0_f64, 0.0, 0.0, 0.0, 1.0, 0.0, 0.0, 0.0, 1.0];
let p = [500.0_f64, 0.0, 320.0, 0.0, 0.0, 500.0, 240.0, 0.0, 0.0, 0.0, 1.0, 0.0];
let d = [0.0_f32; 5];
let info = CameraInfo { frame_id: "cam", distortion_model: "plumb_bob",
projection_type: "pinhole", k: &k, r: &r, p: &p, distortion: &d,
width: 640, height: 480, timestamp_ns: 2 };
let batch = to_record_batch(&info).unwrap();
let array = StructArray::from(batch);
let owned = from_struct_array(&array).unwrap();
assert_eq!(owned.frame_id, "cam");
assert_eq!(owned.width, 640);