mecha10_core/
topics.rs

1//! Type-Safe Topics System
2//!
3//! This module provides compile-time type-safe topic definitions,
4//! eliminating string-based topic errors and enabling better IDE support.
5//!
6//! # Quick Example
7//!
8//! ```rust
9//! use mecha10::prelude::*;
10//! use mecha10::topics::{Topic, sensor};
11//!
12//! // Define custom topics
13//! mod my_topics {
14//!     use super::*;
15//!
16//!     pub const CUSTOM: Topic<MyMessage> = Topic::new("/my/topic");
17//! }
18//!
19//! # async fn example(ctx: &Context) -> Result<()> {
20//! // Use built-in topics
21//! let mut images = ctx.subscribe(sensor::CAMERA_RGB).await?;
22//!
23//! // Use custom topics
24//! let mut custom = ctx.subscribe(my_topics::CUSTOM).await?;
25//! # Ok(())
26//! # }
27//! ```
28//!
29//! # Benefits
30//!
31//! - **Compile-time validation**: No typos, no runtime errors
32//! - **IDE autocomplete**: Full IntelliSense support
33//! - **Refactoring-safe**: Rename topics safely
34//! - **Type inference**: Return types inferred automatically
35
36use crate::messages::Message;
37use std::marker::PhantomData;
38
39/// A type-safe topic with an associated message type
40///
41/// This is the core abstraction that enables compile-time type safety for pub/sub.
42/// Topics are defined as constants and carry type information via phantom types.
43///
44/// # Type Safety Guarantee
45///
46/// The compiler ensures that:
47/// - Subscribe returns the correct message type
48/// - Publish accepts only the correct message type
49/// - No runtime type confusion is possible
50///
51/// # Example: Defining Topics
52///
53/// ```rust
54/// use mecha10::topics::Topic;
55/// use mecha10::messages::Image;
56///
57/// // Simple topic definition
58/// pub const CAMERA_RGB: Topic<Image> = Topic::new("/sensor/camera/rgb");
59///
60/// // Custom message type
61/// #[derive(Serialize, Deserialize)]
62/// struct MyMessage {
63///     value: f32,
64/// }
65///
66/// pub const CUSTOM: Topic<MyMessage> = Topic::new("/custom/topic");
67/// ```
68///
69/// # Example: Using Topics
70///
71/// ```rust
72/// # use mecha10::prelude::*;
73/// # use mecha10::topics::sensor;
74/// # async fn example(ctx: &Context) -> Result<()> {
75/// // Type is inferred as Receiver<Image>
76/// let mut images = ctx.subscribe(sensor::CAMERA_RGB).await?;
77///
78/// while let Some(image) = images.recv().await {
79///     // image is type Image
80///     println!("Image: {}x{}", image.width, image.height);
81///
82///     // Compiler ensures we publish the right type
83///     ctx.publish_to(sensor::CAMERA_RGB, &image).await?;
84///
85///     // This would be a compile error:
86///     // ctx.publish_to(sensor::CAMERA_RGB, &laser_scan).await?;
87///     //                                      ^^^^^^^^^^^ expected Image, found LaserScan
88/// }
89/// # Ok(())
90/// # }
91/// ```
92pub struct Topic<T: Message> {
93    path: &'static str,
94    _phantom: PhantomData<T>,
95}
96
97impl<T: Message> Topic<T> {
98    /// Create a new typed topic
99    ///
100    /// This is a const function, so topics can be defined as constants.
101    pub const fn new(path: &'static str) -> Self {
102        Self {
103            path,
104            _phantom: PhantomData,
105        }
106    }
107
108    /// Get the topic path
109    pub const fn path(&self) -> &'static str {
110        self.path
111    }
112
113    /// Get the topic as a string (for compatibility)
114    pub fn as_str(&self) -> &'static str {
115        self.path
116    }
117}
118
119impl<T: Message> Clone for Topic<T> {
120    fn clone(&self) -> Self {
121        *self
122    }
123}
124
125impl<T: Message> Copy for Topic<T> {}
126
127impl<T: Message> std::fmt::Debug for Topic<T> {
128    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
129        write!(f, "Topic<{}>({:?})", std::any::type_name::<T>(), self.path)
130    }
131}
132
133impl<T: Message> std::fmt::Display for Topic<T> {
134    fn fmt(&self, f: &mut std::fmt::Formatter<'_>) -> std::fmt::Result {
135        write!(f, "{}", self.path)
136    }
137}
138
139// ============================================================================
140// Standard Topic Definitions
141// ============================================================================
142
143/// Sensor topics
144pub mod sensor {
145    use super::*;
146    use crate::messages::{GpsData, Image, Imu, JointState, LaserScan, Odometry};
147
148    /// Camera RGB stream
149    pub const CAMERA_RGB: Topic<Image> = Topic::new("/sensor/camera/rgb");
150
151    /// Camera depth stream
152    pub const CAMERA_DEPTH: Topic<Image> = Topic::new("/sensor/camera/depth");
153
154    /// Left stereo camera
155    pub const CAMERA_LEFT: Topic<Image> = Topic::new("/sensor/camera/left");
156
157    /// Right stereo camera
158    pub const CAMERA_RIGHT: Topic<Image> = Topic::new("/sensor/camera/right");
159
160    /// Infrared camera
161    pub const CAMERA_IR: Topic<Image> = Topic::new("/sensor/camera/ir");
162
163    /// Thermal camera
164    pub const CAMERA_THERMAL: Topic<Image> = Topic::new("/sensor/camera/thermal");
165
166    /// Lidar scan stream (2D)
167    pub const LIDAR_SCAN: Topic<LaserScan> = Topic::new("/sensor/lidar/scan");
168
169    /// Lidar point cloud (3D)
170    pub const LIDAR_CLOUD: Topic<Vec<[f32; 3]>> = Topic::new("/sensor/lidar/cloud");
171
172    /// Odometry stream
173    pub const ODOMETRY: Topic<Odometry> = Topic::new("/sensor/odometry");
174
175    /// Wheel odometry (before sensor fusion)
176    pub const WHEEL_ODOM: Topic<Odometry> = Topic::new("/sensor/wheel_odom");
177
178    /// Visual odometry
179    pub const VISUAL_ODOM: Topic<Odometry> = Topic::new("/sensor/visual_odom");
180
181    /// IMU data stream
182    pub const IMU: Topic<Imu> = Topic::new("/sensor/imu");
183
184    /// IMU raw (uncalibrated)
185    pub const IMU_RAW: Topic<Imu> = Topic::new("/sensor/imu/raw");
186
187    /// GPS data stream
188    pub const GPS: Topic<GpsData> = Topic::new("/sensor/gps");
189
190    /// Joint states (for manipulators)
191    pub const JOINT_STATES: Topic<JointState> = Topic::new("/sensor/joint_states");
192
193    /// Battery voltage
194    pub const BATTERY_VOLTAGE: Topic<f32> = Topic::new("/sensor/battery/voltage");
195
196    /// Battery percentage
197    pub const BATTERY_PERCENT: Topic<f32> = Topic::new("/sensor/battery/percent");
198
199    /// Temperature sensors
200    pub const TEMPERATURE: Topic<f32> = Topic::new("/sensor/temperature");
201
202    /// Ultrasonic range sensors
203    pub const ULTRASONIC: Topic<Vec<f32>> = Topic::new("/sensor/ultrasonic");
204
205    /// Bumper/contact sensors
206    pub const CONTACT: Topic<Vec<bool>> = Topic::new("/sensor/contact");
207
208    /// Force/torque sensor
209    pub const FORCE_TORQUE: Topic<[f32; 6]> = Topic::new("/sensor/force_torque");
210}
211
212/// Actuator topics
213pub mod actuator {
214    use super::*;
215    use crate::messages::{GripperCommand, JointState, Twist};
216
217    /// Velocity command
218    pub const CMD_VEL: Topic<Twist> = Topic::new("/actuator/cmd_vel");
219
220    /// Raw velocity command (bypasses safety checks)
221    pub const CMD_VEL_RAW: Topic<Twist> = Topic::new("/actuator/cmd_vel/raw");
222
223    /// Velocity command from teleop
224    pub const CMD_VEL_TELEOP: Topic<Twist> = Topic::new("/actuator/cmd_vel/teleop");
225
226    /// Velocity command from autonomous nav
227    pub const CMD_VEL_NAV: Topic<Twist> = Topic::new("/actuator/cmd_vel/nav");
228
229    /// Joint state command
230    pub const JOINT_CMD: Topic<JointState> = Topic::new("/actuator/joint_cmd");
231
232    /// Joint trajectory (sequence of joint states)
233    pub const JOINT_TRAJECTORY: Topic<Vec<JointState>> = Topic::new("/actuator/joint_trajectory");
234
235    /// Gripper command
236    pub const GRIPPER_CMD: Topic<GripperCommand> = Topic::new("/actuator/gripper_cmd");
237
238    /// Individual motor commands (PWM values)
239    pub const MOTOR_CMD: Topic<Vec<f32>> = Topic::new("/actuator/motor_cmd");
240
241    /// LED/Light commands
242    pub const LIGHTS: Topic<Vec<u8>> = Topic::new("/actuator/lights");
243
244    /// Speaker/Sound commands
245    pub const SOUND: Topic<String> = Topic::new("/actuator/sound");
246
247    /// Emergency stop
248    pub const EMERGENCY_STOP: Topic<bool> = Topic::new("/actuator/emergency_stop");
249
250    /// Enable/disable motors
251    pub const ENABLE: Topic<bool> = Topic::new("/actuator/enable");
252}
253
254/// Manipulation topics (for robot arms)
255pub mod manipulation {
256    use super::*;
257    use crate::messages::{GripperCommand, JointState, Pose};
258
259    /// End-effector pose target
260    pub const EE_POSE_TARGET: Topic<Pose> = Topic::new("/manipulation/ee_pose_target");
261
262    /// End-effector pose current
263    pub const EE_POSE: Topic<Pose> = Topic::new("/manipulation/ee_pose");
264
265    /// Cartesian path (list of poses)
266    pub const CARTESIAN_PATH: Topic<Vec<Pose>> = Topic::new("/manipulation/cartesian_path");
267
268    /// Joint trajectory for execution
269    pub const TRAJECTORY: Topic<Vec<JointState>> = Topic::new("/manipulation/trajectory");
270
271    /// Gripper command
272    pub const GRIPPER: Topic<GripperCommand> = Topic::new("/manipulation/gripper");
273
274    /// Grasp pose candidates
275    pub const GRASP_POSES: Topic<Vec<Pose>> = Topic::new("/manipulation/grasp_poses");
276
277    /// Selected grasp pose
278    pub const SELECTED_GRASP: Topic<Pose> = Topic::new("/manipulation/selected_grasp");
279
280    /// Manipulation status
281    pub const STATUS: Topic<String> = Topic::new("/manipulation/status");
282}
283
284/// Perception topics
285pub mod perception {
286    use super::*;
287    use crate::messages::{Detection, Image, Pose};
288
289    /// Object detections (all)
290    pub const DETECTIONS: Topic<Vec<Detection>> = Topic::new("/perception/detections");
291
292    /// High-confidence detections only
293    pub const HIGH_CONFIDENCE: Topic<Vec<Detection>> = Topic::new("/perception/detections/high_confidence");
294
295    /// Detections by class
296    pub const PEOPLE: Topic<Vec<Detection>> = Topic::new("/perception/detections/people");
297    pub const OBJECTS: Topic<Vec<Detection>> = Topic::new("/perception/detections/objects");
298    pub const OBSTACLES: Topic<Vec<Detection>> = Topic::new("/perception/detections/obstacles");
299
300    /// Tracked objects
301    pub const TRACKING: Topic<Vec<Detection>> = Topic::new("/perception/tracking");
302
303    /// Estimated robot pose (from SLAM)
304    pub const POSE: Topic<Pose> = Topic::new("/perception/pose");
305
306    /// Localization confidence
307    pub const LOCALIZATION_QUALITY: Topic<f32> = Topic::new("/perception/localization/quality");
308
309    /// Semantic segmentation
310    pub const SEGMENTATION: Topic<Image> = Topic::new("/perception/segmentation");
311
312    /// Depth estimation
313    pub const DEPTH_ESTIMATION: Topic<Image> = Topic::new("/perception/depth");
314
315    /// Optical flow
316    pub const OPTICAL_FLOW: Topic<Vec<[f32; 2]>> = Topic::new("/perception/optical_flow");
317
318    /// Feature points
319    pub const FEATURES: Topic<Vec<[f32; 2]>> = Topic::new("/perception/features");
320
321    /// Scene understanding (room, corridor, etc.)
322    pub const SCENE_TYPE: Topic<String> = Topic::new("/perception/scene_type");
323}
324
325/// Navigation topics
326pub mod navigation {
327    use super::*;
328    use crate::messages::{NavigationGoal, NavigationStatus, Path, Pose, Twist};
329
330    /// Navigation goal (target pose)
331    pub const GOAL: Topic<NavigationGoal> = Topic::new("/navigation/goal");
332
333    /// Cancel current goal
334    pub const CANCEL: Topic<bool> = Topic::new("/navigation/cancel");
335
336    /// Navigation status
337    pub const STATUS: Topic<NavigationStatus> = Topic::new("/navigation/status");
338
339    /// Planned global path
340    pub const GLOBAL_PATH: Topic<Path> = Topic::new("/navigation/global_path");
341
342    /// Local planner path
343    pub const LOCAL_PATH: Topic<Path> = Topic::new("/navigation/local_path");
344
345    /// Current waypoint being tracked
346    pub const CURRENT_WAYPOINT: Topic<crate::messages::Waypoint> = Topic::new("/navigation/waypoint");
347
348    /// Next waypoint in sequence
349    pub const NEXT_WAYPOINT: Topic<crate::messages::Waypoint> = Topic::new("/navigation/next_waypoint");
350
351    /// Costmap (global)
352    pub const GLOBAL_COSTMAP: Topic<Vec<Vec<u8>>> = Topic::new("/navigation/costmap/global");
353
354    /// Costmap (local)
355    pub const LOCAL_COSTMAP: Topic<Vec<Vec<u8>>> = Topic::new("/navigation/costmap/local");
356
357    /// Recovery behaviors trigger
358    pub const RECOVERY: Topic<String> = Topic::new("/navigation/recovery");
359
360    /// Dynamic obstacles
361    pub const DYNAMIC_OBSTACLES: Topic<Vec<Pose>> = Topic::new("/navigation/obstacles/dynamic");
362
363    /// Static obstacles
364    pub const STATIC_OBSTACLES: Topic<Vec<Pose>> = Topic::new("/navigation/obstacles/static");
365
366    /// Velocity limits (dynamic)
367    pub const VELOCITY_LIMITS: Topic<Twist> = Topic::new("/navigation/velocity_limits");
368}
369
370/// Mapping topics (SLAM)
371pub mod mapping {
372    use super::*;
373    use crate::messages::Pose;
374
375    /// Occupancy grid map
376    pub const OCCUPANCY_GRID: Topic<Vec<Vec<u8>>> = Topic::new("/mapping/occupancy_grid");
377
378    /// Map metadata (resolution, origin, etc.)
379    pub const MAP_METADATA: Topic<String> = Topic::new("/mapping/metadata");
380
381    /// Loop closure detections
382    pub const LOOP_CLOSURES: Topic<Vec<(Pose, Pose)>> = Topic::new("/mapping/loop_closures");
383
384    /// Map updates (incremental)
385    pub const MAP_UPDATE: Topic<Vec<(usize, usize, u8)>> = Topic::new("/mapping/update");
386
387    /// Save map command
388    pub const SAVE_MAP: Topic<String> = Topic::new("/mapping/save");
389
390    /// Load map command
391    pub const LOAD_MAP: Topic<String> = Topic::new("/mapping/load");
392
393    /// Mapping status
394    pub const STATUS: Topic<String> = Topic::new("/mapping/status");
395}
396
397/// System topics
398pub mod system {
399    use super::*;
400    use crate::messages::{HealthStatus, NodeStatus, SystemCommand};
401
402    /// Health status updates
403    pub const HEALTH: Topic<HealthStatus> = Topic::new("/system/health");
404
405    /// Node status updates
406    pub const NODE_STATUS: Topic<NodeStatus> = Topic::new("/system/node_status");
407
408    /// System commands (start, stop, restart, etc.)
409    pub const COMMAND: Topic<SystemCommand> = Topic::new("/system/command");
410
411    /// Heartbeat (timestamp in microseconds)
412    pub const HEARTBEAT: Topic<u64> = Topic::new("/system/heartbeat");
413
414    /// Diagnostics aggregated
415    pub const DIAGNOSTICS: Topic<String> = Topic::new("/system/diagnostics");
416
417    /// Warnings
418    pub const WARNINGS: Topic<Vec<String>> = Topic::new("/system/warnings");
419
420    /// Errors
421    pub const ERRORS: Topic<Vec<String>> = Topic::new("/system/errors");
422
423    /// CPU usage percentage
424    pub const CPU_USAGE: Topic<f32> = Topic::new("/system/cpu_usage");
425
426    /// Memory usage percentage
427    pub const MEMORY_USAGE: Topic<f32> = Topic::new("/system/memory_usage");
428
429    /// Disk usage percentage
430    pub const DISK_USAGE: Topic<f32> = Topic::new("/system/disk_usage");
431
432    /// Network statistics
433    pub const NETWORK_STATS: Topic<(f32, f32)> = Topic::new("/system/network_stats"); // (tx, rx in KB/s)
434
435    /// Temperature (CPU/GPU)
436    pub const SYSTEM_TEMP: Topic<f32> = Topic::new("/system/temperature");
437
438    /// Power consumption (watts)
439    pub const POWER: Topic<f32> = Topic::new("/system/power");
440
441    /// Uptime (seconds)
442    pub const UPTIME: Topic<u64> = Topic::new("/system/uptime");
443
444    /// Log messages
445    pub const LOG: Topic<String> = Topic::new("/system/log");
446
447    /// Configuration updates
448    pub const CONFIG_UPDATE: Topic<String> = Topic::new("/system/config_update");
449
450    /// Shutdown request
451    pub const SHUTDOWN: Topic<bool> = Topic::new("/system/shutdown");
452
453    /// Reboot request
454    pub const REBOOT: Topic<bool> = Topic::new("/system/reboot");
455}
456
457/// Teleoperation topics
458pub mod teleop {
459    use super::*;
460    use crate::messages::Twist;
461
462    /// Joystick/gamepad input
463    pub const JOYSTICK: Topic<Vec<f32>> = Topic::new("/teleop/joystick");
464
465    /// Button states
466    pub const BUTTONS: Topic<Vec<bool>> = Topic::new("/teleop/buttons");
467
468    /// Velocity command from teleop
469    pub const CMD_VEL: Topic<Twist> = Topic::new("/teleop/cmd_vel");
470
471    /// Enable/disable teleop
472    pub const ENABLE: Topic<bool> = Topic::new("/teleop/enable");
473
474    /// Teleop mode (normal, turbo, slow, etc.)
475    pub const MODE: Topic<String> = Topic::new("/teleop/mode");
476}
477
478/// AI/ML model topics
479pub mod ml {
480    use super::*;
481    use crate::messages::Detection;
482
483    /// Model inference request
484    pub const INFERENCE_REQUEST: Topic<Vec<u8>> = Topic::new("/ml/inference/request");
485
486    /// Model inference result
487    pub const INFERENCE_RESULT: Topic<Vec<f32>> = Topic::new("/ml/inference/result");
488
489    /// Model predictions
490    pub const PREDICTIONS: Topic<Vec<Detection>> = Topic::new("/ml/predictions");
491
492    /// Model performance metrics
493    pub const METRICS: Topic<String> = Topic::new("/ml/metrics");
494
495    /// Model loading command
496    pub const LOAD_MODEL: Topic<String> = Topic::new("/ml/load_model");
497
498    /// Current model info
499    pub const MODEL_INFO: Topic<String> = Topic::new("/ml/model_info");
500
501    /// Training data collection
502    pub const TRAINING_DATA: Topic<Vec<u8>> = Topic::new("/ml/training_data");
503}
504
505// ============================================================================
506// Topic Groups
507// ============================================================================
508
509/// Macro to define topic groups
510///
511/// # Example
512/// ```rust
513/// topic_group! {
514///     pub struct AllSensors {
515///         camera: sensor::CAMERA_RGB,
516///         lidar: sensor::LIDAR_SCAN,
517///         imu: sensor::IMU,
518///     }
519/// }
520/// ```
521#[macro_export]
522macro_rules! topic_group {
523    (
524        $(#[$meta:meta])*
525        $vis:vis struct $name:ident {
526            $(
527                $field:ident: $topic:expr
528            ),* $(,)?
529        }
530    ) => {
531        $(#[$meta])*
532        $vis struct $name;
533
534        impl $name {
535            /// Get all topics in this group
536            pub fn topics() -> Vec<&'static str> {
537                vec![
538                    $( $topic.path() ),*
539                ]
540            }
541        }
542    };
543}
544
545// Example topic groups
546topic_group! {
547    /// All sensor topics
548    pub struct AllSensors {
549        camera_rgb: sensor::CAMERA_RGB,
550        camera_depth: sensor::CAMERA_DEPTH,
551        lidar: sensor::LIDAR_SCAN,
552        odometry: sensor::ODOMETRY,
553        imu: sensor::IMU,
554        gps: sensor::GPS,
555    }
556}
557
558topic_group! {
559    /// All actuator topics
560    pub struct AllActuators {
561        cmd_vel: actuator::CMD_VEL,
562        joint_cmd: actuator::JOINT_CMD,
563        gripper: actuator::GRIPPER_CMD,
564    }
565}
566
567// ============================================================================
568// Builder Pattern for Subscribe Options
569// ============================================================================
570
571/// Builder for subscription options
572///
573/// Enables fluent API for configuring subscriptions:
574///
575/// ```rust
576/// let mut images = ctx.subscribe(sensor::CAMERA_RGB)
577///     .buffer(10)
578///     .filter(|img| img.width >= 640)
579///     .throttle(Duration::from_millis(100))
580///     .await?;
581/// ```
582pub struct SubscribeBuilder<T: Message> {
583    #[allow(dead_code)]
584    topic: Topic<T>,
585    #[allow(dead_code)]
586    buffer_size: Option<usize>,
587    #[allow(dead_code)]
588    latest_only: bool,
589    #[allow(dead_code)]
590    throttle_ms: Option<u64>,
591}
592
593impl<T: Message> SubscribeBuilder<T> {
594    pub fn new(topic: Topic<T>) -> Self {
595        Self {
596            topic,
597            buffer_size: None,
598            latest_only: false,
599            throttle_ms: None,
600        }
601    }
602
603    /// Set buffer size (default: unbounded)
604    pub fn buffer(mut self, size: usize) -> Self {
605        self.buffer_size = Some(size);
606        self
607    }
608
609    /// Only keep latest message, drop old ones
610    pub fn latest(mut self) -> Self {
611        self.latest_only = true;
612        self.buffer_size = Some(1);
613        self
614    }
615
616    /// Throttle messages to max rate
617    pub fn throttle(mut self, duration: std::time::Duration) -> Self {
618        self.throttle_ms = Some(duration.as_millis() as u64);
619        self
620    }
621
622    // Build method would be implemented in Context
623}
624
625/// Builder for publish options
626///
627/// ```rust
628/// ctx.publish_to(perception::DETECTIONS, &detections)
629///     .when(|d| !d.is_empty())
630///     .throttle(Duration::from_secs(1))
631///     .await?;
632/// ```
633pub struct PublishBuilder<'a, T: Message> {
634    #[allow(dead_code)]
635    topic: Topic<T>,
636    #[allow(dead_code)]
637    message: &'a T,
638    #[allow(dead_code)]
639    #[allow(clippy::type_complexity)]
640    condition: Option<Box<dyn Fn(&T) -> bool>>,
641    #[allow(dead_code)]
642    throttle_ms: Option<u64>,
643}
644
645impl<'a, T: Message> PublishBuilder<'a, T> {
646    pub fn new(topic: Topic<T>, message: &'a T) -> Self {
647        Self {
648            topic,
649            message,
650            condition: None,
651            throttle_ms: None,
652        }
653    }
654
655    /// Only publish if condition is true
656    pub fn when<F>(mut self, condition: F) -> Self
657    where
658        F: Fn(&T) -> bool + 'static,
659    {
660        self.condition = Some(Box::new(condition));
661        self
662    }
663
664    /// Throttle publishing to max rate
665    pub fn throttle(mut self, duration: std::time::Duration) -> Self {
666        self.throttle_ms = Some(duration.as_millis() as u64);
667        self
668    }
669
670    // Build method would be implemented in Context
671}
672
673// ============================================================================
674// Tests
675// ============================================================================