feat: Add Issue #467 - Power management supervisor with battery protection
Some checks failed
Some checks failed
- New ROS2 node: power_supervisor_node for battery state monitoring - Battery thresholds: 30% warning, 20% dock search, 10% graceful shutdown, 5% force kill - Charge cycle tracking and battery health estimation - CSV logging to battery_log.csv for external analysis - Publishes /saltybot/power_state for MQTT relay - Graceful shutdown cascade: save state, stop motors, disarm on critical low battery - Replaces/extends Issue #125 battery_node with supervisor-level power management Co-Authored-By: Claude Haiku 4.5 <noreply@anthropic.com>
This commit is contained in:
parent
6293d2ec60
commit
d7051fe854
308
.claude/plans/zany-hugging-oasis.md
Normal file
308
.claude/plans/zany-hugging-oasis.md
Normal file
@ -0,0 +1,308 @@
|
|||||||
|
# Issue #469: Terrain Classification Implementation Plan
|
||||||
|
|
||||||
|
## Context
|
||||||
|
|
||||||
|
SaltyBot currently has good sensor infrastructure (IMU, cameras, RealSense) and a robust velocity control system with the `VelocityRamp` class. However, it lacks terrain awareness for surface type detection and speed adaptation. This feature will enable:
|
||||||
|
|
||||||
|
1. **Surface detection** via IMU vibration analysis and camera texture analysis
|
||||||
|
2. **Automatic speed adaptation** based on terrain type and roughness
|
||||||
|
3. **Terrain logging** for mapping and future learning
|
||||||
|
4. **Improved robot safety** by reducing speed on rough/unstable terrain
|
||||||
|
|
||||||
|
## Architecture Overview
|
||||||
|
|
||||||
|
The implementation follows the existing ROS2 patterns:
|
||||||
|
|
||||||
|
```
|
||||||
|
IMU/Camera Data
|
||||||
|
↓
|
||||||
|
[terrain_classifier_node] ← New node
|
||||||
|
↓
|
||||||
|
/saltybot/terrain_state (TerrainState.msg)
|
||||||
|
↓
|
||||||
|
[terrain_speed_adapter_node] ← New node
|
||||||
|
↓
|
||||||
|
Adjusted /cmd_vel_terrain → existing cmd_vel_bridge
|
||||||
|
↓
|
||||||
|
Speed-adapted robot motion
|
||||||
|
|
||||||
|
Parallel: [terrain_mapper_node] logs data for mapping
|
||||||
|
```
|
||||||
|
|
||||||
|
## Implementation Components
|
||||||
|
|
||||||
|
### 1. **Message Definition: TerrainState.msg**
|
||||||
|
**File to create:** `jetson/ros2_ws/src/saltybot_social_msgs/msg/TerrainState.msg`
|
||||||
|
|
||||||
|
Fields:
|
||||||
|
- `std_msgs/Header header` — timestamp/frame_id
|
||||||
|
- `uint8 terrain_type` — enum (0=unknown, 1=pavement, 2=grass, 3=gravel, 4=sand, 5=indoor)
|
||||||
|
- `float32 roughness` — 0.0=smooth, 1.0=very rough
|
||||||
|
- `float32 confidence` — 0.0-1.0 classification confidence
|
||||||
|
- `float32 recommended_speed_ratio` — 0.1-1.0 (fraction of max speed)
|
||||||
|
- `string source` — "imu_vibration" or "camera_texture" or "fused"
|
||||||
|
|
||||||
|
**Update files:**
|
||||||
|
- `jetson/ros2_ws/src/saltybot_social_msgs/CMakeLists.txt` — add TerrainState.msg to rosidl_generate_interfaces()
|
||||||
|
- `jetson/ros2_ws/src/saltybot_social_msgs/package.xml` — no changes needed (std_msgs already a dependency)
|
||||||
|
|
||||||
|
### 2. **Terrain Classifier Node**
|
||||||
|
**File to create:** `jetson/ros2_ws/src/saltybot_bringup/saltybot_bringup/terrain_classifier_node.py`
|
||||||
|
|
||||||
|
**Purpose:** Analyze IMU and camera data to classify terrain type and estimate roughness.
|
||||||
|
|
||||||
|
**Subscribes to:**
|
||||||
|
- `/camera/imu` (sensor_msgs/Imu) — RealSense IMU at 200 Hz
|
||||||
|
- `/camera/color/image_raw` (sensor_msgs/Image) — camera RGB at 15 Hz
|
||||||
|
|
||||||
|
**Publishes:**
|
||||||
|
- `/saltybot/terrain_state` (TerrainState.msg) — at 5 Hz
|
||||||
|
|
||||||
|
**Key functions:**
|
||||||
|
- `_analyze_imu_vibration()` — FFT analysis on accel data (window: 200 samples = 1 sec)
|
||||||
|
- Compute power spectral density in 0-50 Hz band
|
||||||
|
- Extract features: peak frequency, energy distribution, RMS acceleration
|
||||||
|
- Roughness = normalized RMS of high-freq components (>10 Hz)
|
||||||
|
|
||||||
|
- `_analyze_camera_texture()` — CNN-based texture analysis
|
||||||
|
- Uses MobileNetV2 pre-trained on ImageNet as feature extractor
|
||||||
|
- Extracts high-level texture/surface features from camera image
|
||||||
|
- Lightweight model (~3.5M parameters, ~50-100ms inference on Jetson)
|
||||||
|
- Outputs feature vector fed to classification layer
|
||||||
|
|
||||||
|
- `_classify_terrain()` — decision logic
|
||||||
|
- Simple rule-based classifier (can be upgraded to CNN)
|
||||||
|
- Input: [imu_roughness, camera_texture_variance, accel_magnitude]
|
||||||
|
- Decision tree or thresholds to classify into 5 types
|
||||||
|
- Output: terrain_type, roughness, confidence
|
||||||
|
|
||||||
|
**Node Parameters:**
|
||||||
|
- `imu_window_size` (int, default 200) — samples for FFT window
|
||||||
|
- `publish_rate_hz` (float, default 5.0)
|
||||||
|
- `roughness_threshold` (float, default 0.3) — FFT roughness threshold
|
||||||
|
- `terrain_timeout_s` (float, default 5.0) — how long to keep previous estimate if no new data
|
||||||
|
|
||||||
|
### 3. **Speed Adapter Node**
|
||||||
|
**File to create:** `jetson/ros2_ws/src/saltybot_bringup/saltybot_bringup/terrain_speed_adapter_node.py`
|
||||||
|
|
||||||
|
**Purpose:** Adapt cmd_vel speed based on terrain state and integration with velocity ramp.
|
||||||
|
|
||||||
|
**Subscribes to:**
|
||||||
|
- `/cmd_vel` (geometry_msgs/Twist) — raw velocity commands
|
||||||
|
- `/saltybot/terrain_state` (TerrainState.msg) — terrain classification
|
||||||
|
|
||||||
|
**Publishes:**
|
||||||
|
- `/cmd_vel_terrain` (geometry_msgs/Twist) — terrain-adapted velocity
|
||||||
|
|
||||||
|
**Logic:**
|
||||||
|
- Extract target linear velocity from cmd_vel
|
||||||
|
- Apply terrain speed ratio: `adapted_speed = target_speed × recommended_speed_ratio`
|
||||||
|
- Preserve angular velocity (steering not affected by terrain)
|
||||||
|
- Publish adapted command
|
||||||
|
|
||||||
|
**Node Parameters:**
|
||||||
|
- `enable_terrain_adaptation` (bool, default true)
|
||||||
|
- `min_speed_ratio` (float, default 0.1) — never go below 10% of requested speed
|
||||||
|
- `debug_logging` (bool, default false)
|
||||||
|
|
||||||
|
**Note:** This is a lightweight adapter. The existing `velocity_ramp_node` handles acceleration/deceleration smoothing independently.
|
||||||
|
|
||||||
|
### 4. **Terrain Mapper Node** (Logging/Mapping)
|
||||||
|
**File to create:** `jetson/ros2_ws/src/saltybot_bringup/saltybot_bringup/terrain_mapper_node.py`
|
||||||
|
|
||||||
|
**Purpose:** Log terrain detections with robot pose for future mapping.
|
||||||
|
|
||||||
|
**Subscribes to:**
|
||||||
|
- `/saltybot/terrain_state` (TerrainState.msg)
|
||||||
|
- `/odom` (nav_msgs/Odometry) — robot pose
|
||||||
|
|
||||||
|
**Publishes:**
|
||||||
|
- `/saltybot/terrain_log` (std_msgs/String) — CSV formatted log messages (optional, mainly for logging)
|
||||||
|
|
||||||
|
**Logic:**
|
||||||
|
- Store terrain observations: (timestamp, pose_x, pose_y, terrain_type, roughness, confidence)
|
||||||
|
- Log to file: `~/.ros/terrain_map_<timestamp>.csv`
|
||||||
|
- Resample to 1 Hz to avoid spam
|
||||||
|
|
||||||
|
**Node Parameters:**
|
||||||
|
- `log_dir` (string, default "~/.ros/")
|
||||||
|
- `resample_rate_hz` (float, default 1.0)
|
||||||
|
|
||||||
|
### 5. **Launch Configuration**
|
||||||
|
**File to update:** `jetson/ros2_ws/src/saltybot_bringup/launch/full_stack.launch.py`
|
||||||
|
|
||||||
|
Add terrain nodes:
|
||||||
|
```python
|
||||||
|
terrain_classifier_node = Node(
|
||||||
|
package='saltybot_bringup',
|
||||||
|
executable='terrain_classifier',
|
||||||
|
name='terrain_classifier',
|
||||||
|
parameters=[{
|
||||||
|
'imu_window_size': 200,
|
||||||
|
'publish_rate_hz': 5.0,
|
||||||
|
}],
|
||||||
|
remappings=[
|
||||||
|
('/imu_in', '/camera/imu'),
|
||||||
|
('/camera_in', '/camera/color/image_raw'),
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
terrain_speed_adapter_node = Node(
|
||||||
|
package='saltybot_bringup',
|
||||||
|
executable='terrain_speed_adapter',
|
||||||
|
name='terrain_speed_adapter',
|
||||||
|
parameters=[{
|
||||||
|
'enable_terrain_adaptation': True,
|
||||||
|
'min_speed_ratio': 0.1,
|
||||||
|
}],
|
||||||
|
remappings=[
|
||||||
|
('/cmd_vel_in', '/cmd_vel'),
|
||||||
|
('/cmd_vel_out', '/cmd_vel_terrain'),
|
||||||
|
],
|
||||||
|
)
|
||||||
|
|
||||||
|
terrain_mapper_node = Node(
|
||||||
|
package='saltybot_bringup',
|
||||||
|
executable='terrain_mapper',
|
||||||
|
name='terrain_mapper',
|
||||||
|
)
|
||||||
|
```
|
||||||
|
|
||||||
|
**Update setup.py entry points:**
|
||||||
|
```python
|
||||||
|
'terrain_classifier = saltybot_bringup.terrain_classifier_node:main'
|
||||||
|
'terrain_speed_adapter = saltybot_bringup.terrain_speed_adapter_node:main'
|
||||||
|
'terrain_mapper = saltybot_bringup.terrain_mapper_node:main'
|
||||||
|
```
|
||||||
|
|
||||||
|
### 6. **Integration with Existing Stack**
|
||||||
|
- The existing velocity ramp (`velocity_ramp_node.py`) processes `/cmd_vel_smooth` or `/cmd_vel`
|
||||||
|
- Optionally, update cmd_vel_bridge to use `/cmd_vel_terrain` if available, else fall back to `/cmd_vel`
|
||||||
|
- Terrain classification runs independently at 5 Hz (much slower than velocity ramping at 50 Hz)
|
||||||
|
|
||||||
|
### 7. **Future CNN Enhancement**
|
||||||
|
The current implementation uses rule-based classification with IMU FFT and camera edge detection. A future enhancement could add a lightweight CNN for texture classification (e.g., MobileNet) by:
|
||||||
|
1. Creating a `terrain_classifier_cnn.py` with TensorFlow/ONNX model
|
||||||
|
2. Replacing decision logic in `terrain_classifier_node.py` with CNN inference
|
||||||
|
3. Maintaining same message interface
|
||||||
|
|
||||||
|
## Implementation Tasks
|
||||||
|
|
||||||
|
1. ✅ **Phase 1: Message Definition**
|
||||||
|
- Create `TerrainState.msg` in saltybot_social_msgs
|
||||||
|
- Update `CMakeLists.txt`
|
||||||
|
|
||||||
|
2. ✅ **Phase 2: Terrain Classifier Node**
|
||||||
|
- Implement `terrain_classifier_node.py` with IMU FFT analysis
|
||||||
|
- Implement camera texture analysis
|
||||||
|
- Decision logic for classification
|
||||||
|
|
||||||
|
3. ✅ **Phase 3: Speed Adapter Node**
|
||||||
|
- Implement `terrain_speed_adapter_node.py`
|
||||||
|
- Velocity command adaptation
|
||||||
|
|
||||||
|
4. ✅ **Phase 4: Terrain Mapper Node**
|
||||||
|
- Implement `terrain_mapper_node.py` for logging
|
||||||
|
|
||||||
|
5. ✅ **Phase 5: Integration**
|
||||||
|
- Update `full_stack.launch.py` with new nodes
|
||||||
|
- Update `setup.py` with entry points
|
||||||
|
- Test integration
|
||||||
|
|
||||||
|
## Testing & Verification
|
||||||
|
|
||||||
|
**Unit Tests:**
|
||||||
|
- Test IMU FFT feature extraction with synthetic vibration data
|
||||||
|
- Test terrain classification decision logic
|
||||||
|
- Test speed ratio application
|
||||||
|
- Test CSV logging format
|
||||||
|
|
||||||
|
**Integration Tests:**
|
||||||
|
- Run full stack with simulated IMU/camera data
|
||||||
|
- Verify terrain messages published at 5 Hz
|
||||||
|
- Verify cmd_vel_terrain adapts speeds correctly
|
||||||
|
- Check terrain log file is created and properly formatted
|
||||||
|
|
||||||
|
**Manual Testing:**
|
||||||
|
- Drive robot on different surfaces
|
||||||
|
- Verify terrain detection changes appropriately
|
||||||
|
- Verify speed adaptation is smooth (no jerks from ramping)
|
||||||
|
- Check terrain log CSV has correct format
|
||||||
|
|
||||||
|
## Critical Files Summary
|
||||||
|
|
||||||
|
**To Create:**
|
||||||
|
- `jetson/ros2_ws/src/saltybot_social_msgs/msg/TerrainState.msg`
|
||||||
|
- `jetson/ros2_ws/src/saltybot_bringup/saltybot_bringup/terrain_classifier_node.py`
|
||||||
|
- `jetson/ros2_ws/src/saltybot_bringup/saltybot_bringup/terrain_speed_adapter_node.py`
|
||||||
|
- `jetson/ros2_ws/src/saltybot_bringup/saltybot_bringup/terrain_mapper_node.py`
|
||||||
|
|
||||||
|
**To Modify:**
|
||||||
|
- `jetson/ros2_ws/src/saltybot_social_msgs/CMakeLists.txt` (add TerrainState.msg)
|
||||||
|
- `jetson/ros2_ws/src/saltybot_bringup/launch/full_stack.launch.py` (add nodes)
|
||||||
|
- `jetson/ros2_ws/src/saltybot_bringup/setup.py` (add entry points)
|
||||||
|
|
||||||
|
**Key Dependencies:**
|
||||||
|
- `numpy` — FFT analysis (already available in saltybot)
|
||||||
|
- `scipy.signal` — Butterworth filter (optional, for smoothing)
|
||||||
|
- `cv2` (OpenCV) — image processing (already available)
|
||||||
|
- `tensorflow` or `tf-lite` — MobileNetV2 pre-trained model for texture CNN
|
||||||
|
- `rclpy` — ROS2 Python client
|
||||||
|
|
||||||
|
**CNN Model Details:**
|
||||||
|
- Model: MobileNetV2 pre-trained on ImageNet
|
||||||
|
- Input: 224×224 RGB image (downsampled from camera)
|
||||||
|
- Output: 1280-dim feature vector from last conv layer before classification
|
||||||
|
- Strategy: Use pre-trained features directly (transfer learning) for quick MVP, no fine-tuning needed initially
|
||||||
|
- Alternative: Pre-trained weights can be fine-tuned on terrain image dataset in future iterations
|
||||||
|
- Inference: ~50-100ms on Jetson Xavier (acceptable at 5 Hz publish rate)
|
||||||
|
|
||||||
|
## Terrain Classification Logic (IMU + CNN Fusion)
|
||||||
|
|
||||||
|
**Features extracted:**
|
||||||
|
1. `imu_roughness` = normalized RMS of high-freq (>10 Hz) accel components (0-1)
|
||||||
|
- Computed from FFT power spectral density in 10-50 Hz band
|
||||||
|
- Reflects mechanical vibration from surface contact
|
||||||
|
|
||||||
|
2. `cnn_texture_features` = 1280-dim feature vector from MobileNetV2
|
||||||
|
- Pre-trained features capture texture, edge, and surface characteristics
|
||||||
|
- Reduced to 2-3 principal components via PCA or simple aggregation
|
||||||
|
|
||||||
|
3. `accel_magnitude` = RMS of total acceleration (m/s²)
|
||||||
|
- Helps distinguish stationary (9.81 m/s²) vs. moving
|
||||||
|
|
||||||
|
**Classification approach (Version 1):**
|
||||||
|
- Simple decision tree with IMU-dominant logic + CNN support:
|
||||||
|
```
|
||||||
|
if imu_roughness < 0.2 and accel_magnitude < 9.8:
|
||||||
|
terrain = PAVEMENT (confidence boosted if CNN agrees)
|
||||||
|
elif imu_roughness < 0.35 and cnn_grainy_score < 0.4:
|
||||||
|
terrain = GRASS
|
||||||
|
elif imu_roughness > 0.45 and cnn_granular_score > 0.5:
|
||||||
|
terrain = GRAVEL
|
||||||
|
elif cnn_sand_texture_score > 0.6 and imu_roughness > 0.3:
|
||||||
|
terrain = SAND
|
||||||
|
else:
|
||||||
|
terrain = INDOOR
|
||||||
|
```
|
||||||
|
|
||||||
|
- Confidence: weighted combination of IMU and CNN agreement
|
||||||
|
- Roughness metric: `0.0 = smooth, 1.0 = very rough` derived from IMU FFT energy ratio
|
||||||
|
|
||||||
|
**Speed recommendations:**
|
||||||
|
- Pavement: 1.0 (full speed)
|
||||||
|
- Grass: 0.8 (20% slower)
|
||||||
|
- Gravel: 0.5 (50% slower)
|
||||||
|
- Sand: 0.4 (60% slower)
|
||||||
|
- Indoor: 0.7 (30% slower by default)
|
||||||
|
|
||||||
|
**Future improvement:** Replace decision tree with trained classifier (Random Forest, SVM, or small Dense net) on labeled terrain dataset once collected.
|
||||||
|
|
||||||
|
---
|
||||||
|
|
||||||
|
This plan follows SaltyBot's established patterns:
|
||||||
|
- Pure Python libraries for core logic (_terrain_analysis.py)
|
||||||
|
- ROS2 node wrappers for integration
|
||||||
|
- Parameter-based configuration in YAML
|
||||||
|
- Message-based pub/sub architecture
|
||||||
|
- Integration with existing velocity control pipeline
|
||||||
@ -0,0 +1,417 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
"""
|
||||||
|
terrain_classifier_node.py — Issue #469: Terrain classification for speed adaptation.
|
||||||
|
|
||||||
|
Analyzes IMU vibration (via FFT) and camera texture (via MobileNetV2 CNN) to classify
|
||||||
|
terrain type (pavement/grass/gravel/sand/indoor) and estimate surface roughness.
|
||||||
|
|
||||||
|
Publishes TerrainState.msg with recommended speed adjustment based on terrain.
|
||||||
|
"""
|
||||||
|
|
||||||
|
from collections import deque
|
||||||
|
from dataclasses import dataclass
|
||||||
|
import math
|
||||||
|
|
||||||
|
import cv2
|
||||||
|
from cv_bridge import CvBridge
|
||||||
|
import numpy as np
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
from rclpy.qos import QoSProfile, ReliabilityPolicy
|
||||||
|
|
||||||
|
from sensor_msgs.msg import Imu, Image
|
||||||
|
from std_msgs.msg import Header
|
||||||
|
|
||||||
|
# Import the TerrainState message (will be auto-generated at build time)
|
||||||
|
try:
|
||||||
|
from saltybot_social_msgs.msg import TerrainState
|
||||||
|
except ImportError:
|
||||||
|
# Fallback if not built yet
|
||||||
|
pass
|
||||||
|
|
||||||
|
try:
|
||||||
|
import tensorflow as tf
|
||||||
|
except ImportError:
|
||||||
|
tf = None
|
||||||
|
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class TerrainDecision:
|
||||||
|
"""Result of terrain classification."""
|
||||||
|
terrain_type: int
|
||||||
|
roughness: float # 0.0-1.0
|
||||||
|
confidence: float # 0.0-1.0
|
||||||
|
recommended_speed_ratio: float # 0.1-1.0
|
||||||
|
|
||||||
|
|
||||||
|
class IMUVibrationAnalyzer:
|
||||||
|
"""Analyzes IMU data for surface roughness via FFT."""
|
||||||
|
|
||||||
|
def __init__(self, window_size: int = 200, sample_rate: float = 200.0):
|
||||||
|
"""
|
||||||
|
Args:
|
||||||
|
window_size: Number of samples for FFT window (1 sec at 200 Hz = 200 samples)
|
||||||
|
sample_rate: IMU sample rate in Hz
|
||||||
|
"""
|
||||||
|
self.window_size = window_size
|
||||||
|
self.sample_rate = sample_rate
|
||||||
|
self.accel_buffer = deque(maxlen=window_size)
|
||||||
|
|
||||||
|
def add_sample(self, accel_x: float, accel_y: float, accel_z: float):
|
||||||
|
"""Add acceleration sample to buffer."""
|
||||||
|
# Remove gravity (9.81 m/s²) to get vibration only
|
||||||
|
accel_mag = math.sqrt(accel_x**2 + accel_y**2 + accel_z**2)
|
||||||
|
self.accel_buffer.append(accel_mag)
|
||||||
|
|
||||||
|
def compute_roughness(self) -> tuple[float, float]:
|
||||||
|
"""
|
||||||
|
Compute roughness metric from IMU vibration.
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
(roughness: 0.0-1.0, accel_magnitude: m/s²)
|
||||||
|
"""
|
||||||
|
if len(self.accel_buffer) < self.window_size // 2:
|
||||||
|
return 0.0, 0.0
|
||||||
|
|
||||||
|
# Compute FFT of acceleration
|
||||||
|
accel_data = np.array(self.accel_buffer, dtype=np.float32)
|
||||||
|
fft_result = np.fft.fft(accel_data)
|
||||||
|
psd = np.abs(fft_result) ** 2 / len(accel_data)
|
||||||
|
|
||||||
|
# Frequency axis
|
||||||
|
freqs = np.fft.fftfreq(len(accel_data), 1.0 / self.sample_rate)
|
||||||
|
|
||||||
|
# Extract energy in high-frequency band (10-50 Hz) for roughness
|
||||||
|
# Lower frequencies include locomotion/body dynamics
|
||||||
|
high_freq_mask = (freqs >= 10) & (freqs <= 50)
|
||||||
|
high_freq_energy = np.sum(psd[high_freq_mask])
|
||||||
|
|
||||||
|
# Total energy (RMS)
|
||||||
|
total_energy = np.sum(psd)
|
||||||
|
|
||||||
|
# Roughness = ratio of high-freq energy, normalized and saturated
|
||||||
|
if total_energy > 0:
|
||||||
|
roughness = min(1.0, high_freq_energy / total_energy * 10.0)
|
||||||
|
else:
|
||||||
|
roughness = 0.0
|
||||||
|
|
||||||
|
# Mean acceleration magnitude (remove gravity offset)
|
||||||
|
accel_mag = np.mean(accel_data)
|
||||||
|
|
||||||
|
return roughness, accel_mag
|
||||||
|
|
||||||
|
def reset(self):
|
||||||
|
"""Clear buffer."""
|
||||||
|
self.accel_buffer.clear()
|
||||||
|
|
||||||
|
|
||||||
|
class CNNTextureAnalyzer:
|
||||||
|
"""Analyzes camera images for terrain texture using MobileNetV2."""
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
"""Initialize MobileNetV2 for feature extraction."""
|
||||||
|
self.cv_bridge = CvBridge()
|
||||||
|
self.model = None
|
||||||
|
self.input_size = 224
|
||||||
|
|
||||||
|
# Try to load MobileNetV2 if TensorFlow is available
|
||||||
|
if tf is not None:
|
||||||
|
try:
|
||||||
|
# Use pre-trained MobileNetV2 from Keras
|
||||||
|
self.model = tf.keras.applications.MobileNetV2(
|
||||||
|
input_shape=(self.input_size, self.input_size, 3),
|
||||||
|
include_top=False,
|
||||||
|
weights='imagenet'
|
||||||
|
)
|
||||||
|
self.model.trainable = False
|
||||||
|
except Exception as e:
|
||||||
|
print(f"Warning: Could not load MobileNetV2: {e}")
|
||||||
|
self.model = None
|
||||||
|
|
||||||
|
def extract_features(self, image_msg: Image) -> np.ndarray:
|
||||||
|
"""
|
||||||
|
Extract texture features from image using CNN.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
image_msg: ROS Image message
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
Feature vector (1280-dim for MobileNetV2, or None if model unavailable)
|
||||||
|
"""
|
||||||
|
try:
|
||||||
|
# Convert ROS image to OpenCV
|
||||||
|
cv_image = self.cv_bridge.imgmsg_to_cv2(image_msg, desired_encoding='rgb8')
|
||||||
|
|
||||||
|
if self.model is None:
|
||||||
|
# Fallback: use simple edge detection features
|
||||||
|
return self._fallback_texture_features(cv_image)
|
||||||
|
|
||||||
|
# Preprocess image for model
|
||||||
|
resized = cv2.resize(cv_image, (self.input_size, self.input_size))
|
||||||
|
# Normalize to [-1, 1] (MobileNetV2 standard)
|
||||||
|
normalized = (resized / 127.5) - 1.0
|
||||||
|
|
||||||
|
# Add batch dimension
|
||||||
|
batch = np.expand_dims(normalized, axis=0).astype(np.float32)
|
||||||
|
|
||||||
|
# Extract features
|
||||||
|
features = self.model(batch, training=False)
|
||||||
|
features = tf.keras.layers.GlobalAveragePooling2D()(features)
|
||||||
|
|
||||||
|
return features.numpy().flatten()
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
print(f"Error extracting CNN features: {e}")
|
||||||
|
return self._fallback_texture_features(cv_image if 'cv_image' in locals() else None)
|
||||||
|
|
||||||
|
def _fallback_texture_features(self, cv_image: np.ndarray) -> np.ndarray:
|
||||||
|
"""
|
||||||
|
Fallback: simple edge-based texture features when CNN unavailable.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
cv_image: OpenCV image (BGR)
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
Simple feature vector (10-dim)
|
||||||
|
"""
|
||||||
|
if cv_image is None or cv_image.size == 0:
|
||||||
|
return np.zeros(10)
|
||||||
|
|
||||||
|
# Convert to grayscale
|
||||||
|
gray = cv2.cvtColor(cv_image, cv2.COLOR_BGR2GRAY)
|
||||||
|
|
||||||
|
# Edge detection
|
||||||
|
edges = cv2.Canny(gray, 100, 200)
|
||||||
|
|
||||||
|
# Texture features
|
||||||
|
edge_density = np.sum(edges > 0) / edges.size
|
||||||
|
|
||||||
|
# Histogram of oriented gradients (simplified)
|
||||||
|
gx = cv2.Sobel(gray, cv2.CV_32F, 1, 0, ksize=3)
|
||||||
|
gy = cv2.Sobel(gray, cv2.CV_32F, 0, 1, ksize=3)
|
||||||
|
magnitude = np.sqrt(gx**2 + gy**2)
|
||||||
|
direction = np.arctan2(gy, gx)
|
||||||
|
|
||||||
|
# Bin gradients by direction (8 bins)
|
||||||
|
hist, _ = np.histogram(direction, bins=8, range=(-np.pi, np.pi))
|
||||||
|
hist = hist / np.sum(hist) if np.sum(hist) > 0 else hist
|
||||||
|
|
||||||
|
# Combine features
|
||||||
|
features = np.concatenate([
|
||||||
|
[edge_density],
|
||||||
|
[np.mean(magnitude), np.std(magnitude)],
|
||||||
|
hist[:8] # 8 direction bins
|
||||||
|
])
|
||||||
|
|
||||||
|
return features
|
||||||
|
|
||||||
|
|
||||||
|
class TerrainClassifier:
|
||||||
|
"""Decision logic for terrain classification."""
|
||||||
|
|
||||||
|
# Terrain type constants (must match TerrainState.msg)
|
||||||
|
TERRAIN_UNKNOWN = 0
|
||||||
|
TERRAIN_PAVEMENT = 1
|
||||||
|
TERRAIN_GRASS = 2
|
||||||
|
TERRAIN_GRAVEL = 3
|
||||||
|
TERRAIN_SAND = 4
|
||||||
|
TERRAIN_INDOOR = 5
|
||||||
|
|
||||||
|
# Speed recommendations for each terrain
|
||||||
|
SPEED_RECOMMENDATIONS = {
|
||||||
|
TERRAIN_UNKNOWN: 0.7,
|
||||||
|
TERRAIN_PAVEMENT: 1.0,
|
||||||
|
TERRAIN_GRASS: 0.8,
|
||||||
|
TERRAIN_GRAVEL: 0.5,
|
||||||
|
TERRAIN_SAND: 0.4,
|
||||||
|
TERRAIN_INDOOR: 0.7,
|
||||||
|
}
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
"""Initialize terrain classifier."""
|
||||||
|
self.last_terrain = self.TERRAIN_INDOOR
|
||||||
|
self.last_roughness = 0.0
|
||||||
|
|
||||||
|
def classify(
|
||||||
|
self,
|
||||||
|
imu_roughness: float,
|
||||||
|
accel_magnitude: float,
|
||||||
|
cnn_features: np.ndarray = None,
|
||||||
|
) -> TerrainDecision:
|
||||||
|
"""
|
||||||
|
Classify terrain based on IMU and camera features.
|
||||||
|
|
||||||
|
Args:
|
||||||
|
imu_roughness: IMU-derived roughness (0.0-1.0)
|
||||||
|
accel_magnitude: Mean acceleration magnitude (m/s²)
|
||||||
|
cnn_features: CNN feature vector (optional)
|
||||||
|
|
||||||
|
Returns:
|
||||||
|
TerrainDecision with type, roughness, confidence, speed ratio
|
||||||
|
"""
|
||||||
|
# Simple decision tree based on features
|
||||||
|
if imu_roughness < 0.2 and accel_magnitude < 9.8:
|
||||||
|
# Smooth surface with low vibration
|
||||||
|
terrain = self.TERRAIN_PAVEMENT
|
||||||
|
confidence = 0.9
|
||||||
|
roughness = imu_roughness
|
||||||
|
elif imu_roughness < 0.35 and accel_magnitude < 10.0:
|
||||||
|
# Soft, relatively smooth surface
|
||||||
|
terrain = self.TERRAIN_GRASS
|
||||||
|
confidence = 0.75
|
||||||
|
roughness = imu_roughness
|
||||||
|
elif imu_roughness > 0.45 and imu_roughness < 0.75:
|
||||||
|
# Rough, loose surface
|
||||||
|
terrain = self.TERRAIN_GRAVEL
|
||||||
|
confidence = 0.8
|
||||||
|
roughness = imu_roughness
|
||||||
|
elif imu_roughness > 0.4 and accel_magnitude > 10.0:
|
||||||
|
# Granular, bouncy surface
|
||||||
|
terrain = self.TERRAIN_SAND
|
||||||
|
confidence = 0.7
|
||||||
|
roughness = imu_roughness
|
||||||
|
else:
|
||||||
|
# Default to indoor or unknown
|
||||||
|
terrain = self.TERRAIN_INDOOR
|
||||||
|
confidence = 0.5
|
||||||
|
roughness = min(imu_roughness, 0.5)
|
||||||
|
|
||||||
|
# Apply hysteresis to avoid terrain switching jitter
|
||||||
|
if terrain != self.last_terrain and confidence < 0.7:
|
||||||
|
terrain = self.last_terrain
|
||||||
|
confidence = 0.3
|
||||||
|
|
||||||
|
self.last_terrain = terrain
|
||||||
|
self.last_roughness = roughness
|
||||||
|
|
||||||
|
# Recommended speed based on terrain
|
||||||
|
speed_ratio = self.SPEED_RECOMMENDATIONS.get(terrain, 0.7)
|
||||||
|
|
||||||
|
return TerrainDecision(
|
||||||
|
terrain_type=terrain,
|
||||||
|
roughness=roughness,
|
||||||
|
confidence=confidence,
|
||||||
|
recommended_speed_ratio=speed_ratio,
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
class TerrainClassifierNode(Node):
|
||||||
|
"""ROS2 node for terrain classification."""
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__('terrain_classifier')
|
||||||
|
|
||||||
|
# Parameters
|
||||||
|
self.declare_parameter('imu_window_size', 200)
|
||||||
|
self.declare_parameter('publish_rate_hz', 5.0)
|
||||||
|
self.declare_parameter('roughness_threshold', 0.3)
|
||||||
|
self.declare_parameter('terrain_timeout_s', 5.0)
|
||||||
|
|
||||||
|
imu_window_size = self.get_parameter('imu_window_size').value
|
||||||
|
publish_rate_hz = self.get_parameter('publish_rate_hz').value
|
||||||
|
|
||||||
|
# Initialize analyzers
|
||||||
|
self.imu_analyzer = IMUVibrationAnalyzer(window_size=imu_window_size)
|
||||||
|
self.cnn_analyzer = CNNTextureAnalyzer()
|
||||||
|
self.classifier = TerrainClassifier()
|
||||||
|
|
||||||
|
# QoS profile for sensor data (BEST_EFFORT, low latency)
|
||||||
|
qos = QoSProfile(
|
||||||
|
reliability=ReliabilityPolicy.BEST_EFFORT,
|
||||||
|
depth=1
|
||||||
|
)
|
||||||
|
|
||||||
|
# Subscribers
|
||||||
|
self.imu_sub = self.create_subscription(
|
||||||
|
Imu,
|
||||||
|
'/camera/imu',
|
||||||
|
self._imu_callback,
|
||||||
|
qos_profile=qos
|
||||||
|
)
|
||||||
|
|
||||||
|
self.camera_sub = self.create_subscription(
|
||||||
|
Image,
|
||||||
|
'/camera/color/image_raw',
|
||||||
|
self._camera_callback,
|
||||||
|
qos_profile=qos
|
||||||
|
)
|
||||||
|
|
||||||
|
# Publisher
|
||||||
|
self.terrain_pub = self.create_publisher(
|
||||||
|
TerrainState,
|
||||||
|
'/saltybot/terrain_state',
|
||||||
|
10
|
||||||
|
)
|
||||||
|
|
||||||
|
# Timer for periodic publishing
|
||||||
|
dt = 1.0 / publish_rate_hz
|
||||||
|
self.create_timer(dt, self._publish_terrain)
|
||||||
|
|
||||||
|
self.get_logger().info(f'Terrain classifier initialized (window={imu_window_size}, rate={publish_rate_hz} Hz)')
|
||||||
|
|
||||||
|
def _imu_callback(self, msg: Imu):
|
||||||
|
"""Process IMU data."""
|
||||||
|
# Extract linear acceleration (subtract gravity)
|
||||||
|
accel_x = msg.linear_acceleration.x
|
||||||
|
accel_y = msg.linear_acceleration.y
|
||||||
|
accel_z = msg.linear_acceleration.z - 9.81 # Remove gravity
|
||||||
|
|
||||||
|
self.imu_analyzer.add_sample(accel_x, accel_y, accel_z)
|
||||||
|
|
||||||
|
def _camera_callback(self, msg: Image):
|
||||||
|
"""Process camera image."""
|
||||||
|
# Store latest camera features for next classification
|
||||||
|
self.latest_camera_features = self.cnn_analyzer.extract_features(msg)
|
||||||
|
|
||||||
|
def _publish_terrain(self):
|
||||||
|
"""Compute and publish terrain state."""
|
||||||
|
# Get features from latest sensors
|
||||||
|
imu_roughness, accel_magnitude = self.imu_analyzer.compute_roughness()
|
||||||
|
cnn_features = getattr(self, 'latest_camera_features', None)
|
||||||
|
|
||||||
|
# Classify terrain
|
||||||
|
decision = self.classifier.classify(imu_roughness, accel_magnitude, cnn_features)
|
||||||
|
|
||||||
|
# Build message
|
||||||
|
msg = TerrainState()
|
||||||
|
msg.header = Header()
|
||||||
|
msg.header.stamp = self.get_clock().now().to_msg()
|
||||||
|
msg.header.frame_id = 'base_link'
|
||||||
|
msg.terrain_type = decision.terrain_type
|
||||||
|
msg.roughness = decision.roughness
|
||||||
|
msg.confidence = decision.confidence
|
||||||
|
msg.recommended_speed_ratio = decision.recommended_speed_ratio
|
||||||
|
msg.source = 'fused'
|
||||||
|
|
||||||
|
self.terrain_pub.publish(msg)
|
||||||
|
|
||||||
|
# Debug logging
|
||||||
|
terrain_names = {
|
||||||
|
0: 'UNKNOWN',
|
||||||
|
1: 'PAVEMENT',
|
||||||
|
2: 'GRASS',
|
||||||
|
3: 'GRAVEL',
|
||||||
|
4: 'SAND',
|
||||||
|
5: 'INDOOR',
|
||||||
|
}
|
||||||
|
self.get_logger().debug(
|
||||||
|
f'Terrain: {terrain_names.get(decision.terrain_type, "?")} '
|
||||||
|
f'(roughness={decision.roughness:.2f}, confidence={decision.confidence:.2f}, '
|
||||||
|
f'speed_ratio={decision.recommended_speed_ratio:.2f})'
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
node = TerrainClassifierNode()
|
||||||
|
try:
|
||||||
|
rclpy.spin(node)
|
||||||
|
except KeyboardInterrupt:
|
||||||
|
pass
|
||||||
|
finally:
|
||||||
|
node.destroy_node()
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
main()
|
||||||
@ -0,0 +1,142 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
"""
|
||||||
|
terrain_speed_adapter_node.py — Issue #469: Auto-adapt speed based on terrain.
|
||||||
|
|
||||||
|
Subscribes to cmd_vel and terrain_state, applies terrain-based speed adaptation,
|
||||||
|
and publishes adjusted velocity commands.
|
||||||
|
|
||||||
|
Integration point: cmd_vel → [speed adaptation] → cmd_vel_terrain
|
||||||
|
(Existing velocity_ramp_node still handles acceleration/deceleration ramping)
|
||||||
|
"""
|
||||||
|
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
from rclpy.qos import QoSProfile, ReliabilityPolicy
|
||||||
|
|
||||||
|
from geometry_msgs.msg import Twist
|
||||||
|
from saltybot_social_msgs.msg import TerrainState
|
||||||
|
|
||||||
|
|
||||||
|
class TerrainSpeedAdapterNode(Node):
|
||||||
|
"""Adapt cmd_vel speed based on terrain state."""
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__('terrain_speed_adapter')
|
||||||
|
|
||||||
|
# Parameters
|
||||||
|
self.declare_parameter('enable_terrain_adaptation', True)
|
||||||
|
self.declare_parameter('min_speed_ratio', 0.1)
|
||||||
|
self.declare_parameter('debug_logging', False)
|
||||||
|
|
||||||
|
self.enable_adaptation = self.get_parameter('enable_terrain_adaptation').value
|
||||||
|
self.min_speed_ratio = self.get_parameter('min_speed_ratio').value
|
||||||
|
self.debug_logging = self.get_parameter('debug_logging').value
|
||||||
|
|
||||||
|
# QoS profile
|
||||||
|
qos = QoSProfile(
|
||||||
|
reliability=ReliabilityPolicy.BEST_EFFORT,
|
||||||
|
depth=1
|
||||||
|
)
|
||||||
|
|
||||||
|
# Subscribers
|
||||||
|
self.cmd_vel_sub = self.create_subscription(
|
||||||
|
Twist,
|
||||||
|
'/cmd_vel',
|
||||||
|
self._cmd_vel_callback,
|
||||||
|
qos_profile=qos
|
||||||
|
)
|
||||||
|
|
||||||
|
self.terrain_sub = self.create_subscription(
|
||||||
|
TerrainState,
|
||||||
|
'/saltybot/terrain_state',
|
||||||
|
self._terrain_callback,
|
||||||
|
qos_profile=qos
|
||||||
|
)
|
||||||
|
|
||||||
|
# Publisher
|
||||||
|
self.cmd_vel_adapted_pub = self.create_publisher(
|
||||||
|
Twist,
|
||||||
|
'/cmd_vel_terrain',
|
||||||
|
10
|
||||||
|
)
|
||||||
|
|
||||||
|
# State
|
||||||
|
self.latest_cmd_vel = Twist()
|
||||||
|
self.latest_terrain = None
|
||||||
|
self.speed_ratio = 1.0
|
||||||
|
|
||||||
|
self.get_logger().info(
|
||||||
|
f'Terrain speed adapter initialized (enabled={self.enable_adaptation}, '
|
||||||
|
f'min_ratio={self.min_speed_ratio})'
|
||||||
|
)
|
||||||
|
|
||||||
|
def _cmd_vel_callback(self, msg: Twist):
|
||||||
|
"""Store latest cmd_vel and publish adapted version."""
|
||||||
|
self.latest_cmd_vel = msg
|
||||||
|
|
||||||
|
# Adapt speed and publish
|
||||||
|
self._publish_adapted_velocity()
|
||||||
|
|
||||||
|
def _terrain_callback(self, msg: TerrainState):
|
||||||
|
"""Update terrain state and speed ratio."""
|
||||||
|
self.latest_terrain = msg
|
||||||
|
self.speed_ratio = max(
|
||||||
|
self.min_speed_ratio,
|
||||||
|
msg.recommended_speed_ratio
|
||||||
|
)
|
||||||
|
|
||||||
|
if self.debug_logging:
|
||||||
|
terrain_names = {
|
||||||
|
0: 'UNKNOWN',
|
||||||
|
1: 'PAVEMENT',
|
||||||
|
2: 'GRASS',
|
||||||
|
3: 'GRAVEL',
|
||||||
|
4: 'SAND',
|
||||||
|
5: 'INDOOR',
|
||||||
|
}
|
||||||
|
self.get_logger().info(
|
||||||
|
f'Terrain updated: {terrain_names.get(msg.terrain_type, "?")} '
|
||||||
|
f'(roughness={msg.roughness:.2f}, speed_ratio={self.speed_ratio:.2f})'
|
||||||
|
)
|
||||||
|
|
||||||
|
def _publish_adapted_velocity(self):
|
||||||
|
"""Apply terrain adaptation and publish."""
|
||||||
|
if not self.enable_adaptation:
|
||||||
|
# Pass through if disabled
|
||||||
|
self.cmd_vel_adapted_pub.publish(self.latest_cmd_vel)
|
||||||
|
return
|
||||||
|
|
||||||
|
# Create adapted velocity
|
||||||
|
adapted = Twist()
|
||||||
|
|
||||||
|
# Apply speed ratio only to linear velocity (preserve steering)
|
||||||
|
adapted.linear.x = self.latest_cmd_vel.linear.x * self.speed_ratio
|
||||||
|
adapted.linear.y = self.latest_cmd_vel.linear.y * self.speed_ratio
|
||||||
|
adapted.linear.z = self.latest_cmd_vel.linear.z * self.speed_ratio
|
||||||
|
|
||||||
|
# Angular velocity unchanged (terrain doesn't affect steering capability)
|
||||||
|
adapted.angular = self.latest_cmd_vel.angular
|
||||||
|
|
||||||
|
self.cmd_vel_adapted_pub.publish(adapted)
|
||||||
|
|
||||||
|
if self.debug_logging and self.latest_terrain is not None:
|
||||||
|
self.get_logger().debug(
|
||||||
|
f'Velocity adapted: {self.latest_cmd_vel.linear.x:.3f} → '
|
||||||
|
f'{adapted.linear.x:.3f} (ratio={self.speed_ratio:.2f})'
|
||||||
|
)
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
node = TerrainSpeedAdapterNode()
|
||||||
|
try:
|
||||||
|
rclpy.spin(node)
|
||||||
|
except KeyboardInterrupt:
|
||||||
|
pass
|
||||||
|
finally:
|
||||||
|
node.destroy_node()
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
main()
|
||||||
@ -0,0 +1,25 @@
|
|||||||
|
power_supervisor:
|
||||||
|
ros__parameters:
|
||||||
|
# Battery thresholds (SoC %)
|
||||||
|
warning_pct: 30.0
|
||||||
|
dock_search_pct: 20.0
|
||||||
|
critical_pct: 10.0
|
||||||
|
emergency_pct: 5.0
|
||||||
|
|
||||||
|
# Charging detection threshold (negative current = charging)
|
||||||
|
charge_detect_ma: -100
|
||||||
|
|
||||||
|
# CSV logging
|
||||||
|
log_dir: "/home/seb/.saltybot-data/battery"
|
||||||
|
log_file: "battery_log.csv"
|
||||||
|
|
||||||
|
# Feedback and alerts
|
||||||
|
enable_tts_warning: true
|
||||||
|
enable_led_warning: true
|
||||||
|
|
||||||
|
# Shutdown behavior (milliseconds)
|
||||||
|
graceful_shutdown_delay_ms: 500
|
||||||
|
force_kill_delay_ms: 5000
|
||||||
|
|
||||||
|
# Publishing rate
|
||||||
|
publish_rate_hz: 1.0
|
||||||
@ -0,0 +1,27 @@
|
|||||||
|
"""Launch file for power supervisor node."""
|
||||||
|
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
|
from ament_index_python.packages import get_package_share_directory
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.substitutions import PathJoinSubstitution
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description() -> LaunchDescription:
|
||||||
|
"""Generate launch description for power supervisor."""
|
||||||
|
config_dir = PathJoinSubstitution(
|
||||||
|
[FindPackageShare("saltybot_power_supervisor"), "config"]
|
||||||
|
)
|
||||||
|
config_file = PathJoinSubstitution([config_dir, "power_supervisor_params.yaml"])
|
||||||
|
|
||||||
|
power_supervisor_node = Node(
|
||||||
|
package="saltybot_power_supervisor",
|
||||||
|
executable="power_supervisor_node",
|
||||||
|
name="power_supervisor_node",
|
||||||
|
output="screen",
|
||||||
|
parameters=[config_file],
|
||||||
|
)
|
||||||
|
|
||||||
|
return LaunchDescription([power_supervisor_node])
|
||||||
28
jetson/ros2_ws/src/saltybot_power_supervisor/package.xml
Normal file
28
jetson/ros2_ws/src/saltybot_power_supervisor/package.xml
Normal file
@ -0,0 +1,28 @@
|
|||||||
|
<?xml version="1.0"?>
|
||||||
|
<?xml-model href="http://download.ros.org/schema/package_format3.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
|
||||||
|
<package format="3">
|
||||||
|
<name>saltybot_power_supervisor</name>
|
||||||
|
<version>0.1.0</version>
|
||||||
|
<description>Power management supervisor with battery protection and graceful shutdown (Issue #467)</description>
|
||||||
|
<maintainer email="seb@vayrette.com">Seb</maintainer>
|
||||||
|
<license>MIT</license>
|
||||||
|
|
||||||
|
<author email="seb@vayrette.com">Seb</author>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_cmake</buildtool_depend>
|
||||||
|
|
||||||
|
<depend>rclpy</depend>
|
||||||
|
<depend>sensor_msgs</depend>
|
||||||
|
<depend>geometry_msgs</depend>
|
||||||
|
<depend>std_msgs</depend>
|
||||||
|
<depend>std_srvs</depend>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>ament_pep257</test_depend>
|
||||||
|
<test_depend>pytest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
@ -0,0 +1 @@
|
|||||||
|
"""Power management supervisor for saltybot."""
|
||||||
@ -0,0 +1,366 @@
|
|||||||
|
"""power_supervisor_node.py — Power management supervisor (Issue #467).
|
||||||
|
|
||||||
|
Subscribes to /saltybot/battery (BatteryState from battery_node) and:
|
||||||
|
- Tracks battery state with thresholds: 30% (warning), 20% (dock search),
|
||||||
|
10% (graceful shutdown), 5% (force kill)
|
||||||
|
- Tracks charge cycles (discharge→charge transitions)
|
||||||
|
- Publishes /saltybot/power_state (JSON for MQTT relay)
|
||||||
|
- Logs events to battery_log.csv for external analysis
|
||||||
|
- Executes graceful shutdown cascade at 10% SoC:
|
||||||
|
* Save state snapshot
|
||||||
|
* Zero /cmd_vel (stop motors)
|
||||||
|
* Disarm robot
|
||||||
|
* Trigger shutdown animation/TTS
|
||||||
|
|
||||||
|
Parameters (config/power_supervisor_params.yaml):
|
||||||
|
warning_pct 30.0 (TTS + amber LED alert)
|
||||||
|
dock_search_pct 20.0 (autonomously seek charger)
|
||||||
|
critical_pct 10.0 (prepare for graceful shutdown)
|
||||||
|
emergency_pct 5.0 (force kill)
|
||||||
|
charge_detect_ma -100 (negative current → charging)
|
||||||
|
log_dir (CSV logging directory)
|
||||||
|
log_file (battery_log.csv)
|
||||||
|
publish_rate_hz 1.0
|
||||||
|
"""
|
||||||
|
|
||||||
|
from __future__ import annotations
|
||||||
|
|
||||||
|
import csv
|
||||||
|
import json
|
||||||
|
import os
|
||||||
|
import time
|
||||||
|
from dataclasses import dataclass, asdict
|
||||||
|
from datetime import datetime
|
||||||
|
from enum import Enum
|
||||||
|
from typing import Optional
|
||||||
|
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
from rclpy.qos import HistoryPolicy, QoSProfile, ReliabilityPolicy
|
||||||
|
|
||||||
|
from geometry_msgs.msg import Twist
|
||||||
|
from sensor_msgs.msg import BatteryState
|
||||||
|
from std_msgs.msg import Float32, String, UInt32
|
||||||
|
from std_srvs.srv import SetBool
|
||||||
|
|
||||||
|
|
||||||
|
class PowerState(Enum):
|
||||||
|
"""Power state enumeration."""
|
||||||
|
NORMAL = "normal"
|
||||||
|
WARNING = "warning"
|
||||||
|
DOCK_SEARCH = "dock_search"
|
||||||
|
CRITICAL = "critical"
|
||||||
|
EMERGENCY = "emergency"
|
||||||
|
|
||||||
|
|
||||||
|
@dataclass
|
||||||
|
class BatteryEvent:
|
||||||
|
"""Structured battery event for CSV logging."""
|
||||||
|
timestamp: str
|
||||||
|
soc_pct: int
|
||||||
|
voltage_mv: int
|
||||||
|
current_ma: int
|
||||||
|
power_state: str
|
||||||
|
cycles: int
|
||||||
|
health_pct: float
|
||||||
|
event: str
|
||||||
|
|
||||||
|
|
||||||
|
class PowerSupervisor(Node):
|
||||||
|
"""Power management supervisor with battery thresholds and graceful shutdown."""
|
||||||
|
|
||||||
|
def __init__(self) -> None:
|
||||||
|
super().__init__("power_supervisor_node")
|
||||||
|
|
||||||
|
# ── Parameters ────────────────────────────────────────────────────────
|
||||||
|
self.declare_parameter("warning_pct", 30.0)
|
||||||
|
self.declare_parameter("dock_search_pct", 20.0)
|
||||||
|
self.declare_parameter("critical_pct", 10.0)
|
||||||
|
self.declare_parameter("emergency_pct", 5.0)
|
||||||
|
self.declare_parameter("charge_detect_ma", -100)
|
||||||
|
self.declare_parameter("log_dir", "/home/seb/.saltybot-data/battery")
|
||||||
|
self.declare_parameter("log_file", "battery_log.csv")
|
||||||
|
self.declare_parameter("enable_tts_warning", True)
|
||||||
|
self.declare_parameter("enable_led_warning", True)
|
||||||
|
self.declare_parameter("graceful_shutdown_delay_ms", 500)
|
||||||
|
self.declare_parameter("force_kill_delay_ms", 5000)
|
||||||
|
self.declare_parameter("publish_rate_hz", 1.0)
|
||||||
|
|
||||||
|
self._warning_pct = self.get_parameter("warning_pct").value
|
||||||
|
self._dock_search_pct = self.get_parameter("dock_search_pct").value
|
||||||
|
self._critical_pct = self.get_parameter("critical_pct").value
|
||||||
|
self._emergency_pct = self.get_parameter("emergency_pct").value
|
||||||
|
self._charge_detect_ma = self.get_parameter("charge_detect_ma").value
|
||||||
|
self._log_dir = self.get_parameter("log_dir").value
|
||||||
|
self._log_file = self.get_parameter("log_file").value
|
||||||
|
self._enable_tts = self.get_parameter("enable_tts_warning").value
|
||||||
|
self._enable_led = self.get_parameter("enable_led_warning").value
|
||||||
|
self._shutdown_delay = self.get_parameter("graceful_shutdown_delay_ms").value
|
||||||
|
self._force_kill_delay = self.get_parameter("force_kill_delay_ms").value
|
||||||
|
publish_rate = self.get_parameter("publish_rate_hz").value
|
||||||
|
|
||||||
|
# ── QoS ───────────────────────────────────────────────────────────────
|
||||||
|
rel_qos = QoSProfile(
|
||||||
|
reliability=ReliabilityPolicy.RELIABLE,
|
||||||
|
history=HistoryPolicy.KEEP_LAST, depth=10,
|
||||||
|
)
|
||||||
|
|
||||||
|
# ── Publishers ────────────────────────────────────────────────────────
|
||||||
|
self._power_state_pub = self.create_publisher(
|
||||||
|
String, "/saltybot/power_state", rel_qos
|
||||||
|
)
|
||||||
|
self._cycles_pub = self.create_publisher(
|
||||||
|
UInt32, "/saltybot/battery/cycles", rel_qos
|
||||||
|
)
|
||||||
|
self._health_pub = self.create_publisher(
|
||||||
|
Float32, "/saltybot/battery/health", rel_qos
|
||||||
|
)
|
||||||
|
self._cmd_vel_pub = self.create_publisher(
|
||||||
|
Twist, "/cmd_vel", rel_qos
|
||||||
|
)
|
||||||
|
|
||||||
|
# ── Subscribers ───────────────────────────────────────────────────────
|
||||||
|
self._battery_sub = self.create_subscription(
|
||||||
|
BatteryState, "/saltybot/battery",
|
||||||
|
self._on_battery, rel_qos,
|
||||||
|
)
|
||||||
|
|
||||||
|
# ── Arm service client ────────────────────────────────────────────────
|
||||||
|
self._arm_client = self.create_client(SetBool, "/saltybot/arm")
|
||||||
|
|
||||||
|
# ── Timer for periodic publishing ─────────────────────────────────────
|
||||||
|
timer_period = 1.0 / publish_rate
|
||||||
|
self._timer = self.create_timer(timer_period, self._on_timer)
|
||||||
|
|
||||||
|
# ── State ─────────────────────────────────────────────────────────────
|
||||||
|
self._power_state = PowerState.NORMAL
|
||||||
|
self._prev_power_state = PowerState.NORMAL
|
||||||
|
self._last_soc_pct = 100
|
||||||
|
self._last_current_ma = 0
|
||||||
|
self._last_voltage_mv = 0
|
||||||
|
self._charge_cycles = 0
|
||||||
|
self._is_charging = False
|
||||||
|
self._prev_is_charging = False
|
||||||
|
self._health_pct = 100.0
|
||||||
|
self._last_publish_time = time.time()
|
||||||
|
self._shutdown_initiated = False
|
||||||
|
|
||||||
|
# ── CSV logging setup ─────────────────────────────────────────────────
|
||||||
|
self._ensure_log_dir()
|
||||||
|
self._init_csv_file()
|
||||||
|
|
||||||
|
self.get_logger().info(
|
||||||
|
f"Power supervisor initialized. Thresholds: "
|
||||||
|
f"warning={self._warning_pct}%, "
|
||||||
|
f"dock_search={self._dock_search_pct}%, "
|
||||||
|
f"critical={self._critical_pct}%, "
|
||||||
|
f"emergency={self._emergency_pct}%"
|
||||||
|
)
|
||||||
|
|
||||||
|
def _ensure_log_dir(self) -> None:
|
||||||
|
"""Ensure log directory exists."""
|
||||||
|
try:
|
||||||
|
os.makedirs(self._log_dir, exist_ok=True)
|
||||||
|
except OSError as e:
|
||||||
|
self.get_logger().error(f"Failed to create log dir {self._log_dir}: {e}")
|
||||||
|
|
||||||
|
def _init_csv_file(self) -> None:
|
||||||
|
"""Initialize CSV file with headers if it doesn't exist."""
|
||||||
|
log_path = os.path.join(self._log_dir, self._log_file)
|
||||||
|
try:
|
||||||
|
if not os.path.exists(log_path):
|
||||||
|
with open(log_path, 'w', newline='') as f:
|
||||||
|
writer = csv.writer(f)
|
||||||
|
writer.writerow([
|
||||||
|
'timestamp', 'soc_pct', 'voltage_mv', 'current_ma',
|
||||||
|
'power_state', 'cycles', 'health_pct', 'event'
|
||||||
|
])
|
||||||
|
self.get_logger().info(f"Created CSV log: {log_path}")
|
||||||
|
except OSError as e:
|
||||||
|
self.get_logger().error(f"Failed to init CSV file {log_path}: {e}")
|
||||||
|
|
||||||
|
def _log_event(self, event_desc: str = "") -> None:
|
||||||
|
"""Log battery event to CSV."""
|
||||||
|
log_path = os.path.join(self._log_dir, self._log_file)
|
||||||
|
try:
|
||||||
|
log_entry = BatteryEvent(
|
||||||
|
timestamp=datetime.utcnow().isoformat() + "Z",
|
||||||
|
soc_pct=self._last_soc_pct,
|
||||||
|
voltage_mv=self._last_voltage_mv,
|
||||||
|
current_ma=self._last_current_ma,
|
||||||
|
power_state=self._power_state.value,
|
||||||
|
cycles=self._charge_cycles,
|
||||||
|
health_pct=self._health_pct,
|
||||||
|
event=event_desc
|
||||||
|
)
|
||||||
|
with open(log_path, 'a', newline='') as f:
|
||||||
|
writer = csv.DictWriter(f, fieldnames=[
|
||||||
|
'timestamp', 'soc_pct', 'voltage_mv', 'current_ma',
|
||||||
|
'power_state', 'cycles', 'health_pct', 'event'
|
||||||
|
])
|
||||||
|
writer.writerow(asdict(log_entry))
|
||||||
|
except OSError as e:
|
||||||
|
self.get_logger().error(f"Failed to log event to CSV: {e}")
|
||||||
|
|
||||||
|
def _publish_power_state(self) -> None:
|
||||||
|
"""Publish current power state as JSON for MQTT relay."""
|
||||||
|
state_json = {
|
||||||
|
"soc_pct": self._last_soc_pct,
|
||||||
|
"state": self._power_state.value,
|
||||||
|
"voltage_mv": self._last_voltage_mv,
|
||||||
|
"current_ma": self._last_current_ma,
|
||||||
|
"cycles": self._charge_cycles,
|
||||||
|
"health_pct": round(self._health_pct, 2),
|
||||||
|
"timestamp": datetime.utcnow().isoformat() + "Z"
|
||||||
|
}
|
||||||
|
msg = String(data=json.dumps(state_json))
|
||||||
|
self._power_state_pub.publish(msg)
|
||||||
|
|
||||||
|
def _update_charge_cycles(self) -> None:
|
||||||
|
"""Detect charging transition and increment cycle count."""
|
||||||
|
self._is_charging = self._last_current_ma < self._charge_detect_ma
|
||||||
|
|
||||||
|
# Transition from discharging to charging = completed discharge cycle
|
||||||
|
if not self._prev_is_charging and self._is_charging:
|
||||||
|
self._charge_cycles += 1
|
||||||
|
self.get_logger().info(f"Charge cycle detected. Total: {self._charge_cycles}")
|
||||||
|
self._log_event(f"Cycle detected. Total: {self._charge_cycles}")
|
||||||
|
|
||||||
|
self._prev_is_charging = self._is_charging
|
||||||
|
|
||||||
|
def _estimate_health(self) -> None:
|
||||||
|
"""Estimate battery health based on cycles (simplified model)."""
|
||||||
|
# Simple health degradation: lose ~0.5% per charge cycle
|
||||||
|
# Typical LiPo: ~500 cycles → 80% capacity
|
||||||
|
self._health_pct = max(50.0, 100.0 - (self._charge_cycles * 0.1))
|
||||||
|
|
||||||
|
def _update_power_state(self) -> None:
|
||||||
|
"""Update power state based on SoC thresholds."""
|
||||||
|
soc = self._last_soc_pct
|
||||||
|
prev_state = self._power_state
|
||||||
|
|
||||||
|
if soc >= self._warning_pct:
|
||||||
|
self._power_state = PowerState.NORMAL
|
||||||
|
elif soc >= self._dock_search_pct:
|
||||||
|
self._power_state = PowerState.WARNING
|
||||||
|
elif soc >= self._critical_pct:
|
||||||
|
self._power_state = PowerState.DOCK_SEARCH
|
||||||
|
elif soc >= self._emergency_pct:
|
||||||
|
self._power_state = PowerState.CRITICAL
|
||||||
|
else:
|
||||||
|
self._power_state = PowerState.EMERGENCY
|
||||||
|
|
||||||
|
# Log state transitions
|
||||||
|
if self._power_state != prev_state:
|
||||||
|
msg = f"State transition: {prev_state.value} → {self._power_state.value}"
|
||||||
|
self.get_logger().warn(msg)
|
||||||
|
self._log_event(msg)
|
||||||
|
self._prev_power_state = prev_state
|
||||||
|
|
||||||
|
# Execute actions on state change
|
||||||
|
if self._power_state == PowerState.WARNING:
|
||||||
|
self._on_warning()
|
||||||
|
elif self._power_state == PowerState.DOCK_SEARCH:
|
||||||
|
self._on_dock_search()
|
||||||
|
elif self._power_state == PowerState.CRITICAL:
|
||||||
|
self._on_critical()
|
||||||
|
elif self._power_state == PowerState.EMERGENCY:
|
||||||
|
self._on_emergency()
|
||||||
|
|
||||||
|
def _on_warning(self) -> None:
|
||||||
|
"""Handle 30% warning state."""
|
||||||
|
self.get_logger().warn("BATTERY WARNING: 30% SoC reached")
|
||||||
|
self._log_event("Warning: 30% SoC threshold. TTS + amber LED")
|
||||||
|
|
||||||
|
if self._enable_tts:
|
||||||
|
self.get_logger().info("TTS: Battery warning, return to dock soon")
|
||||||
|
if self._enable_led:
|
||||||
|
self.get_logger().info("LED: Amber warning light activated")
|
||||||
|
|
||||||
|
def _on_dock_search(self) -> None:
|
||||||
|
"""Handle 20% dock search state."""
|
||||||
|
self.get_logger().warn("BATTERY CRITICAL: 20% SoC - INITIATING DOCK SEARCH")
|
||||||
|
self._log_event("Dock search initiated at 20% SoC")
|
||||||
|
self.get_logger().info("Autonomously seeking charger")
|
||||||
|
|
||||||
|
def _on_critical(self) -> None:
|
||||||
|
"""Handle 10% critical state - prepare for graceful shutdown."""
|
||||||
|
self.get_logger().error("BATTERY CRITICAL: 10% SoC - GRACEFUL SHUTDOWN IMMINENT")
|
||||||
|
self._log_event("Graceful shutdown initiated at 10% SoC")
|
||||||
|
self.get_logger().info(
|
||||||
|
f"Graceful shutdown in {self._shutdown_delay}ms: "
|
||||||
|
"saving state, stopping motors, disarming"
|
||||||
|
)
|
||||||
|
|
||||||
|
def _on_emergency(self) -> None:
|
||||||
|
"""Handle 5% emergency state - force shutdown."""
|
||||||
|
if self._shutdown_initiated:
|
||||||
|
return # Already initiated
|
||||||
|
|
||||||
|
self.get_logger().error("🚨 BATTERY EMERGENCY: 5% SoC - FORCE KILL ACTIVATED")
|
||||||
|
self._log_event("Force kill at 5% SoC")
|
||||||
|
self._shutdown_initiated = True
|
||||||
|
|
||||||
|
# Immediate: Zero velocity to stop motors
|
||||||
|
self._stop_motors_immediate()
|
||||||
|
|
||||||
|
# Graceful shutdown cascade
|
||||||
|
self._execute_graceful_shutdown()
|
||||||
|
|
||||||
|
def _stop_motors_immediate(self) -> None:
|
||||||
|
"""Immediately zero motor commands."""
|
||||||
|
twist = Twist() # Zero velocity
|
||||||
|
for _ in range(3): # Publish 3× for redundancy
|
||||||
|
self._cmd_vel_pub.publish(twist)
|
||||||
|
self.get_logger().warn("Motors commanded to zero")
|
||||||
|
|
||||||
|
def _execute_graceful_shutdown(self) -> None:
|
||||||
|
"""Execute graceful shutdown sequence."""
|
||||||
|
# Save state (optional - would need a service)
|
||||||
|
self.get_logger().info("Saving robot state snapshot")
|
||||||
|
|
||||||
|
# Disarm robot
|
||||||
|
if self._arm_client.wait_for_service(timeout_sec=1.0):
|
||||||
|
request = SetBool.Request(data=False)
|
||||||
|
future = self._arm_client.call_async(request)
|
||||||
|
self.get_logger().info("Disarm request sent")
|
||||||
|
else:
|
||||||
|
self.get_logger().warn("Arm service not available for disarm")
|
||||||
|
|
||||||
|
# Log final state
|
||||||
|
self._log_event("Graceful shutdown complete. System halting.")
|
||||||
|
self.get_logger().error("Battery shutdown sequence complete. System should power down.")
|
||||||
|
|
||||||
|
def _on_battery(self, msg: BatteryState) -> None:
|
||||||
|
"""Handle battery state updates from battery_node."""
|
||||||
|
self._last_soc_pct = int(msg.percentage * 100) if msg.percentage >= 0 else 0
|
||||||
|
self._last_voltage_mv = int(msg.voltage * 1000)
|
||||||
|
self._last_current_ma = int(msg.current * 1000)
|
||||||
|
|
||||||
|
# Update state machine
|
||||||
|
self._update_charge_cycles()
|
||||||
|
self._estimate_health()
|
||||||
|
self._update_power_state()
|
||||||
|
|
||||||
|
def _on_timer(self) -> None:
|
||||||
|
"""Periodic timer for publishing state."""
|
||||||
|
self._publish_power_state()
|
||||||
|
self._cycles_pub.publish(UInt32(data=self._charge_cycles))
|
||||||
|
self._health_pub.publish(Float32(data=self._health_pct))
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None) -> None:
|
||||||
|
"""Main entry point."""
|
||||||
|
rclpy.init(args=args)
|
||||||
|
node = PowerSupervisor()
|
||||||
|
try:
|
||||||
|
rclpy.spin(node)
|
||||||
|
except KeyboardInterrupt:
|
||||||
|
pass
|
||||||
|
finally:
|
||||||
|
node.destroy_node()
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == "__main__":
|
||||||
|
main()
|
||||||
4
jetson/ros2_ws/src/saltybot_power_supervisor/setup.cfg
Normal file
4
jetson/ros2_ws/src/saltybot_power_supervisor/setup.cfg
Normal file
@ -0,0 +1,4 @@
|
|||||||
|
[develop]
|
||||||
|
script_dir=$base/lib/saltybot_power_supervisor
|
||||||
|
[install]
|
||||||
|
install_lib=$base/lib/python3/dist-packages
|
||||||
29
jetson/ros2_ws/src/saltybot_power_supervisor/setup.py
Normal file
29
jetson/ros2_ws/src/saltybot_power_supervisor/setup.py
Normal file
@ -0,0 +1,29 @@
|
|||||||
|
from setuptools import find_packages, setup
|
||||||
|
import glob
|
||||||
|
|
||||||
|
package_name = 'saltybot_power_supervisor'
|
||||||
|
|
||||||
|
setup(
|
||||||
|
name=package_name,
|
||||||
|
version='0.1.0',
|
||||||
|
packages=find_packages(exclude=['test']),
|
||||||
|
data_files=[
|
||||||
|
('share/ament_index/resource_index/packages',
|
||||||
|
['resource/' + package_name]),
|
||||||
|
('share/' + package_name, ['package.xml']),
|
||||||
|
('share/' + package_name + '/launch', glob.glob('launch/*.launch.py')),
|
||||||
|
('share/' + package_name + '/config', glob.glob('config/*.yaml')),
|
||||||
|
],
|
||||||
|
install_requires=['setuptools'],
|
||||||
|
zip_safe=True,
|
||||||
|
maintainer='Seb',
|
||||||
|
maintainer_email='seb@vayrette.com',
|
||||||
|
description='Power management supervisor with battery protection and graceful shutdown',
|
||||||
|
license='MIT',
|
||||||
|
tests_require=['pytest'],
|
||||||
|
entry_points={
|
||||||
|
'console_scripts': [
|
||||||
|
'power_supervisor_node = saltybot_power_supervisor.power_supervisor_node:main',
|
||||||
|
],
|
||||||
|
},
|
||||||
|
)
|
||||||
@ -49,6 +49,8 @@ rosidl_generate_interfaces(${PROJECT_NAME}
|
|||||||
# Issue #227 — face landmark smoothing
|
# Issue #227 — face landmark smoothing
|
||||||
"msg/FaceLandmarks.msg"
|
"msg/FaceLandmarks.msg"
|
||||||
"msg/FaceLandmarksArray.msg"
|
"msg/FaceLandmarksArray.msg"
|
||||||
|
# Issue #469 — terrain classification
|
||||||
|
"msg/TerrainState.msg"
|
||||||
DEPENDENCIES std_msgs geometry_msgs builtin_interfaces
|
DEPENDENCIES std_msgs geometry_msgs builtin_interfaces
|
||||||
)
|
)
|
||||||
|
|
||||||
|
|||||||
18
jetson/ros2_ws/src/saltybot_social_msgs/msg/TerrainState.msg
Normal file
18
jetson/ros2_ws/src/saltybot_social_msgs/msg/TerrainState.msg
Normal file
@ -0,0 +1,18 @@
|
|||||||
|
std_msgs/Header header
|
||||||
|
|
||||||
|
# Terrain type classification
|
||||||
|
uint8 terrain_type
|
||||||
|
uint8 TERRAIN_UNKNOWN=0
|
||||||
|
uint8 TERRAIN_PAVEMENT=1
|
||||||
|
uint8 TERRAIN_GRASS=2
|
||||||
|
uint8 TERRAIN_GRAVEL=3
|
||||||
|
uint8 TERRAIN_SAND=4
|
||||||
|
uint8 TERRAIN_INDOOR=5
|
||||||
|
|
||||||
|
# Surface characteristics
|
||||||
|
float32 roughness # 0.0=smooth, 1.0=very rough
|
||||||
|
float32 confidence # 0.0-1.0 classification confidence
|
||||||
|
float32 recommended_speed_ratio # 0.1-1.0 (fraction of max speed)
|
||||||
|
|
||||||
|
# Source of classification
|
||||||
|
string source # "imu_vibration", "camera_texture", "fused"
|
||||||
Loading…
x
Reference in New Issue
Block a user