1use serde::{Deserialize, Serialize};
6use validator::Validate;
7
8use super::common::{BoundingBox, BoundingBox2D, ObjectRef, Position3D};
9use crate::models::enums::{DetectionConfidence, GpsFixType, SensorStatus};
10
11#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
13pub struct PerceptionDomain {
14 #[serde(skip_serializing_if = "Option::is_none")]
17 pub lidar: Option<Vec<LidarSensor>>,
18
19 #[serde(skip_serializing_if = "Option::is_none")]
22 pub cameras: Option<Vec<CameraSensor>>,
23
24 #[serde(skip_serializing_if = "Option::is_none")]
27 pub imu: Option<ImuSensor>,
28
29 #[serde(skip_serializing_if = "Option::is_none")]
32 pub gps: Option<GpsSensor>,
33
34 #[serde(skip_serializing_if = "Option::is_none")]
37 pub uwb: Option<UwbSensor>,
38
39 #[serde(skip_serializing_if = "Option::is_none")]
42 pub detections: Option<Vec<Detection>>,
43
44 #[serde(skip_serializing_if = "Option::is_none")]
46 pub detection_count: Option<u32>,
47
48 #[serde(skip_serializing_if = "Option::is_none")]
51 pub environment: Option<EnvironmentPerception>,
52
53 #[serde(skip_serializing_if = "Option::is_none")]
56 pub ultrasonics: Option<Vec<UltrasonicSensor>>,
57
58 #[serde(skip_serializing_if = "Option::is_none")]
60 pub bumpers: Option<Vec<BumperSensor>>,
61
62 #[serde(skip_serializing_if = "Option::is_none")]
64 pub cliff_sensors: Option<Vec<CliffSensor>>,
65}
66
67#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
69pub struct LidarSensor {
70 #[serde(skip_serializing_if = "Option::is_none")]
72 pub sensor_id: Option<String>,
73
74 #[serde(skip_serializing_if = "Option::is_none")]
76 pub name: Option<String>,
77
78 #[serde(skip_serializing_if = "Option::is_none")]
80 pub status: Option<SensorStatus>,
81
82 #[serde(skip_serializing_if = "Option::is_none")]
84 pub sensor_type: Option<String>,
85
86 #[serde(skip_serializing_if = "Option::is_none")]
88 pub point_count: Option<u32>,
89
90 #[serde(skip_serializing_if = "Option::is_none")]
92 pub scan_frequency_hz: Option<f64>,
93
94 #[serde(skip_serializing_if = "Option::is_none")]
96 pub min_range_m: Option<f64>,
97
98 #[serde(skip_serializing_if = "Option::is_none")]
100 pub max_range_m: Option<f64>,
101
102 #[serde(skip_serializing_if = "Option::is_none")]
104 pub min_angle_deg: Option<f64>,
105
106 #[serde(skip_serializing_if = "Option::is_none")]
108 pub max_angle_deg: Option<f64>,
109
110 #[serde(skip_serializing_if = "Option::is_none")]
112 pub angular_resolution_deg: Option<f64>,
113
114 #[serde(skip_serializing_if = "Option::is_none")]
116 pub is_3d: Option<bool>,
117
118 #[serde(skip_serializing_if = "Option::is_none")]
120 pub closest_range_m: Option<f64>,
121
122 #[serde(skip_serializing_if = "Option::is_none")]
124 pub closest_angle_deg: Option<f64>,
125}
126
127#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
129pub struct CameraSensor {
130 #[serde(skip_serializing_if = "Option::is_none")]
132 pub sensor_id: Option<String>,
133
134 #[serde(skip_serializing_if = "Option::is_none")]
136 pub name: Option<String>,
137
138 #[serde(skip_serializing_if = "Option::is_none")]
140 pub status: Option<SensorStatus>,
141
142 #[serde(skip_serializing_if = "Option::is_none")]
144 pub camera_type: Option<String>,
145
146 #[serde(skip_serializing_if = "Option::is_none")]
148 pub width: Option<u32>,
149
150 #[serde(skip_serializing_if = "Option::is_none")]
152 pub height: Option<u32>,
153
154 #[serde(skip_serializing_if = "Option::is_none")]
156 pub frame_rate_fps: Option<f64>,
157
158 #[serde(skip_serializing_if = "Option::is_none")]
160 pub fov_deg: Option<f64>,
161
162 #[serde(skip_serializing_if = "Option::is_none")]
164 pub has_depth: Option<bool>,
165
166 #[serde(skip_serializing_if = "Option::is_none")]
168 pub exposure_ms: Option<f64>,
169
170 #[serde(skip_serializing_if = "Option::is_none")]
172 pub gain: Option<f64>,
173}
174
175#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
177pub struct ImuSensor {
178 #[serde(skip_serializing_if = "Option::is_none")]
180 pub status: Option<SensorStatus>,
181
182 #[serde(skip_serializing_if = "Option::is_none")]
184 pub accel_x_mps2: Option<f64>,
185
186 #[serde(skip_serializing_if = "Option::is_none")]
188 pub accel_y_mps2: Option<f64>,
189
190 #[serde(skip_serializing_if = "Option::is_none")]
192 pub accel_z_mps2: Option<f64>,
193
194 #[serde(skip_serializing_if = "Option::is_none")]
196 pub gyro_x_dps: Option<f64>,
197
198 #[serde(skip_serializing_if = "Option::is_none")]
200 pub gyro_y_dps: Option<f64>,
201
202 #[serde(skip_serializing_if = "Option::is_none")]
204 pub gyro_z_dps: Option<f64>,
205
206 #[serde(skip_serializing_if = "Option::is_none")]
208 pub mag_x_ut: Option<f64>,
209
210 #[serde(skip_serializing_if = "Option::is_none")]
212 pub mag_y_ut: Option<f64>,
213
214 #[serde(skip_serializing_if = "Option::is_none")]
216 pub mag_z_ut: Option<f64>,
217
218 #[serde(skip_serializing_if = "Option::is_none")]
220 pub temperature_c: Option<f64>,
221
222 #[serde(skip_serializing_if = "Option::is_none")]
224 pub update_rate_hz: Option<f64>,
225}
226
227#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
229pub struct GpsSensor {
230 #[serde(skip_serializing_if = "Option::is_none")]
232 pub status: Option<SensorStatus>,
233
234 #[serde(skip_serializing_if = "Option::is_none")]
236 pub fix_type: Option<GpsFixType>,
237
238 #[serde(skip_serializing_if = "Option::is_none")]
240 pub satellites: Option<u32>,
241
242 #[serde(skip_serializing_if = "Option::is_none")]
244 pub hdop: Option<f64>,
245
246 #[serde(skip_serializing_if = "Option::is_none")]
248 pub vdop: Option<f64>,
249
250 #[serde(skip_serializing_if = "Option::is_none")]
252 pub pdop: Option<f64>,
253
254 #[serde(skip_serializing_if = "Option::is_none")]
256 #[validate(range(min = 0.0))]
257 pub horizontal_accuracy_m: Option<f64>,
258
259 #[serde(skip_serializing_if = "Option::is_none")]
261 #[validate(range(min = 0.0))]
262 pub vertical_accuracy_m: Option<f64>,
263
264 #[serde(skip_serializing_if = "Option::is_none")]
266 #[validate(range(min = 0.0))]
267 pub speed_mps: Option<f64>,
268
269 #[serde(skip_serializing_if = "Option::is_none")]
271 #[validate(range(min = 0.0, max = 360.0))]
272 pub course_deg: Option<f64>,
273}
274
275#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
277pub struct UwbSensor {
278 #[serde(skip_serializing_if = "Option::is_none")]
280 pub status: Option<SensorStatus>,
281
282 #[serde(skip_serializing_if = "Option::is_none")]
284 pub anchors_in_range: Option<u32>,
285
286 #[serde(skip_serializing_if = "Option::is_none")]
288 #[validate(range(min = 0.0))]
289 pub position_accuracy_m: Option<f64>,
290
291 #[serde(skip_serializing_if = "Option::is_none")]
293 pub anchors: Option<Vec<UwbAnchor>>,
294}
295
296#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
298pub struct UwbAnchor {
299 #[serde(skip_serializing_if = "Option::is_none")]
301 pub anchor_id: Option<String>,
302
303 #[serde(skip_serializing_if = "Option::is_none")]
305 #[validate(range(min = 0.0))]
306 pub distance_m: Option<f64>,
307
308 #[serde(skip_serializing_if = "Option::is_none")]
310 pub rssi_dbm: Option<f64>,
311}
312
313#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
315pub struct Detection {
316 #[serde(skip_serializing_if = "Option::is_none")]
318 pub detection_id: Option<String>,
319
320 #[serde(skip_serializing_if = "Option::is_none")]
322 pub object: Option<ObjectRef>,
323
324 #[serde(skip_serializing_if = "Option::is_none")]
326 pub class_label: Option<String>,
327
328 #[serde(skip_serializing_if = "Option::is_none")]
330 pub confidence: Option<DetectionConfidence>,
331
332 #[serde(skip_serializing_if = "Option::is_none")]
334 #[validate(range(min = 0.0, max = 1.0))]
335 pub confidence_score: Option<f64>,
336
337 #[serde(skip_serializing_if = "Option::is_none")]
339 pub bounding_box_3d: Option<BoundingBox>,
340
341 #[serde(skip_serializing_if = "Option::is_none")]
343 pub bounding_box_2d: Option<BoundingBox2D>,
344
345 #[serde(skip_serializing_if = "Option::is_none")]
347 pub position: Option<Position3D>,
348
349 #[serde(skip_serializing_if = "Option::is_none")]
351 #[validate(range(min = 0.0))]
352 pub distance_m: Option<f64>,
353
354 #[serde(skip_serializing_if = "Option::is_none")]
356 pub source_sensor: Option<String>,
357
358 #[serde(skip_serializing_if = "Option::is_none")]
360 pub is_human: Option<bool>,
361
362 #[serde(skip_serializing_if = "Option::is_none")]
364 pub velocity_mps: Option<f64>,
365
366 #[serde(skip_serializing_if = "Option::is_none")]
368 pub heading_deg: Option<f64>,
369}
370
371#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
373pub struct EnvironmentPerception {
374 #[serde(skip_serializing_if = "Option::is_none")]
376 #[validate(range(min = 0.0))]
377 pub ambient_light_lux: Option<f64>,
378
379 #[serde(skip_serializing_if = "Option::is_none")]
381 pub surface_type: Option<String>,
382
383 #[serde(skip_serializing_if = "Option::is_none")]
385 #[validate(range(min = 0.0, max = 1.0))]
386 pub surface_friction: Option<f64>,
387
388 #[serde(skip_serializing_if = "Option::is_none")]
390 pub incline_deg: Option<f64>,
391
392 #[serde(skip_serializing_if = "Option::is_none")]
394 pub visibility_m: Option<f64>,
395
396 #[serde(skip_serializing_if = "Option::is_none")]
398 pub is_cluttered: Option<bool>,
399}
400
401#[derive(Debug, Clone, Default, Serialize, Deserialize, Validate)]
403pub struct UltrasonicSensor {
404 #[serde(skip_serializing_if = "Option::is_none")]
406 pub sensor_id: Option<String>,
407
408 #[serde(skip_serializing_if = "Option::is_none")]
410 pub status: Option<SensorStatus>,
411
412 #[serde(skip_serializing_if = "Option::is_none")]
414 #[validate(range(min = 0.0))]
415 pub range_m: Option<f64>,
416
417 #[serde(skip_serializing_if = "Option::is_none")]
419 pub min_range_m: Option<f64>,
420
421 #[serde(skip_serializing_if = "Option::is_none")]
423 pub max_range_m: Option<f64>,
424}
425
426#[derive(Debug, Clone, Default, Serialize, Deserialize)]
428pub struct BumperSensor {
429 #[serde(skip_serializing_if = "Option::is_none")]
431 pub sensor_id: Option<String>,
432
433 #[serde(skip_serializing_if = "Option::is_none")]
435 pub is_triggered: Option<bool>,
436
437 #[serde(skip_serializing_if = "Option::is_none")]
439 pub location: Option<String>,
440}
441
442#[derive(Debug, Clone, Default, Serialize, Deserialize)]
444pub struct CliffSensor {
445 #[serde(skip_serializing_if = "Option::is_none")]
447 pub sensor_id: Option<String>,
448
449 #[serde(skip_serializing_if = "Option::is_none")]
451 pub cliff_detected: Option<bool>,
452
453 #[serde(skip_serializing_if = "Option::is_none")]
455 pub location: Option<String>,
456}
457
458impl PerceptionDomain {
459 pub fn with_lidar(sensor: LidarSensor) -> Self {
461 Self {
462 lidar: Some(vec![sensor]),
463 ..Default::default()
464 }
465 }
466
467 pub fn with_detection(mut self, detection: Detection) -> Self {
469 let detections = self.detections.get_or_insert_with(Vec::new);
470 detections.push(detection);
471 self.detection_count = Some(detections.len() as u32);
472 self
473 }
474
475 pub fn with_imu(mut self, imu: ImuSensor) -> Self {
477 self.imu = Some(imu);
478 self
479 }
480
481 pub fn with_gps(mut self, gps: GpsSensor) -> Self {
483 self.gps = Some(gps);
484 self
485 }
486}
487
488impl Detection {
489 pub fn human(distance_m: f64, confidence: f64) -> Self {
491 Self {
492 class_label: Some("person".to_string()),
493 is_human: Some(true),
494 distance_m: Some(distance_m),
495 confidence_score: Some(confidence),
496 ..Default::default()
497 }
498 }
499
500 pub fn new(class_label: impl Into<String>, distance_m: f64, confidence: f64) -> Self {
502 Self {
503 class_label: Some(class_label.into()),
504 distance_m: Some(distance_m),
505 confidence_score: Some(confidence),
506 ..Default::default()
507 }
508 }
509}
510
511#[cfg(test)]
512mod tests {
513 use super::*;
514
515 #[test]
516 fn test_detection_human() {
517 let det = Detection::human(2.5, 0.95);
518 assert_eq!(det.is_human, Some(true));
519 assert_eq!(det.distance_m, Some(2.5));
520 }
521
522 #[test]
523 fn test_perception_domain() {
524 let perception = PerceptionDomain::default()
525 .with_detection(Detection::human(3.0, 0.9))
526 .with_detection(Detection::new("forklift", 5.0, 0.85));
527
528 assert_eq!(perception.detection_count, Some(2));
529 }
530}