gloamy-robot 0.1.0

Standalone robot crate for Gloamy with drive, sensing, speech, vision, and safety helpers.
Documentation
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
//! Movement tool implementations.
//!
//! The current crate supports three concrete execution paths:
//!
//! - `mock`: log movement commands without touching hardware
//! - `serial`: write text commands to a motor-controller serial port
//! - `ros2`: shell out to the `ros2` CLI and publish `geometry_msgs/Twist`
//!
//! Direct GPIO drive control is intentionally left explicit and is not wired in
//! yet, even though the configuration surface reserves room for it.

use crate::config::RobotConfig;
use crate::traits::{Tool, ToolResult};
use anyhow::Result;
use async_trait::async_trait;
use serde_json::{json, Value};
use std::sync::Arc;
use std::time::Duration;
use tokio::sync::Mutex;

/// Drive backend abstraction
#[async_trait]
trait DriveBackend: Send + Sync {
    async fn move_robot(
        &self,
        linear_x: f64,
        linear_y: f64,
        angular_z: f64,
        duration_ms: u64,
    ) -> Result<()>;
    async fn stop(&self) -> Result<()>;
    #[allow(dead_code)]
    async fn get_odometry(&self) -> Result<(f64, f64, f64)>; // x, y, theta - reserved for future odometry integration
}

/// Mock backend for testing
struct MockDrive;

#[async_trait]
impl DriveBackend for MockDrive {
    async fn move_robot(
        &self,
        linear_x: f64,
        linear_y: f64,
        angular_z: f64,
        duration_ms: u64,
    ) -> Result<()> {
        tracing::info!(
            "MOCK DRIVE: linear=({:.2}, {:.2}), angular={:.2}, duration={}ms",
            linear_x,
            linear_y,
            angular_z,
            duration_ms
        );
        tokio::time::sleep(Duration::from_millis(duration_ms.min(100))).await;
        Ok(())
    }

    async fn stop(&self) -> Result<()> {
        tracing::info!("MOCK DRIVE: STOP");
        Ok(())
    }

    async fn get_odometry(&self) -> Result<(f64, f64, f64)> {
        Ok((0.0, 0.0, 0.0))
    }
}

/// ROS2 backend - shells out to ros2 topic pub
struct Ros2Drive {
    topic: String,
}

#[async_trait]
impl DriveBackend for Ros2Drive {
    async fn move_robot(
        &self,
        linear_x: f64,
        linear_y: f64,
        angular_z: f64,
        duration_ms: u64,
    ) -> Result<()> {
        // Publish Twist message via ros2 CLI
        // In production, use rclrs (Rust ROS2 bindings) instead
        let msg = format!(
            "{{linear: {{x: {:.2}, y: {:.2}, z: 0.0}}, angular: {{x: 0.0, y: 0.0, z: {:.2}}}}}",
            linear_x, linear_y, angular_z
        );

        let output = tokio::process::Command::new("ros2")
            .args([
                "topic",
                "pub",
                "--once",
                &self.topic,
                "geometry_msgs/msg/Twist",
                &msg,
            ])
            .output()
            .await?;

        if !output.status.success() {
            anyhow::bail!(
                "ROS2 publish failed: {}",
                String::from_utf8_lossy(&output.stderr)
            );
        }

        // Hold for duration then stop
        tokio::time::sleep(Duration::from_millis(duration_ms)).await;
        self.stop().await?;

        Ok(())
    }

    async fn stop(&self) -> Result<()> {
        let msg = "{linear: {x: 0.0, y: 0.0, z: 0.0}, angular: {x: 0.0, y: 0.0, z: 0.0}}";
        tokio::process::Command::new("ros2")
            .args([
                "topic",
                "pub",
                "--once",
                &self.topic,
                "geometry_msgs/msg/Twist",
                msg,
            ])
            .output()
            .await?;
        Ok(())
    }

    async fn get_odometry(&self) -> Result<(f64, f64, f64)> {
        // Would subscribe to /odom topic in production
        Ok((0.0, 0.0, 0.0))
    }
}

/// Serial backend - sends commands to Arduino/motor controller
struct SerialDrive {
    port: String,
}

#[async_trait]
impl DriveBackend for SerialDrive {
    async fn move_robot(
        &self,
        linear_x: f64,
        linear_y: f64,
        angular_z: f64,
        duration_ms: u64,
    ) -> Result<()> {
        // Protocol: "M <lx> <ly> <az> <ms>\n"
        // The motor controller interprets this and drives motors
        let cmd = format!(
            "M {:.2} {:.2} {:.2} {}\n",
            linear_x, linear_y, angular_z, duration_ms
        );

        // Use blocking serial in spawn_blocking
        let port = self.port.clone();
        tokio::task::spawn_blocking(move || {
            use std::io::Write;
            let mut serial = std::fs::OpenOptions::new().write(true).open(&port)?;
            serial.write_all(cmd.as_bytes())?;
            serial.flush()?;
            Ok::<_, anyhow::Error>(())
        })
        .await??;

        tokio::time::sleep(Duration::from_millis(duration_ms)).await;
        Ok(())
    }

    async fn stop(&self) -> Result<()> {
        self.move_robot(0.0, 0.0, 0.0, 0).await
    }

    async fn get_odometry(&self) -> Result<(f64, f64, f64)> {
        Ok((0.0, 0.0, 0.0))
    }
}

/// Tool that exposes base movement commands.
pub struct DriveTool {
    config: RobotConfig,
    backend: Arc<dyn DriveBackend>,
    last_command: Arc<Mutex<Option<std::time::Instant>>>,
}

impl DriveTool {
    pub fn new(config: RobotConfig) -> Self {
        let backend: Arc<dyn DriveBackend> = match config.drive.backend.as_str() {
            "ros2" => Arc::new(Ros2Drive {
                topic: config.drive.ros2_topic.clone(),
            }),
            "serial" => Arc::new(SerialDrive {
                port: config.drive.serial_port.clone(),
            }),
            // "gpio" => Arc::new(GpioDrive::new(&config)), // Would use rppal
            _ => Arc::new(MockDrive),
        };

        Self {
            config,
            backend,
            last_command: Arc::new(Mutex::new(None)),
        }
    }
}

#[async_trait]
impl Tool for DriveTool {
    fn name(&self) -> &str {
        "drive"
    }

    fn description(&self) -> &str {
        "Move the robot. Supports omni-directional movement (forward, backward, strafe left/right, rotate). \
         Use 'stop' action to halt immediately. Distance is in meters, rotation in degrees."
    }

    fn parameters_schema(&self) -> Value {
        json!({
            "type": "object",
            "properties": {
                "action": {
                    "type": "string",
                    "enum": ["forward", "backward", "left", "right", "rotate_left", "rotate_right", "stop", "custom"],
                    "description": "Movement action. 'left'/'right' are strafe (omni wheels). 'rotate_*' spins in place."
                },
                "distance": {
                    "type": "number",
                    "description": "Distance in meters (for linear moves) or degrees (for rotation). Default 0.5m or 90deg."
                },
                "speed": {
                    "type": "number",
                    "description": "Speed multiplier 0.0-1.0. Default 0.5 (half speed for safety)."
                },
                "linear_x": {
                    "type": "number",
                    "description": "Custom: forward/backward velocity (-1.0 to 1.0)"
                },
                "linear_y": {
                    "type": "number",
                    "description": "Custom: left/right strafe velocity (-1.0 to 1.0)"
                },
                "angular_z": {
                    "type": "number",
                    "description": "Custom: rotation velocity (-1.0 to 1.0)"
                },
                "duration_ms": {
                    "type": "integer",
                    "description": "Custom only: how long to apply the custom velocity command."
                }
            },
            "required": ["action"]
        })
    }

    async fn execute(&self, args: Value) -> Result<ToolResult> {
        let action = args["action"]
            .as_str()
            .ok_or_else(|| anyhow::anyhow!("Missing 'action' parameter"))?;

        // Safety: check max drive duration
        {
            let mut last = self.last_command.lock().await;
            if let Some(instant) = *last {
                if instant.elapsed() < Duration::from_secs(1) {
                    return Ok(ToolResult {
                        success: false,
                        output: String::new(),
                        error: Some(
                            "Rate limited: wait 1 second between drive commands".to_string(),
                        ),
                    });
                }
            }
            *last = Some(std::time::Instant::now());
        }

        let speed = args["speed"].as_f64().unwrap_or(0.5).clamp(0.0, 1.0);
        let max_speed = self.config.drive.max_speed * speed;
        let max_rotation = self.config.drive.max_rotation * speed;

        let (linear_x, linear_y, angular_z, duration_ms) = match action {
            "stop" => {
                self.backend.stop().await?;
                return Ok(ToolResult {
                    success: true,
                    output: "Robot stopped".to_string(),
                    error: None,
                });
            }
            "forward" => {
                let dist = args["distance"].as_f64().unwrap_or(0.5);
                let duration = (dist / max_speed * 1000.0) as u64;
                (
                    max_speed,
                    0.0,
                    0.0,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            "backward" => {
                let dist = args["distance"].as_f64().unwrap_or(0.5);
                let duration = (dist / max_speed * 1000.0) as u64;
                (
                    -max_speed,
                    0.0,
                    0.0,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            "left" => {
                let dist = args["distance"].as_f64().unwrap_or(0.5);
                let duration = (dist / max_speed * 1000.0) as u64;
                (
                    0.0,
                    max_speed,
                    0.0,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            "right" => {
                let dist = args["distance"].as_f64().unwrap_or(0.5);
                let duration = (dist / max_speed * 1000.0) as u64;
                (
                    0.0,
                    -max_speed,
                    0.0,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            "rotate_left" => {
                let degrees = args["distance"].as_f64().unwrap_or(90.0);
                let radians = degrees.to_radians();
                let duration = (radians / max_rotation * 1000.0) as u64;
                (
                    0.0,
                    0.0,
                    max_rotation,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            "rotate_right" => {
                let degrees = args["distance"].as_f64().unwrap_or(90.0);
                let radians = degrees.to_radians();
                let duration = (radians / max_rotation * 1000.0) as u64;
                (
                    0.0,
                    0.0,
                    -max_rotation,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            "custom" => {
                let lx = args["linear_x"].as_f64().unwrap_or(0.0).clamp(-1.0, 1.0) * max_speed;
                let ly = args["linear_y"].as_f64().unwrap_or(0.0).clamp(-1.0, 1.0) * max_speed;
                let az = args["angular_z"].as_f64().unwrap_or(0.0).clamp(-1.0, 1.0) * max_rotation;
                let duration = args["duration_ms"].as_u64().unwrap_or(1000);
                (
                    lx,
                    ly,
                    az,
                    duration.min(self.config.safety.max_drive_duration * 1000),
                )
            }
            _ => {
                return Ok(ToolResult {
                    success: false,
                    output: String::new(),
                    error: Some(format!("Unknown action: {action}")),
                });
            }
        };

        self.backend
            .move_robot(linear_x, linear_y, angular_z, duration_ms)
            .await?;

        Ok(ToolResult {
            success: true,
            output: format!(
                "Moved: action={}, linear=({:.2}, {:.2}), angular={:.2}, duration={}ms",
                action, linear_x, linear_y, angular_z, duration_ms
            ),
            error: None,
        })
    }
}

#[cfg(test)]
mod tests {
    use super::*;

    #[test]
    fn drive_tool_name() {
        let tool = DriveTool::new(RobotConfig::default());
        assert_eq!(tool.name(), "drive");
    }

    #[test]
    fn drive_tool_schema_has_action() {
        let tool = DriveTool::new(RobotConfig::default());
        let schema = tool.parameters_schema();
        assert!(schema["properties"]["action"].is_object());
    }

    #[tokio::test]
    async fn drive_forward_mock() {
        let tool = DriveTool::new(RobotConfig::default());
        let result = tool
            .execute(json!({"action": "forward", "distance": 1.0}))
            .await
            .unwrap();
        assert!(result.success);
        assert!(result.output.contains("forward"));
    }

    #[tokio::test]
    async fn drive_stop() {
        let tool = DriveTool::new(RobotConfig::default());
        let result = tool.execute(json!({"action": "stop"})).await.unwrap();
        assert!(result.success);
        assert!(result.output.contains("stopped"));
    }

    #[tokio::test]
    async fn drive_unknown_action() {
        let tool = DriveTool::new(RobotConfig::default());
        let result = tool.execute(json!({"action": "fly"})).await.unwrap();
        assert!(!result.success);
    }
}