1#![cfg_attr(docsrs, feature(doc_cfg))]
3#![warn(missing_docs)]
11#![cfg_attr(not(feature = "cdylib"), allow(dead_code))]
12
13mod articulation;
14mod camera;
15mod channel;
16mod demo;
17mod imu;
18mod lidar;
19mod lifecycle;
20mod odometry;
21mod producer;
22mod sensor;
23mod source;
24
25pub use articulation::cmd_vel::{
26 cmd_vel_consumer_count, cmd_vel_producer_count, peek_cmd_vel, register_cmd_vel_consumer,
27 register_cmd_vel_producer, CmdVelChannel,
28};
29pub use camera::depth::{
30 camera_depth_consumer_count, dispatch_camera_depth, register_camera_depth_consumer, CameraDepth,
31};
32pub use camera::info::{
33 camera_info_consumer_count, dispatch_camera_info, register_camera_info_consumer, CameraInfo,
34 CameraInfoFrame,
35};
36pub use camera::rgb::{
37 camera_rgb_consumer_count, dispatch_camera_rgb, register_camera_rgb_consumer, CameraRgb,
38};
39pub use imu::{dispatch_imu, imu_consumer_count, register_imu_consumer, Imu};
40pub use lidar::flatscan::{
41 dispatch_lidar_flatscan, lidar_flatscan_consumer_count, register_lidar_flatscan_consumer,
42 LidarFlatScan,
43};
44pub use lidar::pointcloud::{
45 dispatch_lidar_pointcloud, lidar_pointcloud_consumer_count, register_lidar_pointcloud_consumer,
46 LidarPointCloud,
47};
48pub use odometry::{
49 dispatch_odometry, odometry_consumer_count, register_odometry_consumer, Odometry,
50};
51pub use producer::{ProducerRegistry, ProducerSlot};
52pub use sensor::Sensor;
53pub use source::SourceFilter;
54
55#[allow(clippy::too_many_arguments)]
56#[allow(missing_docs)]
57#[cxx::bridge(namespace = "isaacsimrs")]
58mod ffi {
59 #[derive(Clone, Copy)]
60 struct LidarFlatScanMeta {
61 horizontal_fov: f32,
62 horizontal_resolution: f32,
63 azimuth_min: f32,
64 azimuth_max: f32,
65 depth_min: f32,
66 depth_max: f32,
67 num_rows: i32,
68 num_cols: i32,
69 rotation_rate: f32,
70 }
71
72 #[derive(Clone, Copy)]
73 struct LidarPointCloudMeta {
74 num_points: i32,
75 width: i32,
76 height: i32,
77 }
78
79 #[derive(Clone, Copy)]
80 struct CameraRgbMeta {
81 width: i32,
82 height: i32,
83 fx: f32,
84 fy: f32,
85 cx: f32,
86 cy: f32,
87 timestamp_ns: i64,
88 }
89
90 #[derive(Clone, Copy)]
91 struct CameraDepthMeta {
92 width: i32,
93 height: i32,
94 fx: f32,
95 fy: f32,
96 cx: f32,
97 cy: f32,
98 timestamp_ns: i64,
99 }
100
101 #[derive(Clone, Copy)]
102 struct CameraInfoMeta {
103 width: i32,
104 height: i32,
105 timestamp_ns: i64,
106 }
107
108 #[derive(Clone, Copy)]
109 struct ImuMeta {
110 lin_acc_x: f64,
111 lin_acc_y: f64,
112 lin_acc_z: f64,
113 ang_vel_x: f64,
114 ang_vel_y: f64,
115 ang_vel_z: f64,
116 orientation_w: f64,
117 orientation_x: f64,
118 orientation_y: f64,
119 orientation_z: f64,
120 timestamp_ns: i64,
121 }
122
123 #[derive(Clone, Copy)]
124 struct OdometryMeta {
125 position_x: f64,
126 position_y: f64,
127 position_z: f64,
128 orientation_w: f64,
129 orientation_x: f64,
130 orientation_y: f64,
131 orientation_z: f64,
132 lin_vel_x: f64,
133 lin_vel_y: f64,
134 lin_vel_z: f64,
135 ang_vel_x: f64,
136 ang_vel_y: f64,
137 ang_vel_z: f64,
138 timestamp_ns: i64,
139 }
140
141 #[derive(Default, Clone, Copy)]
142 struct CmdVel {
143 linear_x: f32,
144 linear_y: f32,
145 linear_z: f32,
146 angular_x: f32,
147 angular_y: f32,
148 angular_z: f32,
149 timestamp_ns: i64,
150 }
151
152 #[cfg(feature = "cdylib")]
153 extern "Rust" {
154 fn init();
155 fn double_value(x: i32) -> i32;
156 fn forward_lidar_flatscan(
157 source_id: &str,
158 scan: &[f32],
159 intensities: &[u8],
160 meta: &LidarFlatScanMeta,
161 );
162 fn forward_lidar_pointcloud(source_id: &str, points: &[f32], meta: &LidarPointCloudMeta);
163 fn forward_camera_rgb(source_id: &str, pixels: &[u8], meta: &CameraRgbMeta);
164 fn forward_camera_depth(source_id: &str, depths: &[f32], meta: &CameraDepthMeta);
165 fn forward_camera_info(
166 source_id: &str,
167 frame_id: &str,
168 distortion_model: &str,
169 projection_type: &str,
170 k: &[f64],
171 r: &[f64],
172 p: &[f64],
173 distortion: &[f32],
174 meta: &CameraInfoMeta,
175 );
176 fn forward_imu(source_id: &str, frame_id: &str, meta: &ImuMeta);
177 fn forward_odometry(
178 source_id: &str,
179 chassis_frame_id: &str,
180 odom_frame_id: &str,
181 meta: &OdometryMeta,
182 );
183 fn poll_cmd_vel(target_id: &str, out: &mut CmdVel) -> bool;
184 }
185}
186
187pub use ffi::{
190 CameraDepthMeta, CameraInfoMeta, CameraRgbMeta, CmdVel, ImuMeta, LidarFlatScanMeta,
191 LidarPointCloudMeta, OdometryMeta,
192};
193
194#[cfg(feature = "cdylib")]
195use articulation::cmd_vel::poll_cmd_vel;
196#[cfg(feature = "cdylib")]
197use camera::depth::forward_camera_depth;
198#[cfg(feature = "cdylib")]
199use camera::info::forward_camera_info;
200#[cfg(feature = "cdylib")]
201use camera::rgb::forward_camera_rgb;
202#[cfg(feature = "cdylib")]
203use demo::double_value;
204#[cfg(feature = "cdylib")]
205use imu::forward_imu;
206#[cfg(feature = "cdylib")]
207use lidar::flatscan::forward_lidar_flatscan;
208#[cfg(feature = "cdylib")]
209use lidar::pointcloud::forward_lidar_pointcloud;
210#[cfg(feature = "cdylib")]
211use lifecycle::init;
212#[cfg(feature = "cdylib")]
213use odometry::forward_odometry;