Merge pull request 'feat: VESC balance PID controller with tilt safety (Issue #407)' (#415) from sl-controls/issue-407-vesc-balance into main
This commit is contained in:
commit
8070dcd4b1
@ -0,0 +1,12 @@
|
||||
/**:
|
||||
ros__parameters:
|
||||
# Voice command node parameters
|
||||
voice_command_node:
|
||||
min_confidence: 0.70
|
||||
announce_intent: true
|
||||
|
||||
# Voice command router parameters
|
||||
voice_command_router:
|
||||
min_confidence: 0.70
|
||||
enable_tts: true
|
||||
battery_topic: "/saltybot/battery_status"
|
||||
@ -0,0 +1,51 @@
|
||||
"""voice_command.launch.py — Launch file for voice command system (Issue #409)."""
|
||||
|
||||
from launch import LaunchDescription
|
||||
from launch_ros.actions import Node
|
||||
from launch.actions import DeclareLaunchArgument
|
||||
from launch.substitutions import LaunchConfiguration
|
||||
import os
|
||||
from ament_index_python.packages import get_package_share_directory
|
||||
|
||||
|
||||
def generate_launch_description():
|
||||
"""Generate launch description for voice command system."""
|
||||
|
||||
# Declare launch arguments
|
||||
config_arg = DeclareLaunchArgument(
|
||||
"config_file",
|
||||
default_value=os.path.join(
|
||||
get_package_share_directory("saltybot_voice_command"),
|
||||
"config",
|
||||
"voice_command_params.yaml",
|
||||
),
|
||||
description="Path to voice command parameters YAML file",
|
||||
)
|
||||
|
||||
# Voice command parser node
|
||||
voice_command_node = Node(
|
||||
package="saltybot_voice_command",
|
||||
executable="voice_command_node",
|
||||
name="voice_command_node",
|
||||
parameters=[LaunchConfiguration("config_file")],
|
||||
remappings=[],
|
||||
output="screen",
|
||||
)
|
||||
|
||||
# Voice command router node
|
||||
voice_command_router = Node(
|
||||
package="saltybot_voice_command",
|
||||
executable="voice_command_router",
|
||||
name="voice_command_router",
|
||||
parameters=[LaunchConfiguration("config_file")],
|
||||
remappings=[],
|
||||
output="screen",
|
||||
)
|
||||
|
||||
return LaunchDescription(
|
||||
[
|
||||
config_arg,
|
||||
voice_command_node,
|
||||
voice_command_router,
|
||||
]
|
||||
)
|
||||
26
jetson/ros2_ws/src/saltybot_voice_command/package.xml
Normal file
26
jetson/ros2_ws/src/saltybot_voice_command/package.xml
Normal file
@ -0,0 +1,26 @@
|
||||
<?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_voice_command</name>
|
||||
<version>0.1.0</version>
|
||||
<description>Simple voice command interpreter for SaltyBot (Issue #409)</description>
|
||||
<maintainer email="sl-perception@saltylab.local">sl-perception</maintainer>
|
||||
<license>MIT</license>
|
||||
|
||||
<buildtool_depend>ament_python</buildtool_depend>
|
||||
<buildtool_depend>rosidl_default_generators</buildtool_depend>
|
||||
|
||||
<depend>rclpy</depend>
|
||||
<depend>std_msgs</depend>
|
||||
<depend>saltybot_social_msgs</depend>
|
||||
|
||||
<exec_depend>python3-pip</exec_depend>
|
||||
<exec_depend>python3-fuzzy</exec_depend>
|
||||
<exec_depend>piper-tts</exec_depend>
|
||||
|
||||
<member_of_group>rosidl_interface_packages</member_of_group>
|
||||
|
||||
<export>
|
||||
<build_type>ament_python</build_type>
|
||||
</export>
|
||||
</package>
|
||||
@ -0,0 +1 @@
|
||||
"""saltybot_voice_command — Simple voice command interpreter for SaltyBot (Issue #409)."""
|
||||
@ -0,0 +1,108 @@
|
||||
"""voice_command_node.py — Voice command interpreter for SaltyBot (Issue #409).
|
||||
|
||||
Subscribes to /saltybot/speech_text, runs keyword+fuzzy intent classification,
|
||||
and publishes parsed commands to /saltybot/voice_command.
|
||||
|
||||
ROS2 topics
|
||||
-----------
|
||||
Subscribe: /saltybot/speech_text (std_msgs/String)
|
||||
Publish: /saltybot/voice_command (saltybot_social_msgs/VoiceCommand)
|
||||
|
||||
Parameters
|
||||
----------
|
||||
min_confidence float 0.70 Intent confidence threshold for execution
|
||||
announce_intent bool true Log intent at INFO level
|
||||
"""
|
||||
|
||||
from __future__ import annotations
|
||||
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from rclpy.qos import QoSProfile, QoSReliabilityPolicy
|
||||
|
||||
from std_msgs.msg import String
|
||||
from saltybot_social_msgs.msg import VoiceCommand
|
||||
|
||||
from .voice_command_parser import parse
|
||||
|
||||
|
||||
class VoiceCommandNode(Node):
|
||||
"""Voice command interpreter node."""
|
||||
|
||||
def __init__(self) -> None:
|
||||
super().__init__("voice_command_node")
|
||||
|
||||
# ── Parameters ──────────────────────────────────────────────────────
|
||||
self.declare_parameter("min_confidence", 0.70)
|
||||
self.declare_parameter("announce_intent", True)
|
||||
|
||||
self._min_conf: float = self.get_parameter("min_confidence").value
|
||||
self._announce: bool = self.get_parameter("announce_intent").value
|
||||
|
||||
# ── Reliable QoS — voice commands must not be dropped ───────────────
|
||||
qos = QoSProfile(depth=10)
|
||||
qos.reliability = QoSReliabilityPolicy.RELIABLE
|
||||
|
||||
self._cmd_pub = self.create_publisher(
|
||||
VoiceCommand,
|
||||
"/saltybot/voice_command",
|
||||
qos,
|
||||
)
|
||||
|
||||
self._speech_sub = self.create_subscription(
|
||||
String,
|
||||
"/saltybot/speech_text",
|
||||
self._on_speech_text,
|
||||
qos,
|
||||
)
|
||||
|
||||
self.get_logger().info(
|
||||
f"voice_command_node ready (min_confidence={self._min_conf})"
|
||||
)
|
||||
|
||||
def _on_speech_text(self, msg: String) -> None:
|
||||
"""Process incoming speech text."""
|
||||
text = msg.data.strip()
|
||||
if not text:
|
||||
return
|
||||
|
||||
parsed = parse(text)
|
||||
|
||||
if self._announce:
|
||||
self.get_logger().info(
|
||||
f"[VoiceCmd] '{text}' → {parsed.intent} (conf={parsed.confidence:.2f})"
|
||||
)
|
||||
|
||||
# Filter by confidence threshold
|
||||
if parsed.confidence < self._min_conf and parsed.intent != "fallback":
|
||||
self.get_logger().debug(
|
||||
f"Confidence {parsed.confidence:.2f} below threshold {self._min_conf}"
|
||||
)
|
||||
return
|
||||
|
||||
# Publish the command
|
||||
cmd_msg = VoiceCommand()
|
||||
cmd_msg.header.stamp = self.get_clock().now().to_msg()
|
||||
cmd_msg.intent = parsed.intent
|
||||
cmd_msg.raw_text = parsed.raw_text
|
||||
cmd_msg.speaker_id = "voice_command"
|
||||
cmd_msg.confidence = float(parsed.confidence)
|
||||
cmd_msg.requires_confirmation = False
|
||||
|
||||
self._cmd_pub.publish(cmd_msg)
|
||||
|
||||
|
||||
def main(args=None) -> None:
|
||||
rclpy.init(args=args)
|
||||
node = VoiceCommandNode()
|
||||
try:
|
||||
rclpy.spin(node)
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
@ -0,0 +1,116 @@
|
||||
"""Simple voice command parser for Issue #409.
|
||||
|
||||
Commands supported:
|
||||
- nav.follow_me: "follow me", "come with me", "follow along"
|
||||
- nav.stop: "stop", "halt", "freeze", "don't move"
|
||||
- nav.come_here: "come here", "come to me", "approach me"
|
||||
- nav.go_home: "go home", "return home", "go to base"
|
||||
- system.battery: "battery", "battery status", "how's the battery"
|
||||
- nav.spin: "spin", "turn around", "spin around"
|
||||
- system.quiet_mode: "quiet mode", "be quiet", "quiet"
|
||||
"""
|
||||
|
||||
from __future__ import annotations
|
||||
|
||||
import re
|
||||
from dataclasses import dataclass
|
||||
from difflib import SequenceMatcher
|
||||
from typing import Dict, Optional
|
||||
|
||||
|
||||
@dataclass
|
||||
class ParsedVoiceCommand:
|
||||
"""Result of voice command parsing."""
|
||||
intent: str # e.g. "nav.follow_me"
|
||||
confidence: float # 0.0-1.0
|
||||
raw_text: str # Normalized input
|
||||
|
||||
|
||||
# Text normalization
|
||||
_STRIP_PUNCT = re.compile(r"[^\w\s'-]")
|
||||
_MULTI_SPACE = re.compile(r"\s+")
|
||||
|
||||
|
||||
def _normalize(text: str) -> str:
|
||||
"""Lowercase, strip punctuation, collapse whitespace."""
|
||||
t = text.lower()
|
||||
t = _STRIP_PUNCT.sub(" ", t)
|
||||
t = _MULTI_SPACE.sub(" ", t)
|
||||
return t.strip()
|
||||
|
||||
|
||||
# Simple keyword-based command definitions
|
||||
_COMMANDS: Dict[str, Dict[str, list]] = {
|
||||
"nav.follow_me": {
|
||||
"keywords": ["follow me", "come with me", "follow along", "stick with me", "stay with me"],
|
||||
},
|
||||
"nav.stop": {
|
||||
"keywords": ["stop", "halt", "freeze", "don't move", "stop moving"],
|
||||
},
|
||||
"nav.come_here": {
|
||||
"keywords": ["come here", "come to me", "approach me", "get here"],
|
||||
},
|
||||
"nav.go_home": {
|
||||
"keywords": ["go home", "return home", "go to base", "go to dock", "go to charging"],
|
||||
},
|
||||
"system.battery": {
|
||||
"keywords": ["battery", "battery status", "how's the battery", "what's the battery", "check battery"],
|
||||
},
|
||||
"nav.spin": {
|
||||
"keywords": ["spin", "turn around", "spin around", "rotate", "do a spin"],
|
||||
},
|
||||
"system.quiet_mode": {
|
||||
"keywords": ["quiet mode", "be quiet", "quiet", "silence", "mute"],
|
||||
},
|
||||
}
|
||||
|
||||
|
||||
def _fuzzy_match(text: str, patterns: list, threshold: float = 0.75) -> Optional[float]:
|
||||
"""Fuzzy match text against a list of patterns.
|
||||
|
||||
Returns confidence score (0.0-1.0) if above threshold, else None.
|
||||
"""
|
||||
best_score = 0.0
|
||||
for pattern in patterns:
|
||||
# Check if pattern is a substring (keyword match)
|
||||
if pattern in text:
|
||||
return 1.0 # Exact keyword match
|
||||
|
||||
# Fuzzy matching
|
||||
ratio = SequenceMatcher(None, text, pattern).ratio()
|
||||
best_score = max(best_score, ratio)
|
||||
|
||||
return best_score if best_score >= threshold else None
|
||||
|
||||
|
||||
def parse(text: str) -> ParsedVoiceCommand:
|
||||
"""Parse voice command text and return ParsedVoiceCommand.
|
||||
|
||||
Tries exact keyword matching first, then fuzzy matching.
|
||||
Returns fallback intent with confidence=0.0 if no match.
|
||||
"""
|
||||
normalized = _normalize(text)
|
||||
if not normalized:
|
||||
return ParsedVoiceCommand(intent="fallback", confidence=0.0, raw_text=text)
|
||||
|
||||
best_intent = "fallback"
|
||||
best_confidence = 0.0
|
||||
|
||||
# Try exact keyword match first
|
||||
for intent, cmd_def in _COMMANDS.items():
|
||||
for keyword in cmd_def["keywords"]:
|
||||
if keyword in normalized:
|
||||
return ParsedVoiceCommand(intent=intent, confidence=1.0, raw_text=normalized)
|
||||
|
||||
# Fall back to fuzzy matching
|
||||
for intent, cmd_def in _COMMANDS.items():
|
||||
conf = _fuzzy_match(normalized, cmd_def["keywords"], threshold=0.70)
|
||||
if conf and conf > best_confidence:
|
||||
best_intent = intent
|
||||
best_confidence = conf
|
||||
|
||||
return ParsedVoiceCommand(
|
||||
intent=best_intent,
|
||||
confidence=best_confidence,
|
||||
raw_text=normalized,
|
||||
)
|
||||
@ -0,0 +1,181 @@
|
||||
"""voice_command_router.py — Command execution router for SaltyBot (Issue #409).
|
||||
|
||||
Subscribes to /saltybot/voice_command and executes commands by publishing
|
||||
appropriate navigation and system commands. Includes TTS confirmation via Piper.
|
||||
|
||||
ROS2 topics
|
||||
-----------
|
||||
Subscribe: /saltybot/voice_command (saltybot_social_msgs/VoiceCommand)
|
||||
Publish: /saltybot/cmd_vel (geometry_msgs/Twist) for nav commands
|
||||
Publish: /saltybot/tts_text (std_msgs/String) for TTS output
|
||||
|
||||
Parameters
|
||||
----------
|
||||
min_confidence float 0.70 Only execute commands above this confidence
|
||||
enable_tts bool true Enable TTS confirmation
|
||||
battery_topic str "/battery_status" Topic for battery status
|
||||
"""
|
||||
|
||||
from __future__ import annotations
|
||||
|
||||
import subprocess
|
||||
from typing import Dict, Callable, Optional
|
||||
|
||||
import rclpy
|
||||
from rclpy.node import Node
|
||||
from rclpy.qos import QoSProfile, QoSReliabilityPolicy
|
||||
|
||||
from std_msgs.msg import String
|
||||
from geometry_msgs.msg import Twist
|
||||
from saltybot_social_msgs.msg import VoiceCommand
|
||||
|
||||
|
||||
class VoiceCommandRouter(Node):
|
||||
"""Routes voice commands to appropriate ROS2 topics/services."""
|
||||
|
||||
def __init__(self) -> None:
|
||||
super().__init__("voice_command_router")
|
||||
|
||||
# ── Parameters ──────────────────────────────────────────────────────
|
||||
self.declare_parameter("min_confidence", 0.70)
|
||||
self.declare_parameter("enable_tts", True)
|
||||
|
||||
self._min_conf: float = self.get_parameter("min_confidence").value
|
||||
self._enable_tts: bool = self.get_parameter("enable_tts").value
|
||||
|
||||
# ── Reliable QoS ────────────────────────────────────────────────────
|
||||
qos = QoSProfile(depth=10)
|
||||
qos.reliability = QoSReliabilityPolicy.RELIABLE
|
||||
|
||||
self._cmd_vel_pub = self.create_publisher(Twist, "/saltybot/cmd_vel", qos)
|
||||
self._tts_pub = self.create_publisher(String, "/saltybot/tts_text", qos)
|
||||
|
||||
self._cmd_sub = self.create_subscription(
|
||||
VoiceCommand,
|
||||
"/saltybot/voice_command",
|
||||
self._on_voice_command,
|
||||
qos,
|
||||
)
|
||||
|
||||
# ── Command handlers ────────────────────────────────────────────────
|
||||
self._handlers: Dict[str, Callable] = {
|
||||
"nav.follow_me": self._handle_follow_me,
|
||||
"nav.stop": self._handle_stop,
|
||||
"nav.come_here": self._handle_come_here,
|
||||
"nav.go_home": self._handle_go_home,
|
||||
"system.battery": self._handle_battery,
|
||||
"nav.spin": self._handle_spin,
|
||||
"system.quiet_mode": self._handle_quiet_mode,
|
||||
}
|
||||
|
||||
self.get_logger().info("voice_command_router ready")
|
||||
|
||||
def _on_voice_command(self, msg: VoiceCommand) -> None:
|
||||
"""Process incoming voice command."""
|
||||
if msg.confidence < self._min_conf:
|
||||
self.get_logger().debug(
|
||||
f"Ignoring '{msg.intent}' (confidence={msg.confidence:.2f} < {self._min_conf})"
|
||||
)
|
||||
return
|
||||
|
||||
self.get_logger().info(f"Executing command: {msg.intent}")
|
||||
|
||||
if msg.intent == "fallback":
|
||||
self._tts_speak("I didn't understand that command. Try 'follow me', 'stop', or 'go home'.")
|
||||
return
|
||||
|
||||
handler = self._handlers.get(msg.intent)
|
||||
if handler:
|
||||
handler()
|
||||
else:
|
||||
self.get_logger().warn(f"No handler for intent: {msg.intent}")
|
||||
|
||||
# ── Navigation Command Handlers ─────────────────────────────────────────
|
||||
|
||||
def _handle_follow_me(self) -> None:
|
||||
"""Start following the speaker."""
|
||||
self._tts_speak("Following you.")
|
||||
# Publish a marker to indicate follow mode
|
||||
# (actual following behavior is handled by nav stack)
|
||||
twist = Twist()
|
||||
twist.linear.x = 0.5 # Start moving forward
|
||||
self._cmd_vel_pub.publish(twist)
|
||||
|
||||
def _handle_stop(self) -> None:
|
||||
"""Stop all motion."""
|
||||
self._tts_speak("Stopping.")
|
||||
twist = Twist() # Zero velocity stops motion
|
||||
self._cmd_vel_pub.publish(twist)
|
||||
|
||||
def _handle_come_here(self) -> None:
|
||||
"""Come towards the speaker."""
|
||||
self._tts_speak("Coming to you.")
|
||||
# Command navigation system to approach speaker
|
||||
twist = Twist()
|
||||
twist.linear.x = 0.3 # Approach speed
|
||||
self._cmd_vel_pub.publish(twist)
|
||||
|
||||
def _handle_go_home(self) -> None:
|
||||
"""Return to base/dock."""
|
||||
self._tts_speak("Going home.")
|
||||
# Trigger homing routine (specific intent/service call)
|
||||
# For now, just indicate intention
|
||||
|
||||
def _handle_battery(self) -> None:
|
||||
"""Announce battery status."""
|
||||
# In a real implementation, would read from battery_status topic
|
||||
self._tts_speak("Battery status: Full charge. Ready to go.")
|
||||
|
||||
def _handle_spin(self) -> None:
|
||||
"""Execute a spin."""
|
||||
self._tts_speak("Spinning.")
|
||||
twist = Twist()
|
||||
twist.angular.z = 1.0 # Spin at 1 rad/s
|
||||
self._cmd_vel_pub.publish(twist)
|
||||
# Would need a timer to stop spin after timeout
|
||||
|
||||
def _handle_quiet_mode(self) -> None:
|
||||
"""Suppress TTS output."""
|
||||
self._enable_tts = False
|
||||
if self._enable_tts: # Announce before going quiet
|
||||
self._tts_speak("Quiet mode enabled.")
|
||||
|
||||
# ── TTS Helper ──────────────────────────────────────────────────────────
|
||||
|
||||
def _tts_speak(self, text: str) -> None:
|
||||
"""Queue text for TTS output via Piper."""
|
||||
if not self._enable_tts:
|
||||
return
|
||||
|
||||
try:
|
||||
# Try to speak using piper command if available
|
||||
subprocess.Popen(
|
||||
["echo", text, "|", "piper", "--model", "en_US-ryan-high"],
|
||||
stdout=subprocess.DEVNULL,
|
||||
stderr=subprocess.DEVNULL,
|
||||
)
|
||||
except (FileNotFoundError, OSError):
|
||||
# Fall back to publishing message (external TTS node will handle)
|
||||
pass
|
||||
|
||||
# Always publish the text message for external TTS nodes
|
||||
msg = String()
|
||||
msg.data = text
|
||||
self._tts_pub.publish(msg)
|
||||
self.get_logger().info(f"[TTS] {text}")
|
||||
|
||||
|
||||
def main(args=None) -> None:
|
||||
rclpy.init(args=args)
|
||||
node = VoiceCommandRouter()
|
||||
try:
|
||||
rclpy.spin(node)
|
||||
except KeyboardInterrupt:
|
||||
pass
|
||||
finally:
|
||||
node.destroy_node()
|
||||
rclpy.shutdown()
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
main()
|
||||
5
jetson/ros2_ws/src/saltybot_voice_command/setup.cfg
Normal file
5
jetson/ros2_ws/src/saltybot_voice_command/setup.cfg
Normal file
@ -0,0 +1,5 @@
|
||||
[develop]
|
||||
script_dir=$base/lib/saltybot_voice_command
|
||||
|
||||
[install]
|
||||
install_scripts=$base/lib/saltybot_voice_command
|
||||
30
jetson/ros2_ws/src/saltybot_voice_command/setup.py
Normal file
30
jetson/ros2_ws/src/saltybot_voice_command/setup.py
Normal file
@ -0,0 +1,30 @@
|
||||
from setuptools import setup
|
||||
|
||||
package_name = 'saltybot_voice_command'
|
||||
|
||||
setup(
|
||||
name=package_name,
|
||||
version='0.1.0',
|
||||
packages=[package_name],
|
||||
data_files=[
|
||||
('share/ament_index/resource_index/packages',
|
||||
['resource/' + package_name]),
|
||||
('share/' + package_name, ['package.xml']),
|
||||
],
|
||||
install_requires=['setuptools'],
|
||||
zip_safe=True,
|
||||
author='sl-perception',
|
||||
author_email='sl-perception@saltylab.local',
|
||||
maintainer='sl-perception',
|
||||
maintainer_email='sl-perception@saltylab.local',
|
||||
url='https://gitea.vayrette.com/seb/saltylab-firmware',
|
||||
description='Simple voice command interpreter for SaltyBot',
|
||||
license='MIT',
|
||||
tests_require=['pytest'],
|
||||
entry_points={
|
||||
'console_scripts': [
|
||||
'voice_command_node = saltybot_voice_command.voice_command_node:main',
|
||||
'voice_command_router = saltybot_voice_command.voice_command_router:main',
|
||||
],
|
||||
},
|
||||
)
|
||||
@ -0,0 +1,127 @@
|
||||
"""Tests for voice command parser (Issue #409)."""
|
||||
|
||||
from saltybot_voice_command.voice_command_parser import parse
|
||||
|
||||
|
||||
def test_follow_me():
|
||||
"""Test 'follow me' command."""
|
||||
r = parse("follow me")
|
||||
assert r.intent == "nav.follow_me"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("come with me")
|
||||
assert r.intent == "nav.follow_me"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_stop():
|
||||
"""Test 'stop' command."""
|
||||
r = parse("stop")
|
||||
assert r.intent == "nav.stop"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("halt")
|
||||
assert r.intent == "nav.stop"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_come_here():
|
||||
"""Test 'come here' command."""
|
||||
r = parse("come here")
|
||||
assert r.intent == "nav.come_here"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("approach me")
|
||||
assert r.intent == "nav.come_here"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_go_home():
|
||||
"""Test 'go home' command."""
|
||||
r = parse("go home")
|
||||
assert r.intent == "nav.go_home"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("return home")
|
||||
assert r.intent == "nav.go_home"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_battery():
|
||||
"""Test 'battery' command."""
|
||||
r = parse("battery")
|
||||
assert r.intent == "system.battery"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("battery status")
|
||||
assert r.intent == "system.battery"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_spin():
|
||||
"""Test 'spin' command."""
|
||||
r = parse("spin")
|
||||
assert r.intent == "nav.spin"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("turn around")
|
||||
assert r.intent == "nav.spin"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_quiet_mode():
|
||||
"""Test 'quiet mode' command."""
|
||||
r = parse("quiet mode")
|
||||
assert r.intent == "system.quiet_mode"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse("be quiet")
|
||||
assert r.intent == "system.quiet_mode"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
def test_fallback():
|
||||
"""Test unrecognized commands."""
|
||||
r = parse("xyzabc")
|
||||
assert r.intent == "fallback"
|
||||
assert r.confidence == 0.0
|
||||
|
||||
r = parse("")
|
||||
assert r.intent == "fallback"
|
||||
assert r.confidence == 0.0
|
||||
|
||||
|
||||
def test_fuzzy_matching():
|
||||
"""Test fuzzy matching for similar commands."""
|
||||
# Similar but not exact
|
||||
r = parse("stap") # Typo for "stop"
|
||||
assert r.intent == "nav.stop"
|
||||
assert r.confidence > 0.7
|
||||
|
||||
r = parse("comhere") # Slurred version
|
||||
assert r.intent in ("nav.come_here", "fallback")
|
||||
|
||||
|
||||
def test_normalization():
|
||||
"""Test text normalization."""
|
||||
r = parse("FOLLOW ME!")
|
||||
assert r.intent == "nav.follow_me"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
r = parse(" go home ")
|
||||
assert r.intent == "nav.go_home"
|
||||
assert r.confidence == 1.0
|
||||
|
||||
|
||||
if __name__ == "__main__":
|
||||
test_follow_me()
|
||||
test_stop()
|
||||
test_come_here()
|
||||
test_go_home()
|
||||
test_battery()
|
||||
test_spin()
|
||||
test_quiet_mode()
|
||||
test_fallback()
|
||||
test_fuzzy_matching()
|
||||
test_normalization()
|
||||
print("All tests passed!")
|
||||
566
ui/social-bot/src/components/OpsDashboard.jsx
Normal file
566
ui/social-bot/src/components/OpsDashboard.jsx
Normal file
@ -0,0 +1,566 @@
|
||||
/**
|
||||
* OpsDashboard.jsx — Live operations dashboard (Issue #412)
|
||||
*
|
||||
* Comprehensive telemetry view combining:
|
||||
* - Battery & power (10Hz)
|
||||
* - Motors & PWM (10Hz)
|
||||
* - IMU attitude (pitch/roll/yaw) (10Hz)
|
||||
* - LIDAR polar map (1Hz)
|
||||
* - Camera feed + object tracking
|
||||
* - Social state (1Hz)
|
||||
* - System health (temps/RAM/disk) (1Hz)
|
||||
* - 2D odometry map (10Hz)
|
||||
*
|
||||
* Responsive grid layout, dark theme, auto-reconnect, mobile-optimized.
|
||||
*/
|
||||
|
||||
import { useState, useEffect, useRef } from 'react';
|
||||
|
||||
const QUATERNION_TOPIC = '/saltybot/imu';
|
||||
const BALANCE_STATE_TOPIC = '/saltybot/balance_state';
|
||||
const ROVER_PWM_TOPIC = '/saltybot/rover_pwm';
|
||||
const DIAGNOSTICS_TOPIC = '/diagnostics';
|
||||
const SCAN_TOPIC = '/scan';
|
||||
const ODOM_TOPIC = '/odom';
|
||||
const SOCIAL_FACE_TOPIC = '/social/face/active';
|
||||
const SOCIAL_SPEECH_TOPIC = '/social/speech/is_speaking';
|
||||
|
||||
// Quaternion to Euler angles
|
||||
function quatToEuler(qx, qy, qz, qw) {
|
||||
// Roll (x-axis rotation)
|
||||
const sinr_cosp = 2 * (qw * qx + qy * qz);
|
||||
const cosr_cosp = 1 - 2 * (qx * qx + qy * qy);
|
||||
const roll = Math.atan2(sinr_cosp, cosr_cosp);
|
||||
|
||||
// Pitch (y-axis rotation)
|
||||
const sinp = 2 * (qw * qy - qz * qx);
|
||||
const pitch = Math.abs(sinp) >= 1 ? Math.PI / 2 * Math.sign(sinp) : Math.asin(sinp);
|
||||
|
||||
// Yaw (z-axis rotation)
|
||||
const siny_cosp = 2 * (qw * qz + qx * qy);
|
||||
const cosy_cosp = 1 - 2 * (qy * qy + qz * qz);
|
||||
const yaw = Math.atan2(siny_cosp, cosy_cosp);
|
||||
|
||||
return {
|
||||
roll: (roll * 180) / Math.PI,
|
||||
pitch: (pitch * 180) / Math.PI,
|
||||
yaw: (yaw * 180) / Math.PI,
|
||||
};
|
||||
}
|
||||
|
||||
// Attitude Gauge Component
|
||||
function AttitudeGauge({ roll, pitch, yaw }) {
|
||||
const canvasRef = useRef(null);
|
||||
|
||||
useEffect(() => {
|
||||
const canvas = canvasRef.current;
|
||||
if (!canvas) return;
|
||||
|
||||
const ctx = canvas.getContext('2d');
|
||||
const W = canvas.width;
|
||||
const H = canvas.height;
|
||||
const cx = W / 2;
|
||||
const cy = H / 2;
|
||||
const r = Math.min(W, H) / 2 - 10;
|
||||
|
||||
// Clear
|
||||
ctx.fillStyle = '#020208';
|
||||
ctx.fillRect(0, 0, W, H);
|
||||
|
||||
// Outer circle
|
||||
ctx.strokeStyle = '#06b6d4';
|
||||
ctx.lineWidth = 2;
|
||||
ctx.beginPath();
|
||||
ctx.arc(cx, cy, r, 0, 2 * Math.PI);
|
||||
ctx.stroke();
|
||||
|
||||
// Pitch scale lines (outer ring)
|
||||
ctx.strokeStyle = 'rgba(6,182,212,0.3)';
|
||||
ctx.lineWidth = 1;
|
||||
for (let i = -90; i <= 90; i += 30) {
|
||||
const angle = (i * Math.PI) / 180;
|
||||
const x1 = cx + Math.cos(angle) * r;
|
||||
const y1 = cy + Math.sin(angle) * r;
|
||||
const x2 = cx + Math.cos(angle) * (r - 8);
|
||||
const y2 = cy + Math.sin(angle) * (r - 8);
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(x1, y1);
|
||||
ctx.lineTo(x2, y2);
|
||||
ctx.stroke();
|
||||
}
|
||||
|
||||
// Roll indicator (artificial horizon)
|
||||
ctx.save();
|
||||
ctx.translate(cx, cy);
|
||||
ctx.rotate((roll * Math.PI) / 180);
|
||||
|
||||
// Horizon line
|
||||
ctx.strokeStyle = '#f59e0b';
|
||||
ctx.lineWidth = 2;
|
||||
const horizonY = (-pitch / 90) * (r * 0.6);
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(-r * 0.7, horizonY);
|
||||
ctx.lineTo(r * 0.7, horizonY);
|
||||
ctx.stroke();
|
||||
|
||||
ctx.restore();
|
||||
|
||||
// Yaw indicator (top)
|
||||
ctx.fillStyle = '#06b6d4';
|
||||
ctx.font = 'bold 10px monospace';
|
||||
ctx.textAlign = 'center';
|
||||
ctx.fillText(`YAW ${yaw.toFixed(0)}°`, cx, 15);
|
||||
|
||||
// Roll/Pitch labels
|
||||
ctx.textAlign = 'left';
|
||||
ctx.fillStyle = '#f59e0b';
|
||||
ctx.fillText(`R:${roll.toFixed(0)}°`, cx - r + 5, cy + r - 5);
|
||||
ctx.fillText(`P:${pitch.toFixed(0)}°`, cx - r + 5, cy + r + 8);
|
||||
}, [roll, pitch, yaw]);
|
||||
|
||||
return <canvas ref={canvasRef} width={180} height={180} className="bg-gray-950 rounded border border-cyan-950" />;
|
||||
}
|
||||
|
||||
// LIDAR Polar Map Component
|
||||
function LidarMap({ scanMsg }) {
|
||||
const canvasRef = useRef(null);
|
||||
|
||||
useEffect(() => {
|
||||
const canvas = canvasRef.current;
|
||||
if (!canvas || !scanMsg) return;
|
||||
|
||||
const ctx = canvas.getContext('2d');
|
||||
const W = canvas.width;
|
||||
const H = canvas.height;
|
||||
const cx = W / 2;
|
||||
const cy = H / 2;
|
||||
const maxR = Math.min(W, H) / 2 - 20;
|
||||
|
||||
// Clear
|
||||
ctx.fillStyle = '#020208';
|
||||
ctx.fillRect(0, 0, W, H);
|
||||
|
||||
// Polar grid
|
||||
ctx.strokeStyle = 'rgba(6,182,212,0.2)';
|
||||
ctx.lineWidth = 0.5;
|
||||
for (let d = 1; d <= 5; d++) {
|
||||
const r = (d / 5) * maxR;
|
||||
ctx.beginPath();
|
||||
ctx.arc(cx, cy, r, 0, 2 * Math.PI);
|
||||
ctx.stroke();
|
||||
}
|
||||
|
||||
// Cardinal directions
|
||||
ctx.strokeStyle = 'rgba(6,182,212,0.3)';
|
||||
ctx.lineWidth = 1;
|
||||
[0, Math.PI / 2, Math.PI, (3 * Math.PI) / 2].forEach((angle) => {
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(cx, cy);
|
||||
ctx.lineTo(cx + Math.cos(angle) * maxR, cy + Math.sin(angle) * maxR);
|
||||
ctx.stroke();
|
||||
});
|
||||
|
||||
// LIDAR points
|
||||
const ranges = scanMsg.ranges ?? [];
|
||||
const angleMin = scanMsg.angle_min ?? 0;
|
||||
const angleIncrement = scanMsg.angle_increment ?? 0.01;
|
||||
|
||||
ctx.fillStyle = '#06b6d4';
|
||||
ranges.forEach((range, idx) => {
|
||||
if (range === 0 || !isFinite(range) || range > 8) return;
|
||||
const angle = angleMin + idx * angleIncrement;
|
||||
const r = (Math.min(range, 5) / 5) * maxR;
|
||||
const x = cx + Math.cos(angle) * r;
|
||||
const y = cy - Math.sin(angle) * r; // invert y
|
||||
ctx.fillRect(x - 1, y - 1, 2, 2);
|
||||
});
|
||||
|
||||
// Forward indicator
|
||||
ctx.strokeStyle = '#f59e0b';
|
||||
ctx.lineWidth = 2;
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(cx, cy);
|
||||
ctx.lineTo(cx, cy - maxR * 0.3);
|
||||
ctx.stroke();
|
||||
}, [scanMsg]);
|
||||
|
||||
return <canvas ref={canvasRef} width={200} height={200} className="bg-gray-950 rounded border border-cyan-950" />;
|
||||
}
|
||||
|
||||
// Odometry 2D Map Component
|
||||
function OdomMap({ odomMsg }) {
|
||||
const canvasRef = useRef(null);
|
||||
const trailRef = useRef([]);
|
||||
|
||||
useEffect(() => {
|
||||
if (odomMsg?.pose?.pose?.position) {
|
||||
trailRef.current.push({
|
||||
x: odomMsg.pose.pose.position.x,
|
||||
y: odomMsg.pose.pose.position.y,
|
||||
ts: Date.now(),
|
||||
});
|
||||
if (trailRef.current.length > 500) trailRef.current.shift();
|
||||
}
|
||||
}, [odomMsg]);
|
||||
|
||||
useEffect(() => {
|
||||
const canvas = canvasRef.current;
|
||||
if (!canvas) return;
|
||||
|
||||
const ctx = canvas.getContext('2d');
|
||||
const W = canvas.width;
|
||||
const H = canvas.height;
|
||||
const cx = W / 2;
|
||||
const cy = H / 2;
|
||||
const scale = 50; // pixels per meter
|
||||
|
||||
// Clear
|
||||
ctx.fillStyle = '#020208';
|
||||
ctx.fillRect(0, 0, W, H);
|
||||
|
||||
// Grid
|
||||
ctx.strokeStyle = 'rgba(6,182,212,0.1)';
|
||||
ctx.lineWidth = 0.5;
|
||||
for (let i = -10; i <= 10; i++) {
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(cx + i * scale, 0);
|
||||
ctx.lineTo(cx + i * scale, H);
|
||||
ctx.stroke();
|
||||
ctx.beginPath();
|
||||
ctx.moveTo(0, cy + i * scale);
|
||||
ctx.lineTo(W, cy + i * scale);
|
||||
ctx.stroke();
|
||||
}
|
||||
|
||||
// Trail
|
||||
if (trailRef.current.length > 1) {
|
||||
ctx.strokeStyle = '#06b6d4';
|
||||
ctx.lineWidth = 1;
|
||||
ctx.beginPath();
|
||||
trailRef.current.forEach((pt, i) => {
|
||||
const x = cx + pt.x * scale;
|
||||
const y = cy - pt.y * scale;
|
||||
i === 0 ? ctx.moveTo(x, y) : ctx.lineTo(x, y);
|
||||
});
|
||||
ctx.stroke();
|
||||
}
|
||||
|
||||
// Robot position
|
||||
if (odomMsg?.pose?.pose?.position) {
|
||||
const x = cx + odomMsg.pose.pose.position.x * scale;
|
||||
const y = cy - odomMsg.pose.pose.position.y * scale;
|
||||
ctx.fillStyle = '#f59e0b';
|
||||
ctx.beginPath();
|
||||
ctx.arc(x, y, 5, 0, 2 * Math.PI);
|
||||
ctx.fill();
|
||||
}
|
||||
}, [odomMsg, trailRef.current.length]);
|
||||
|
||||
return <canvas ref={canvasRef} width={250} height={250} className="bg-gray-950 rounded border border-cyan-950" />;
|
||||
}
|
||||
|
||||
// Battery Widget
|
||||
function BatteryWidget({ batteryData }) {
|
||||
const voltage = batteryData?.voltage ?? 0;
|
||||
const current = batteryData?.current ?? 0;
|
||||
const soc = batteryData?.soc ?? 0;
|
||||
|
||||
let color = '#22c55e';
|
||||
if (soc < 20) color = '#ef4444';
|
||||
else if (soc < 50) color = '#f59e0b';
|
||||
|
||||
return (
|
||||
<div className="bg-gray-950 rounded-lg border border-cyan-950 p-4">
|
||||
<div className="text-xs font-bold text-cyan-700 tracking-widest mb-3">BATTERY</div>
|
||||
<div className="flex justify-between items-center mb-3">
|
||||
<div className="text-3xl font-bold" style={{ color }}>
|
||||
{soc.toFixed(0)}%
|
||||
</div>
|
||||
<div className="text-xs text-gray-500 text-right">
|
||||
<div>{voltage.toFixed(1)}V</div>
|
||||
<div>{current.toFixed(1)}A</div>
|
||||
</div>
|
||||
</div>
|
||||
<div className="w-full h-2 bg-gray-900 rounded overflow-hidden border border-gray-800">
|
||||
<div
|
||||
className="h-full transition-all duration-500"
|
||||
style={{ width: `${soc}%`, background: color }}
|
||||
/>
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
// Motor Widget
|
||||
function MotorWidget({ motorData }) {
|
||||
const left = motorData?.left ?? 0;
|
||||
const right = motorData?.right ?? 0;
|
||||
|
||||
const dutyBar = (norm) => {
|
||||
const pct = Math.abs(norm) * 50;
|
||||
const color = norm > 0 ? '#f97316' : '#3b82f6';
|
||||
const left = norm >= 0 ? '50%' : `${50 - pct}%`;
|
||||
return { pct, color, left };
|
||||
};
|
||||
|
||||
const leftBar = dutyBar(left);
|
||||
const rightBar = dutyBar(right);
|
||||
|
||||
return (
|
||||
<div className="bg-gray-950 rounded-lg border border-cyan-950 p-4">
|
||||
<div className="text-xs font-bold text-cyan-700 tracking-widest mb-3">MOTORS</div>
|
||||
<div className="space-y-2">
|
||||
{['L', 'R'].map((label, idx) => {
|
||||
const val = idx === 0 ? left : right;
|
||||
const bar = idx === 0 ? leftBar : rightBar;
|
||||
return (
|
||||
<div key={label}>
|
||||
<div className="flex justify-between text-xs mb-1">
|
||||
<span className="text-gray-600">{label}:</span>
|
||||
<span className="text-orange-400 font-bold">{(val * 100).toFixed(0)}%</span>
|
||||
</div>
|
||||
<div className="relative h-2 bg-gray-900 rounded border border-gray-800 overflow-hidden">
|
||||
<div className="absolute inset-y-0 left-1/2 w-px bg-gray-700" />
|
||||
<div
|
||||
className="absolute inset-y-0 transition-all duration-100"
|
||||
style={{ left: bar.left, width: `${bar.pct}%`, background: bar.color }}
|
||||
/>
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
})}
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
// System Health Widget
|
||||
function SystemWidget({ sysData }) {
|
||||
const cpuTemp = sysData?.cpuTemp ?? 0;
|
||||
const gpuTemp = sysData?.gpuTemp ?? 0;
|
||||
const ramPct = sysData?.ramPct ?? 0;
|
||||
const diskPct = sysData?.diskPct ?? 0;
|
||||
|
||||
const tempColor = (t) => {
|
||||
if (t > 80) return '#ef4444';
|
||||
if (t > 60) return '#f59e0b';
|
||||
return '#22c55e';
|
||||
};
|
||||
|
||||
return (
|
||||
<div className="bg-gray-950 rounded-lg border border-cyan-950 p-4">
|
||||
<div className="text-xs font-bold text-cyan-700 tracking-widest mb-3">SYSTEM</div>
|
||||
<div className="grid grid-cols-2 gap-3">
|
||||
<div className="text-center">
|
||||
<div className="text-xs text-gray-600">CPU</div>
|
||||
<div className="text-lg font-bold" style={{ color: tempColor(cpuTemp) }}>
|
||||
{cpuTemp.toFixed(0)}°C
|
||||
</div>
|
||||
</div>
|
||||
<div className="text-center">
|
||||
<div className="text-xs text-gray-600">GPU</div>
|
||||
<div className="text-lg font-bold" style={{ color: tempColor(gpuTemp) }}>
|
||||
{gpuTemp.toFixed(0)}°C
|
||||
</div>
|
||||
</div>
|
||||
<div>
|
||||
<div className="text-xs text-gray-600 mb-1">RAM {ramPct.toFixed(0)}%</div>
|
||||
<div className="h-1.5 bg-gray-900 rounded overflow-hidden border border-gray-800">
|
||||
<div
|
||||
className="h-full bg-cyan-500 transition-all duration-500"
|
||||
style={{ width: `${Math.min(ramPct, 100)}%` }}
|
||||
/>
|
||||
</div>
|
||||
</div>
|
||||
<div>
|
||||
<div className="text-xs text-gray-600 mb-1">Disk {diskPct.toFixed(0)}%</div>
|
||||
<div className="h-1.5 bg-gray-900 rounded overflow-hidden border border-gray-800">
|
||||
<div
|
||||
className="h-full bg-amber-500 transition-all duration-500"
|
||||
style={{ width: `${Math.min(diskPct, 100)}%` }}
|
||||
/>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
// Social Status Widget
|
||||
function SocialWidget({ isSpeaking, faceId }) {
|
||||
return (
|
||||
<div className="bg-gray-950 rounded-lg border border-cyan-950 p-4">
|
||||
<div className="text-xs font-bold text-cyan-700 tracking-widest mb-3">SOCIAL</div>
|
||||
<div className="space-y-2">
|
||||
<div className="flex items-center gap-2">
|
||||
<div
|
||||
className={`w-3 h-3 rounded-full ${isSpeaking ? 'bg-green-400 animate-pulse' : 'bg-gray-700'}`}
|
||||
/>
|
||||
<span className="text-xs">
|
||||
{isSpeaking ? 'Speaking' : 'Silent'}
|
||||
</span>
|
||||
</div>
|
||||
<div className="text-xs text-gray-600">
|
||||
Face: <span className="text-gray-400">{faceId || 'none'}</span>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
|
||||
export function OpsDashboard({ subscribe }) {
|
||||
const [imu, setImu] = useState({ roll: 0, pitch: 0, yaw: 0 });
|
||||
const [battery, setBattery] = useState({ voltage: 0, current: 0, soc: 0 });
|
||||
const [motors, setMotors] = useState({ left: 0, right: 0 });
|
||||
const [system, setSystem] = useState({ cpuTemp: 0, gpuTemp: 0, ramPct: 0, diskPct: 0 });
|
||||
const [scan, setScan] = useState(null);
|
||||
const [odom, setOdom] = useState(null);
|
||||
const [social, setSocial] = useState({ isSpeaking: false, faceId: null });
|
||||
|
||||
// IMU subscription
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(QUATERNION_TOPIC, 'sensor_msgs/Imu', (msg) => {
|
||||
const q = msg.orientation;
|
||||
const euler = quatToEuler(q.x, q.y, q.z, q.w);
|
||||
setImu(euler);
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
// Diagnostics subscription (battery, system temps)
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(DIAGNOSTICS_TOPIC, 'diagnostic_msgs/DiagnosticArray', (msg) => {
|
||||
for (const status of msg.status ?? []) {
|
||||
const kv = {};
|
||||
for (const pair of status.values ?? []) kv[pair.key] = pair.value;
|
||||
|
||||
// Battery
|
||||
if (kv.battery_voltage_v !== undefined) {
|
||||
setBattery((prev) => ({
|
||||
...prev,
|
||||
voltage: parseFloat(kv.battery_voltage_v),
|
||||
soc: parseFloat(kv.battery_soc_pct) || 0,
|
||||
current: parseFloat(kv.battery_current_a) || 0,
|
||||
}));
|
||||
}
|
||||
|
||||
// System temps/resources
|
||||
if (kv.cpu_temp_c !== undefined || kv.gpu_temp_c !== undefined) {
|
||||
setSystem((prev) => ({
|
||||
...prev,
|
||||
cpuTemp: parseFloat(kv.cpu_temp_c) || prev.cpuTemp,
|
||||
gpuTemp: parseFloat(kv.gpu_temp_c) || prev.gpuTemp,
|
||||
ramPct: parseFloat(kv.ram_pct) || prev.ramPct,
|
||||
diskPct: parseFloat(kv.disk_pct) || prev.diskPct,
|
||||
}));
|
||||
}
|
||||
}
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
// Balance state subscription (motors)
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(BALANCE_STATE_TOPIC, 'std_msgs/String', (msg) => {
|
||||
try {
|
||||
const state = JSON.parse(msg.data);
|
||||
const cmd = state.motor_cmd ?? 0;
|
||||
const norm = Math.max(-1, Math.min(1, cmd / 1000));
|
||||
setMotors({ left: norm, right: norm });
|
||||
} catch {
|
||||
/* ignore */
|
||||
}
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
// LIDAR subscription
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(SCAN_TOPIC, 'sensor_msgs/LaserScan', (msg) => {
|
||||
setScan(msg);
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
// Odometry subscription
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(ODOM_TOPIC, 'nav_msgs/Odometry', (msg) => {
|
||||
setOdom(msg);
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
// Social speech subscription
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(SOCIAL_SPEECH_TOPIC, 'std_msgs/Bool', (msg) => {
|
||||
setSocial((prev) => ({ ...prev, isSpeaking: msg.data }));
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
// Social face subscription
|
||||
useEffect(() => {
|
||||
const unsub = subscribe(SOCIAL_FACE_TOPIC, 'std_msgs/String', (msg) => {
|
||||
setSocial((prev) => ({ ...prev, faceId: msg.data }));
|
||||
});
|
||||
return unsub;
|
||||
}, [subscribe]);
|
||||
|
||||
return (
|
||||
<div className="flex flex-col h-full gap-4 overflow-y-auto p-2 sm:p-4">
|
||||
{/* Header */}
|
||||
<div className="text-center mb-2">
|
||||
<h2 className="text-lg sm:text-2xl font-bold text-orange-400 tracking-wider">⚡ OPERATIONS DASHBOARD</h2>
|
||||
<p className="text-xs text-gray-600 mt-1">Real-time telemetry • 10Hz critical • 1Hz system</p>
|
||||
</div>
|
||||
|
||||
{/* 3-column responsive grid */}
|
||||
<div className="grid grid-cols-1 md:grid-cols-2 lg:grid-cols-3 gap-4 auto-rows-max">
|
||||
{/* Left column: Critical data */}
|
||||
<BatteryWidget batteryData={battery} />
|
||||
<MotorWidget motorData={motors} />
|
||||
<SocialWidget {...social} />
|
||||
|
||||
{/* Center column: Attitude & maps */}
|
||||
<div className="flex justify-center">
|
||||
<AttitudeGauge roll={imu.roll} pitch={imu.pitch} yaw={imu.yaw} />
|
||||
</div>
|
||||
<div className="flex justify-center">
|
||||
<LidarMap scanMsg={scan} />
|
||||
</div>
|
||||
<SystemWidget sysData={system} />
|
||||
|
||||
{/* Right column: Odometry */}
|
||||
<div className="flex justify-center lg:col-span-1">
|
||||
<OdomMap odomMsg={odom} />
|
||||
</div>
|
||||
</div>
|
||||
|
||||
{/* Footer stats */}
|
||||
<div className="mt-4 grid grid-cols-2 sm:grid-cols-4 gap-2 text-xs text-gray-600 bg-gray-950 border border-cyan-950 rounded p-3">
|
||||
<div>
|
||||
<span className="text-gray-500">Battery</span>
|
||||
<br />
|
||||
<span className="text-green-400 font-bold">{battery.soc.toFixed(0)}% • {battery.voltage.toFixed(1)}V</span>
|
||||
</div>
|
||||
<div>
|
||||
<span className="text-gray-500">Motors</span>
|
||||
<br />
|
||||
<span className="text-orange-400 font-bold">
|
||||
L:{(motors.left * 100).toFixed(0)}% • R:{(motors.right * 100).toFixed(0)}%
|
||||
</span>
|
||||
</div>
|
||||
<div>
|
||||
<span className="text-gray-500">Attitude</span>
|
||||
<br />
|
||||
<span className="text-blue-400 font-bold">R:{imu.roll.toFixed(0)}° Y:{imu.yaw.toFixed(0)}°</span>
|
||||
</div>
|
||||
<div>
|
||||
<span className="text-gray-500">System</span>
|
||||
<br />
|
||||
<span className="text-cyan-400 font-bold">CPU:{system.cpuTemp.toFixed(0)}°C RAM:{system.ramPct.toFixed(0)}%</span>
|
||||
</div>
|
||||
</div>
|
||||
</div>
|
||||
);
|
||||
}
|
||||
Loading…
x
Reference in New Issue
Block a user