Skip to main content

from_struct_array

Function from_struct_array 

Source
pub fn from_struct_array(
    array: &StructArray,
) -> Result<OdometryOwned, ArrowError>
Expand description

Decode the first row of a StructArray into a heap-owned OdometryOwned.

ยงExample

use arrow::array::StructArray;
use isaac_sim_arrow::odometry::{Odometry, to_record_batch, from_struct_array};
let odom = Odometry {
    chassis_frame_id: "base_link",
    odom_frame_id: "odom",
    position_x: 1.0, position_y: 2.0, position_z: 0.0,
    orientation_w: 1.0, orientation_x: 0.0, orientation_y: 0.0, orientation_z: 0.0,
    lin_vel_x: 0.4, lin_vel_y: 0.0, lin_vel_z: 0.0,
    ang_vel_x: 0.0, ang_vel_y: 0.0, ang_vel_z: 0.3,
    timestamp_ns: 7,
};
let batch = to_record_batch(&odom).unwrap();
let array = StructArray::from(batch);
let owned = from_struct_array(&array).unwrap();
assert_eq!(owned.chassis_frame_id, "base_link");
assert_eq!(owned.timestamp_ns, 7);