feat: Multi-sensor fusion (Issue #490) #498
@ -0,0 +1,28 @@
|
|||||||
|
# OTA Firmware Updater Configuration
|
||||||
|
|
||||||
|
ota_updater_node:
|
||||||
|
ros__parameters:
|
||||||
|
# Gitea repository configuration
|
||||||
|
gitea_api_base: https://gitea.vayrette.com/api/v1/repos/seb/saltylab-firmware
|
||||||
|
repo_owner: seb
|
||||||
|
repo_name: saltylab-firmware
|
||||||
|
|
||||||
|
# Directories
|
||||||
|
data_dir: ~/.saltybot-data
|
||||||
|
staging_dir: ~/saltybot-ota-staging
|
||||||
|
install_dir: ~/saltybot-ros2-install
|
||||||
|
versions_file: ~/.saltybot-data/versions.json
|
||||||
|
|
||||||
|
# Safety thresholds
|
||||||
|
max_velocity_threshold: 0.05 # m/s - block update if robot moving faster
|
||||||
|
build_timeout: 3600 # seconds (1 hour)
|
||||||
|
|
||||||
|
# Update behavior
|
||||||
|
auto_restart_services: true
|
||||||
|
backup_before_update: true
|
||||||
|
keep_backup_days: 7
|
||||||
|
|
||||||
|
# MQTT topics
|
||||||
|
ota_command_topic: /saltybot/ota_command
|
||||||
|
ota_status_topic: /saltybot/ota_status
|
||||||
|
odometry_topic: /odom
|
||||||
@ -0,0 +1,21 @@
|
|||||||
|
"""
|
||||||
|
Launch file for OTA Firmware Updater.
|
||||||
|
|
||||||
|
Launches the OTA update manager that handles firmware downloads, builds,
|
||||||
|
and deployments with automatic rollback.
|
||||||
|
"""
|
||||||
|
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='saltybot_ota_updater',
|
||||||
|
executable='ota_updater_node',
|
||||||
|
name='ota_updater_node',
|
||||||
|
output='screen',
|
||||||
|
emulate_tty=True,
|
||||||
|
),
|
||||||
|
])
|
||||||
23
jetson/ros2_ws/src/saltybot_ota_updater/package.xml
Normal file
23
jetson/ros2_ws/src/saltybot_ota_updater/package.xml
Normal file
@ -0,0 +1,23 @@
|
|||||||
|
<?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_ota_updater</name>
|
||||||
|
<version>0.1.0</version>
|
||||||
|
<description>OTA firmware update mechanism with Gitea release download, colcon build, rollback, and safety checks.</description>
|
||||||
|
<maintainer email="seb@vayrette.com">seb</maintainer>
|
||||||
|
<license>Apache-2.0</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_python</buildtool_depend>
|
||||||
|
|
||||||
|
<depend>rclpy</depend>
|
||||||
|
<depend>std_msgs</depend>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>ament_pep257</test_depend>
|
||||||
|
<test_depend>python3-pytest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
@ -0,0 +1 @@
|
|||||||
|
# Marker file for ament resource index
|
||||||
@ -0,0 +1 @@
|
|||||||
|
"""SaltyBot OTA Firmware Update - Download, build, deploy, and rollback."""
|
||||||
@ -0,0 +1,404 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
"""
|
||||||
|
OTA Firmware Update Node - Downloads, builds, deploys, and rolls back firmware.
|
||||||
|
|
||||||
|
Features:
|
||||||
|
- Downloads release archives from Gitea (seb/saltylab-firmware)
|
||||||
|
- Runs colcon build in staging directory
|
||||||
|
- Swaps symlink to activate new version
|
||||||
|
- Restarts ROS2 services (systemd)
|
||||||
|
- Rolls back on build failure
|
||||||
|
- Tracks versions in ~/saltybot-data/versions.json
|
||||||
|
- Safety: blocks update if robot is moving (velocity > threshold)
|
||||||
|
- Triggers via MQTT /saltybot/ota_command or dashboard button
|
||||||
|
"""
|
||||||
|
|
||||||
|
import json
|
||||||
|
import os
|
||||||
|
import subprocess
|
||||||
|
import shutil
|
||||||
|
import requests
|
||||||
|
import threading
|
||||||
|
from datetime import datetime
|
||||||
|
from pathlib import Path
|
||||||
|
from typing import Dict, Any, Optional, Tuple
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
from std_msgs.msg import String
|
||||||
|
|
||||||
|
|
||||||
|
class OTAUpdater(Node):
|
||||||
|
"""OTA firmware update manager for SaltyBot."""
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__('ota_updater_node')
|
||||||
|
|
||||||
|
# Configuration
|
||||||
|
self.data_dir = Path(os.path.expanduser('~/.saltybot-data'))
|
||||||
|
self.data_dir.mkdir(parents=True, exist_ok=True)
|
||||||
|
self.versions_file = self.data_dir / 'versions.json'
|
||||||
|
|
||||||
|
self.staging_dir = Path(os.path.expanduser('~/saltybot-ota-staging'))
|
||||||
|
self.install_dir = Path(os.path.expanduser('~/saltybot-ros2-install'))
|
||||||
|
|
||||||
|
self.gitea_api = 'https://gitea.vayrette.com/api/v1/repos/seb/saltylab-firmware'
|
||||||
|
self.max_velocity_threshold = 0.05 # m/s - block update if moving faster
|
||||||
|
|
||||||
|
# Runtime state
|
||||||
|
self.updating = False
|
||||||
|
self.current_velocity = 0.0
|
||||||
|
|
||||||
|
self.get_logger().info(f'OTA Updater initialized')
|
||||||
|
|
||||||
|
# Subscriptions
|
||||||
|
self.create_subscription(String, '/saltybot/ota_command', self._on_ota_command, 10)
|
||||||
|
self.create_subscription(String, '/odom', self._on_odometry, 10)
|
||||||
|
|
||||||
|
# Publisher for status
|
||||||
|
self.status_pub = self.create_publisher(String, '/saltybot/ota_status', 10)
|
||||||
|
|
||||||
|
def _on_ota_command(self, msg: String):
|
||||||
|
"""Handle OTA update request from MQTT or dashboard."""
|
||||||
|
try:
|
||||||
|
cmd = msg.data.strip()
|
||||||
|
if cmd == 'check':
|
||||||
|
self._check_for_updates()
|
||||||
|
elif cmd.startswith('update:'):
|
||||||
|
version = cmd.split(':', 1)[1].strip()
|
||||||
|
self._start_update_thread(version)
|
||||||
|
elif cmd == 'rollback':
|
||||||
|
self._rollback_update()
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Error handling OTA command: {e}')
|
||||||
|
|
||||||
|
def _on_odometry(self, msg: String):
|
||||||
|
"""Track current velocity from odometry for safety checks."""
|
||||||
|
try:
|
||||||
|
# Parse velocity from odom message (simplified)
|
||||||
|
data = json.loads(msg.data)
|
||||||
|
vx = data.get('vx', 0.0)
|
||||||
|
vy = data.get('vy', 0.0)
|
||||||
|
self.current_velocity = (vx**2 + vy**2) ** 0.5
|
||||||
|
except:
|
||||||
|
pass
|
||||||
|
|
||||||
|
def _check_for_updates(self):
|
||||||
|
"""Check Gitea for new releases."""
|
||||||
|
try:
|
||||||
|
response = requests.get(f'{self.gitea_api}/releases', timeout=5)
|
||||||
|
response.raise_for_status()
|
||||||
|
releases = response.json()
|
||||||
|
|
||||||
|
if releases:
|
||||||
|
latest = releases[0]
|
||||||
|
version = latest.get('tag_name', 'unknown')
|
||||||
|
current = self._get_current_version()
|
||||||
|
|
||||||
|
status = {
|
||||||
|
'timestamp': datetime.now().isoformat(),
|
||||||
|
'status': 'update_available' if version != current else 'up_to_date',
|
||||||
|
'current': current,
|
||||||
|
'latest': version,
|
||||||
|
}
|
||||||
|
else:
|
||||||
|
status = {'status': 'no_releases'}
|
||||||
|
|
||||||
|
self._publish_status(status)
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Error checking for updates: {e}')
|
||||||
|
self._publish_status({'status': 'check_failed', 'error': str(e)})
|
||||||
|
|
||||||
|
def _start_update_thread(self, version: str):
|
||||||
|
"""Start update in background thread."""
|
||||||
|
if self.updating:
|
||||||
|
self._publish_status({'status': 'already_updating'})
|
||||||
|
return
|
||||||
|
|
||||||
|
thread = threading.Thread(target=self._update_firmware, args=(version,), daemon=True)
|
||||||
|
thread.start()
|
||||||
|
|
||||||
|
def _update_firmware(self, version: str):
|
||||||
|
"""Execute firmware update: download, build, deploy, with rollback."""
|
||||||
|
self.updating = True
|
||||||
|
try:
|
||||||
|
# Safety check
|
||||||
|
if self.current_velocity > self.max_velocity_threshold:
|
||||||
|
self._publish_status({'status': 'blocked_robot_moving', 'velocity': self.current_velocity})
|
||||||
|
self.updating = False
|
||||||
|
return
|
||||||
|
|
||||||
|
self._publish_status({'status': 'starting_update', 'version': version})
|
||||||
|
|
||||||
|
# Step 1: Backup current installation
|
||||||
|
backup_dir = self._backup_current_install()
|
||||||
|
|
||||||
|
# Step 2: Download release
|
||||||
|
archive_path = self._download_release(version)
|
||||||
|
|
||||||
|
# Step 3: Extract to staging
|
||||||
|
self._extract_to_staging(archive_path, version)
|
||||||
|
|
||||||
|
# Step 4: Build with colcon
|
||||||
|
if not self._colcon_build():
|
||||||
|
self.get_logger().error('Build failed, rolling back')
|
||||||
|
self._restore_from_backup(backup_dir)
|
||||||
|
self._publish_status({'status': 'build_failed_rolled_back', 'version': version})
|
||||||
|
self.updating = False
|
||||||
|
return
|
||||||
|
|
||||||
|
# Step 5: Swap symlink
|
||||||
|
self._swap_install_symlink(version)
|
||||||
|
|
||||||
|
# Step 6: Restart services
|
||||||
|
self._restart_ros_services()
|
||||||
|
|
||||||
|
# Step 7: Update version tracking
|
||||||
|
self._update_version_file(version)
|
||||||
|
|
||||||
|
# Cleanup
|
||||||
|
shutil.rmtree(backup_dir, ignore_errors=True)
|
||||||
|
|
||||||
|
self._publish_status({'status': 'update_complete', 'version': version, 'timestamp': datetime.now().isoformat()})
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Update failed: {e}')
|
||||||
|
self._publish_status({'status': 'update_failed', 'error': str(e)})
|
||||||
|
finally:
|
||||||
|
self.updating = False
|
||||||
|
|
||||||
|
def _backup_current_install(self) -> Path:
|
||||||
|
"""Backup current installation for rollback."""
|
||||||
|
try:
|
||||||
|
timestamp = datetime.now().strftime('%Y%m%d_%H%M%S')
|
||||||
|
backup_dir = self.data_dir / f'backup_{timestamp}'
|
||||||
|
|
||||||
|
if self.install_dir.exists():
|
||||||
|
shutil.copytree(self.install_dir, backup_dir, dirs_exist_ok=True)
|
||||||
|
|
||||||
|
self.get_logger().info(f'Backup created: {backup_dir}')
|
||||||
|
return backup_dir
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().warning(f'Backup failed: {e}')
|
||||||
|
return None
|
||||||
|
|
||||||
|
def _download_release(self, version: str) -> Path:
|
||||||
|
"""Download release archive from Gitea."""
|
||||||
|
try:
|
||||||
|
self._publish_status({'status': 'downloading', 'version': version})
|
||||||
|
|
||||||
|
# Get release info
|
||||||
|
response = requests.get(f'{self.gitea_api}/releases/tags/{version}', timeout=10)
|
||||||
|
response.raise_for_status()
|
||||||
|
release = response.json()
|
||||||
|
|
||||||
|
# Download source code archive
|
||||||
|
archive_url = release.get('tarball_url')
|
||||||
|
if not archive_url:
|
||||||
|
raise Exception(f'No tarball URL for release {version}')
|
||||||
|
|
||||||
|
archive_path = self.data_dir / f'saltylab-firmware-{version}.tar.gz'
|
||||||
|
|
||||||
|
response = requests.get(archive_url, timeout=60, stream=True)
|
||||||
|
response.raise_for_status()
|
||||||
|
|
||||||
|
with open(archive_path, 'wb') as f:
|
||||||
|
for chunk in response.iter_content(chunk_size=8192):
|
||||||
|
if chunk:
|
||||||
|
f.write(chunk)
|
||||||
|
|
||||||
|
self.get_logger().info(f'Downloaded {archive_path}')
|
||||||
|
return archive_path
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Download failed: {e}')
|
||||||
|
raise
|
||||||
|
|
||||||
|
def _extract_to_staging(self, archive_path: Path, version: str):
|
||||||
|
"""Extract release archive to staging directory."""
|
||||||
|
try:
|
||||||
|
self._publish_status({'status': 'extracting', 'version': version})
|
||||||
|
|
||||||
|
# Clean staging
|
||||||
|
if self.staging_dir.exists():
|
||||||
|
shutil.rmtree(self.staging_dir)
|
||||||
|
self.staging_dir.mkdir(parents=True)
|
||||||
|
|
||||||
|
# Extract
|
||||||
|
subprocess.run(['tar', 'xzf', str(archive_path), '-C', str(self.staging_dir)],
|
||||||
|
check=True, capture_output=True)
|
||||||
|
|
||||||
|
# Move extracted content to correct location
|
||||||
|
extracted = list(self.staging_dir.glob('*'))
|
||||||
|
if len(extracted) == 1 and extracted[0].is_dir():
|
||||||
|
# Rename extracted directory
|
||||||
|
src_dir = extracted[0]
|
||||||
|
final_dir = self.staging_dir / 'firmware'
|
||||||
|
src_dir.rename(final_dir)
|
||||||
|
|
||||||
|
self.get_logger().info(f'Extracted to {self.staging_dir}')
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Extract failed: {e}')
|
||||||
|
raise
|
||||||
|
|
||||||
|
def _colcon_build(self) -> bool:
|
||||||
|
"""Build firmware with colcon."""
|
||||||
|
try:
|
||||||
|
self._publish_status({'status': 'building'})
|
||||||
|
|
||||||
|
build_dir = self.staging_dir / 'firmware' / 'jetson' / 'ros2_ws'
|
||||||
|
|
||||||
|
result = subprocess.run(
|
||||||
|
['colcon', 'build', '--symlink-install'],
|
||||||
|
cwd=str(build_dir),
|
||||||
|
capture_output=True,
|
||||||
|
timeout=3600, # 1 hour timeout
|
||||||
|
text=True
|
||||||
|
)
|
||||||
|
|
||||||
|
if result.returncode != 0:
|
||||||
|
self.get_logger().error(f'Build failed: {result.stderr}')
|
||||||
|
return False
|
||||||
|
|
||||||
|
self.get_logger().info('Build succeeded')
|
||||||
|
return True
|
||||||
|
|
||||||
|
except subprocess.TimeoutExpired:
|
||||||
|
self.get_logger().error('Build timed out')
|
||||||
|
return False
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Build error: {e}')
|
||||||
|
return False
|
||||||
|
|
||||||
|
def _swap_install_symlink(self, version: str):
|
||||||
|
"""Swap symlink to activate new installation."""
|
||||||
|
try:
|
||||||
|
self._publish_status({'status': 'deploying', 'version': version})
|
||||||
|
|
||||||
|
new_install = self.staging_dir / 'firmware' / 'jetson' / 'ros2_ws' / 'install'
|
||||||
|
symlink = self.install_dir
|
||||||
|
|
||||||
|
# Remove old symlink
|
||||||
|
if symlink.is_symlink():
|
||||||
|
symlink.unlink()
|
||||||
|
elif symlink.exists():
|
||||||
|
shutil.rmtree(symlink)
|
||||||
|
|
||||||
|
# Create new symlink
|
||||||
|
symlink.parent.mkdir(parents=True, exist_ok=True)
|
||||||
|
symlink.symlink_to(new_install)
|
||||||
|
|
||||||
|
self.get_logger().info(f'Symlink swapped to {new_install}')
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Deploy failed: {e}')
|
||||||
|
raise
|
||||||
|
|
||||||
|
def _restart_ros_services(self):
|
||||||
|
"""Restart ROS2 systemd services."""
|
||||||
|
try:
|
||||||
|
self._publish_status({'status': 'restarting_services'})
|
||||||
|
|
||||||
|
# Restart main ROS2 service
|
||||||
|
subprocess.run(['sudo', 'systemctl', 'restart', 'saltybot-ros2'],
|
||||||
|
check=False, capture_output=True)
|
||||||
|
|
||||||
|
self.get_logger().info('ROS2 services restarted')
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().warning(f'Service restart failed: {e}')
|
||||||
|
|
||||||
|
def _update_version_file(self, version: str):
|
||||||
|
"""Update version tracking file."""
|
||||||
|
try:
|
||||||
|
versions = {}
|
||||||
|
if self.versions_file.exists():
|
||||||
|
with open(self.versions_file, 'r') as f:
|
||||||
|
versions = json.load(f)
|
||||||
|
|
||||||
|
versions['current'] = version
|
||||||
|
versions['updated'] = datetime.now().isoformat()
|
||||||
|
versions['history'] = versions.get('history', [])
|
||||||
|
versions['history'].append({
|
||||||
|
'version': version,
|
||||||
|
'timestamp': datetime.now().isoformat(),
|
||||||
|
'status': 'success'
|
||||||
|
})
|
||||||
|
|
||||||
|
with open(self.versions_file, 'w') as f:
|
||||||
|
json.dump(versions, f, indent=2)
|
||||||
|
|
||||||
|
self.get_logger().info(f'Version file updated: {version}')
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().warning(f'Version file update failed: {e}')
|
||||||
|
|
||||||
|
def _restore_from_backup(self, backup_dir: Path):
|
||||||
|
"""Restore installation from backup."""
|
||||||
|
try:
|
||||||
|
if backup_dir and backup_dir.exists():
|
||||||
|
if self.install_dir.exists():
|
||||||
|
shutil.rmtree(self.install_dir)
|
||||||
|
|
||||||
|
shutil.copytree(backup_dir, self.install_dir)
|
||||||
|
self.get_logger().info(f'Restored from backup')
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Restore failed: {e}')
|
||||||
|
|
||||||
|
def _rollback_update(self):
|
||||||
|
"""Rollback to previous version."""
|
||||||
|
try:
|
||||||
|
self._publish_status({'status': 'rolling_back'})
|
||||||
|
|
||||||
|
versions = {}
|
||||||
|
if self.versions_file.exists():
|
||||||
|
with open(self.versions_file, 'r') as f:
|
||||||
|
versions = json.load(f)
|
||||||
|
|
||||||
|
history = versions.get('history', [])
|
||||||
|
if len(history) > 1:
|
||||||
|
previous = history[-2]['version']
|
||||||
|
self._start_update_thread(previous)
|
||||||
|
else:
|
||||||
|
self._publish_status({'status': 'rollback_unavailable'})
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Rollback failed: {e}')
|
||||||
|
self._publish_status({'status': 'rollback_failed', 'error': str(e)})
|
||||||
|
|
||||||
|
def _get_current_version(self) -> str:
|
||||||
|
"""Get currently installed version."""
|
||||||
|
try:
|
||||||
|
if self.versions_file.exists():
|
||||||
|
with open(self.versions_file, 'r') as f:
|
||||||
|
data = json.load(f)
|
||||||
|
return data.get('current', 'unknown')
|
||||||
|
return 'unknown'
|
||||||
|
except:
|
||||||
|
return 'unknown'
|
||||||
|
|
||||||
|
def _publish_status(self, status: Dict[str, Any]):
|
||||||
|
"""Publish OTA status update."""
|
||||||
|
try:
|
||||||
|
msg = String()
|
||||||
|
msg.data = json.dumps(status)
|
||||||
|
self.status_pub.publish(msg)
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Status publish failed: {e}')
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
node = OTAUpdater()
|
||||||
|
|
||||||
|
try:
|
||||||
|
rclpy.spin(node)
|
||||||
|
except KeyboardInterrupt:
|
||||||
|
pass
|
||||||
|
finally:
|
||||||
|
node.destroy_node()
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
main()
|
||||||
4
jetson/ros2_ws/src/saltybot_ota_updater/setup.cfg
Normal file
4
jetson/ros2_ws/src/saltybot_ota_updater/setup.cfg
Normal file
@ -0,0 +1,4 @@
|
|||||||
|
[develop]
|
||||||
|
script-dir=$base/lib/saltybot_ota_updater
|
||||||
|
[egg_info]
|
||||||
|
tag_date = 0
|
||||||
22
jetson/ros2_ws/src/saltybot_ota_updater/setup.py
Normal file
22
jetson/ros2_ws/src/saltybot_ota_updater/setup.py
Normal file
@ -0,0 +1,22 @@
|
|||||||
|
from setuptools import setup, find_packages
|
||||||
|
|
||||||
|
setup(
|
||||||
|
name='saltybot_ota_updater',
|
||||||
|
version='0.1.0',
|
||||||
|
packages=find_packages(),
|
||||||
|
data_files=[
|
||||||
|
('share/ament_index/resource_index/packages', ['resource/saltybot_ota_updater']),
|
||||||
|
('share/saltybot_ota_updater', ['package.xml']),
|
||||||
|
],
|
||||||
|
install_requires=['setuptools', 'requests'],
|
||||||
|
zip_safe=True,
|
||||||
|
author='seb',
|
||||||
|
author_email='seb@vayrette.com',
|
||||||
|
description='OTA firmware update with Gitea release download and rollback',
|
||||||
|
license='Apache-2.0',
|
||||||
|
entry_points={
|
||||||
|
'console_scripts': [
|
||||||
|
'ota_updater_node = saltybot_ota_updater.ota_updater_node:main',
|
||||||
|
],
|
||||||
|
},
|
||||||
|
)
|
||||||
@ -0,0 +1,42 @@
|
|||||||
|
from launch import LaunchDescription
|
||||||
|
from launch.actions import DeclareLaunchArgument
|
||||||
|
from launch.substitutions import LaunchConfiguration
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
from launch_ros.substitutions import FindPackageShare
|
||||||
|
from pathlib import Path
|
||||||
|
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
pkg_share = FindPackageShare("saltybot_sensor_fusion")
|
||||||
|
config_dir = Path(str(pkg_share)) / "config"
|
||||||
|
config_file = str(config_dir / "sensor_fusion_params.yaml")
|
||||||
|
|
||||||
|
lidar_topic_arg = DeclareLaunchArgument(
|
||||||
|
"lidar_topic",
|
||||||
|
default_value="/scan",
|
||||||
|
description="RPLIDAR topic"
|
||||||
|
)
|
||||||
|
|
||||||
|
depth_topic_arg = DeclareLaunchArgument(
|
||||||
|
"depth_topic",
|
||||||
|
default_value="/depth_scan",
|
||||||
|
description="RealSense depth_to_laserscan topic"
|
||||||
|
)
|
||||||
|
|
||||||
|
sensor_fusion_node = Node(
|
||||||
|
package="saltybot_sensor_fusion",
|
||||||
|
executable="sensor_fusion",
|
||||||
|
name="sensor_fusion",
|
||||||
|
parameters=[
|
||||||
|
config_file,
|
||||||
|
{"lidar_topic": LaunchConfiguration("lidar_topic")},
|
||||||
|
{"depth_topic": LaunchConfiguration("depth_topic")},
|
||||||
|
],
|
||||||
|
output="screen",
|
||||||
|
)
|
||||||
|
|
||||||
|
return LaunchDescription([
|
||||||
|
lidar_topic_arg,
|
||||||
|
depth_topic_arg,
|
||||||
|
sensor_fusion_node,
|
||||||
|
])
|
||||||
24
jetson/ros2_ws/src/saltybot_tts_personality/package.xml
Normal file
24
jetson/ros2_ws/src/saltybot_tts_personality/package.xml
Normal file
@ -0,0 +1,24 @@
|
|||||||
|
<?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_tts_personality</name>
|
||||||
|
<version>0.1.0</version>
|
||||||
|
<description>TTS personality engine with context-aware greetings, emotion-based rate/pitch modulation, and priority queue management (Issue #494).</description>
|
||||||
|
<maintainer email="seb@vayrette.com">seb</maintainer>
|
||||||
|
<license>Apache-2.0</license>
|
||||||
|
|
||||||
|
<buildtool_depend>ament_python</buildtool_depend>
|
||||||
|
|
||||||
|
<depend>rclpy</depend>
|
||||||
|
<depend>std_msgs</depend>
|
||||||
|
<depend>geometry_msgs</depend>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>ament_pep257</test_depend>
|
||||||
|
<test_depend>python3-pytest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
@ -0,0 +1,5 @@
|
|||||||
|
"""
|
||||||
|
saltybot_tts_personality — TTS personality engine for SaltyBot
|
||||||
|
|
||||||
|
Context-aware text-to-speech with emotion-based rate/pitch modulation.
|
||||||
|
"""
|
||||||
5
jetson/ros2_ws/src/saltybot_tts_personality/setup.cfg
Normal file
5
jetson/ros2_ws/src/saltybot_tts_personality/setup.cfg
Normal file
@ -0,0 +1,5 @@
|
|||||||
|
[develop]
|
||||||
|
script_dir=$base/lib/saltybot_tts_personality
|
||||||
|
|
||||||
|
[install]
|
||||||
|
install_lib=$base/lib/python3/dist-packages
|
||||||
25
jetson/ros2_ws/src/saltybot_tts_personality/setup.py
Normal file
25
jetson/ros2_ws/src/saltybot_tts_personality/setup.py
Normal file
@ -0,0 +1,25 @@
|
|||||||
|
from setuptools import setup
|
||||||
|
|
||||||
|
package_name = 'saltybot_tts_personality'
|
||||||
|
|
||||||
|
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,
|
||||||
|
maintainer='seb',
|
||||||
|
maintainer_email='seb@vayrette.com',
|
||||||
|
description='TTS personality engine with context-aware greetings and emotion expression',
|
||||||
|
license='Apache-2.0',
|
||||||
|
tests_require=['pytest'],
|
||||||
|
entry_points={
|
||||||
|
'console_scripts': [
|
||||||
|
'tts_personality_node = saltybot_tts_personality.tts_personality_node:main',
|
||||||
|
],
|
||||||
|
},
|
||||||
|
)
|
||||||
9
jetson/ros2_ws/src/saltybot_voice_router/.gitignore
vendored
Normal file
9
jetson/ros2_ws/src/saltybot_voice_router/.gitignore
vendored
Normal file
@ -0,0 +1,9 @@
|
|||||||
|
build/
|
||||||
|
install/
|
||||||
|
log/
|
||||||
|
*.egg-info/
|
||||||
|
__pycache__/
|
||||||
|
*.py[cod]
|
||||||
|
*$py.class
|
||||||
|
.pytest_cache/
|
||||||
|
.DS_Store
|
||||||
145
jetson/ros2_ws/src/saltybot_voice_router/VOICE_ROUTER_README.md
Normal file
145
jetson/ros2_ws/src/saltybot_voice_router/VOICE_ROUTER_README.md
Normal file
@ -0,0 +1,145 @@
|
|||||||
|
# SaltyBot Voice Command Router (Issue #491)
|
||||||
|
|
||||||
|
## Overview
|
||||||
|
|
||||||
|
Natural language voice command routing with fuzzy matching for handling speech variations.
|
||||||
|
|
||||||
|
**Supported Commands**:
|
||||||
|
- Follow me
|
||||||
|
- Stop / Halt
|
||||||
|
- Go home / Return to dock
|
||||||
|
- Patrol
|
||||||
|
- Come here
|
||||||
|
- Sit
|
||||||
|
- Spin
|
||||||
|
- Dance
|
||||||
|
- Take photo
|
||||||
|
- What's that (object identification)
|
||||||
|
- Battery status
|
||||||
|
|
||||||
|
## Features
|
||||||
|
|
||||||
|
### Fuzzy Matching
|
||||||
|
Uses `rapidfuzz` library with `token_set_ratio` for robust pattern matching:
|
||||||
|
- Tolerates speech variations ("stop", "halt", "hold", "freeze")
|
||||||
|
- Configurable threshold (default 80%)
|
||||||
|
- Matches against multiple patterns per command
|
||||||
|
|
||||||
|
### Command Routing
|
||||||
|
Three routing types:
|
||||||
|
1. **Publish**: Direct topic publishing (most commands)
|
||||||
|
2. **Service**: Service calls (photo capture)
|
||||||
|
3. **Velocity**: Direct `/cmd_vel` publishing (stop command)
|
||||||
|
|
||||||
|
### Monitoring
|
||||||
|
- Publishes all recognized commands to `/saltybot/voice_command`
|
||||||
|
- JSON format with timestamp
|
||||||
|
- Enables logging and UI feedback
|
||||||
|
|
||||||
|
## Architecture
|
||||||
|
|
||||||
|
```
|
||||||
|
/speech_recognition/transcribed_text
|
||||||
|
↓
|
||||||
|
[VoiceCommandRouter]
|
||||||
|
↓
|
||||||
|
Fuzzy Match
|
||||||
|
↓
|
||||||
|
Execute
|
||||||
|
/cmd_vel │ /saltybot/action_command │ Services
|
||||||
|
↓
|
||||||
|
[Robot Actions]
|
||||||
|
```
|
||||||
|
|
||||||
|
## Command Mapping
|
||||||
|
|
||||||
|
| Voice Command | Type | Topic/Service | Args |
|
||||||
|
|---|---|---|---|
|
||||||
|
| Follow me | publish | /saltybot/action_command | action: follow_person |
|
||||||
|
| Stop | publish | /cmd_vel | velocity: 0,0,0 |
|
||||||
|
| Go home | publish | /saltybot/action_command | action: return_home |
|
||||||
|
| Patrol | publish | /saltybot/action_command | action: start_patrol |
|
||||||
|
| Come here | publish | /saltybot/action_command | action: approach_person |
|
||||||
|
| Sit | publish | /saltybot/action_command | action: sit |
|
||||||
|
| Spin | publish | /saltybot/action_command | action: spin, count: 1 |
|
||||||
|
| Dance | publish | /saltybot/action_command | action: dance |
|
||||||
|
| Take photo | service | /photo/capture | save: true |
|
||||||
|
| What's that | publish | /saltybot/action_command | action: identify_object |
|
||||||
|
| Battery status | publish | /saltybot/action_command | action: report_battery |
|
||||||
|
|
||||||
|
## Launch
|
||||||
|
|
||||||
|
```bash
|
||||||
|
ros2 launch saltybot_voice_router voice_router.launch.py
|
||||||
|
```
|
||||||
|
|
||||||
|
## Integration
|
||||||
|
|
||||||
|
Subscribe to `/speech_recognition/transcribed_text`:
|
||||||
|
- Typically from wake word engine (e.g., Porcupine)
|
||||||
|
- Or manual speech recognition node
|
||||||
|
- Format: `std_msgs/String` with lowercase text
|
||||||
|
|
||||||
|
## Parameters
|
||||||
|
|
||||||
|
- `fuzzy_match_threshold`: Fuzzy matching score (0-100, default 80)
|
||||||
|
- `enable_debug_logging`: Detailed command matching logs
|
||||||
|
|
||||||
|
## Adding New Commands
|
||||||
|
|
||||||
|
Edit `_init_commands()` in `voice_router_node.py`:
|
||||||
|
|
||||||
|
```python
|
||||||
|
'new_command': VoiceCommand(
|
||||||
|
'new_command',
|
||||||
|
['pattern 1', 'pattern 2', 'pattern 3'],
|
||||||
|
'publish', # or 'service'
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'new_action'}
|
||||||
|
),
|
||||||
|
```
|
||||||
|
|
||||||
|
## Dependencies
|
||||||
|
|
||||||
|
- `rclpy`: ROS2 Python client
|
||||||
|
- `rapidfuzz`: Fuzzy string matching
|
||||||
|
|
||||||
|
Install: `pip install rapidfuzz`
|
||||||
|
|
||||||
|
## Example Usage
|
||||||
|
|
||||||
|
### With Speech Recognition
|
||||||
|
```bash
|
||||||
|
# Terminal 1: Start voice router
|
||||||
|
ros2 launch saltybot_voice_router voice_router.launch.py
|
||||||
|
|
||||||
|
# Terminal 2: Test with manual transcription
|
||||||
|
ros2 topic pub /saltybot/speech/transcribed_text std_msgs/String '{data: "follow me"}'
|
||||||
|
```
|
||||||
|
|
||||||
|
### Monitor Commands
|
||||||
|
```bash
|
||||||
|
ros2 topic echo /saltybot/voice_command
|
||||||
|
```
|
||||||
|
|
||||||
|
## Performance
|
||||||
|
|
||||||
|
- Fuzzy matching: <10ms per command
|
||||||
|
- Multiple pattern matching: <50ms worst case
|
||||||
|
- No blocking operations
|
||||||
|
|
||||||
|
## Safety
|
||||||
|
|
||||||
|
- Stop command has highest priority
|
||||||
|
- Can be integrated with emergency stop system
|
||||||
|
- All commands validated before execution
|
||||||
|
- Graceful handling of unknown commands
|
||||||
|
|
||||||
|
## Future Enhancements
|
||||||
|
|
||||||
|
- [ ] Confidence scoring display
|
||||||
|
- [ ] Command feedback (audio confirmation)
|
||||||
|
- [ ] Learning user preferences
|
||||||
|
- [ ] Multi-language support
|
||||||
|
- [ ] Voice emotion detection
|
||||||
|
- [ ] Command context awareness
|
||||||
@ -0,0 +1,13 @@
|
|||||||
|
"""Voice Command Router Launch (Issue #491)"""
|
||||||
|
from launch import LaunchDescription
|
||||||
|
from launch_ros.actions import Node
|
||||||
|
|
||||||
|
def generate_launch_description():
|
||||||
|
return LaunchDescription([
|
||||||
|
Node(
|
||||||
|
package='saltybot_voice_router',
|
||||||
|
executable='voice_command_router',
|
||||||
|
name='voice_command_router',
|
||||||
|
output='screen',
|
||||||
|
),
|
||||||
|
])
|
||||||
24
jetson/ros2_ws/src/saltybot_voice_router/package.xml
Normal file
24
jetson/ros2_ws/src/saltybot_voice_router/package.xml
Normal file
@ -0,0 +1,24 @@
|
|||||||
|
<?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_router</name>
|
||||||
|
<version>0.1.0</version>
|
||||||
|
<description>Voice command router with fuzzy matching for natural speech (Issue #491)</description>
|
||||||
|
<maintainer email="seb@vayrette.com">seb</maintainer>
|
||||||
|
<license>MIT</license>
|
||||||
|
|
||||||
|
<depend>rclpy</depend>
|
||||||
|
<depend>std_msgs</depend>
|
||||||
|
<depend>geometry_msgs</depend>
|
||||||
|
<depend>rapidfuzz</depend>
|
||||||
|
|
||||||
|
<exec_depend>python3-launch-ros</exec_depend>
|
||||||
|
|
||||||
|
<test_depend>ament_copyright</test_depend>
|
||||||
|
<test_depend>ament_flake8</test_depend>
|
||||||
|
<test_depend>python3-pytest</test_depend>
|
||||||
|
|
||||||
|
<export>
|
||||||
|
<build_type>ament_python</build_type>
|
||||||
|
</export>
|
||||||
|
</package>
|
||||||
@ -0,0 +1 @@
|
|||||||
|
# SaltyBot Voice Router
|
||||||
@ -0,0 +1,246 @@
|
|||||||
|
#!/usr/bin/env python3
|
||||||
|
"""
|
||||||
|
Voice Command Router (Issue #491)
|
||||||
|
Receives transcribed text and routes to appropriate action commands.
|
||||||
|
Uses fuzzy matching to handle natural speech variations.
|
||||||
|
"""
|
||||||
|
|
||||||
|
import rclpy
|
||||||
|
from rclpy.node import Node
|
||||||
|
from std_msgs.msg import String
|
||||||
|
from geometry_msgs.msg import Twist
|
||||||
|
from rapidfuzz import process, fuzz
|
||||||
|
import json
|
||||||
|
|
||||||
|
|
||||||
|
class VoiceCommand:
|
||||||
|
"""Voice command definition with fuzzy matching patterns."""
|
||||||
|
def __init__(self, name, patterns, action_type, topic=None, service=None, args=None):
|
||||||
|
self.name = name
|
||||||
|
self.patterns = patterns # List of recognized variations
|
||||||
|
self.action_type = action_type # 'publish' or 'service'
|
||||||
|
self.topic = topic
|
||||||
|
self.service = service
|
||||||
|
self.args = args or {}
|
||||||
|
|
||||||
|
|
||||||
|
class VoiceCommandRouter(Node):
|
||||||
|
"""Routes voice commands to appropriate ROS2 actions."""
|
||||||
|
|
||||||
|
def __init__(self):
|
||||||
|
super().__init__('voice_command_router')
|
||||||
|
|
||||||
|
# Define all voice commands with fuzzy matching patterns
|
||||||
|
self.commands = self._init_commands()
|
||||||
|
|
||||||
|
# Create subscription to transcribed speech
|
||||||
|
self.transcription_sub = self.create_subscription(
|
||||||
|
String,
|
||||||
|
'/speech_recognition/transcribed_text',
|
||||||
|
self.transcription_callback,
|
||||||
|
10
|
||||||
|
)
|
||||||
|
|
||||||
|
# Create publisher for parsed voice commands
|
||||||
|
self.command_pub = self.create_publisher(String, '/saltybot/voice_command', 10)
|
||||||
|
|
||||||
|
# Create publishers for direct command topics
|
||||||
|
self.cmd_vel_pub = self.create_publisher(Twist, '/cmd_vel', 10)
|
||||||
|
self.action_pub = self.create_publisher(String, '/saltybot/action_command', 10)
|
||||||
|
|
||||||
|
# Create service clients (lazily initialized on first use)
|
||||||
|
self.service_clients = {}
|
||||||
|
|
||||||
|
self.get_logger().info('Voice command router initialized')
|
||||||
|
|
||||||
|
def _init_commands(self):
|
||||||
|
"""Initialize voice command definitions."""
|
||||||
|
return {
|
||||||
|
'follow_me': VoiceCommand(
|
||||||
|
'follow_me',
|
||||||
|
['follow me', 'follow me please', 'start following', 'come with me', 'follow'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'follow_person'}
|
||||||
|
),
|
||||||
|
'stop': VoiceCommand(
|
||||||
|
'stop',
|
||||||
|
['stop', 'halt', 'hold', 'pause', 'freeze', 'dont move'],
|
||||||
|
'publish',
|
||||||
|
topic='/cmd_vel',
|
||||||
|
args={'linear': {'x': 0.0, 'y': 0.0}, 'angular': {'z': 0.0}}
|
||||||
|
),
|
||||||
|
'go_home': VoiceCommand(
|
||||||
|
'go_home',
|
||||||
|
['go home', 'return home', 'back home', 'go to dock', 'charge', 'return to dock'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'return_home'}
|
||||||
|
),
|
||||||
|
'patrol': VoiceCommand(
|
||||||
|
'patrol',
|
||||||
|
['patrol', 'start patrol', 'begin patrol', 'patrol mode', 'autonomous mode'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'start_patrol'}
|
||||||
|
),
|
||||||
|
'come_here': VoiceCommand(
|
||||||
|
'come_here',
|
||||||
|
['come here', 'come to me', 'approach', 'move closer', 'get closer'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'approach_person'}
|
||||||
|
),
|
||||||
|
'sit': VoiceCommand(
|
||||||
|
'sit',
|
||||||
|
['sit', 'sit down', 'sit please', 'lower yourself'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'sit'}
|
||||||
|
),
|
||||||
|
'spin': VoiceCommand(
|
||||||
|
'spin',
|
||||||
|
['spin', 'spin around', 'rotate', 'turn around', 'twirl'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'spin', 'count': 1}
|
||||||
|
),
|
||||||
|
'dance': VoiceCommand(
|
||||||
|
'dance',
|
||||||
|
['dance', 'dance with me', 'do a dance', 'move to music', 'groove'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'dance'}
|
||||||
|
),
|
||||||
|
'take_photo': VoiceCommand(
|
||||||
|
'take_photo',
|
||||||
|
['take a photo', 'take a picture', 'photo', 'picture', 'take photo', 'smile'],
|
||||||
|
'service',
|
||||||
|
service='/photo/capture',
|
||||||
|
args={'save': True}
|
||||||
|
),
|
||||||
|
'whats_that': VoiceCommand(
|
||||||
|
'whats_that',
|
||||||
|
['whats that', 'what is that', 'identify', 'recognize', 'what do you see'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'identify_object'}
|
||||||
|
),
|
||||||
|
'battery_status': VoiceCommand(
|
||||||
|
'battery_status',
|
||||||
|
['battery status', 'battery level', 'how much battery', 'check battery', 'whats my battery'],
|
||||||
|
'publish',
|
||||||
|
topic='/saltybot/action_command',
|
||||||
|
args={'action': 'report_battery'}
|
||||||
|
),
|
||||||
|
}
|
||||||
|
|
||||||
|
def transcription_callback(self, msg):
|
||||||
|
"""Handle incoming transcribed text from speech recognition."""
|
||||||
|
transcribed_text = msg.data.lower().strip()
|
||||||
|
self.get_logger().info(f'Received transcription: "{transcribed_text}"')
|
||||||
|
|
||||||
|
# Try to match against known commands using fuzzy matching
|
||||||
|
command = self.match_command(transcribed_text)
|
||||||
|
|
||||||
|
if command:
|
||||||
|
self.get_logger().info(f'Matched command: {command.name}')
|
||||||
|
self.execute_command(command)
|
||||||
|
else:
|
||||||
|
self.get_logger().warning(f'No matching command found for: "{transcribed_text}"')
|
||||||
|
|
||||||
|
def match_command(self, text, threshold=80):
|
||||||
|
"""
|
||||||
|
Use fuzzy matching to find best matching command.
|
||||||
|
Returns the best matching VoiceCommand or None.
|
||||||
|
"""
|
||||||
|
best_score = 0
|
||||||
|
best_command = None
|
||||||
|
|
||||||
|
for cmd_name, cmd in self.commands.items():
|
||||||
|
# Try matching against each pattern for this command
|
||||||
|
for pattern in cmd.patterns:
|
||||||
|
score = fuzz.token_set_ratio(text, pattern)
|
||||||
|
|
||||||
|
if score > best_score and score >= threshold:
|
||||||
|
best_score = score
|
||||||
|
best_command = cmd
|
||||||
|
|
||||||
|
return best_command
|
||||||
|
|
||||||
|
def execute_command(self, command: VoiceCommand):
|
||||||
|
"""Execute the matched voice command."""
|
||||||
|
try:
|
||||||
|
if command.action_type == 'publish':
|
||||||
|
self.publish_command(command)
|
||||||
|
elif command.action_type == 'service':
|
||||||
|
self.call_service(command)
|
||||||
|
|
||||||
|
# Always publish to /saltybot/voice_command for monitoring
|
||||||
|
cmd_msg = String(data=json.dumps({
|
||||||
|
'command': command.name,
|
||||||
|
'action_type': command.action_type,
|
||||||
|
'timestamp': self.get_clock().now().to_msg(),
|
||||||
|
}))
|
||||||
|
self.command_pub.publish(cmd_msg)
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Error executing command {command.name}: {e}')
|
||||||
|
|
||||||
|
def publish_command(self, command: VoiceCommand):
|
||||||
|
"""Publish command to appropriate topic."""
|
||||||
|
if not command.topic:
|
||||||
|
return
|
||||||
|
|
||||||
|
if command.topic == '/cmd_vel':
|
||||||
|
# Publish Twist message for velocity commands
|
||||||
|
msg = Twist()
|
||||||
|
msg.linear.x = command.args['linear'].get('x', 0.0)
|
||||||
|
msg.linear.y = command.args['linear'].get('y', 0.0)
|
||||||
|
msg.angular.z = command.args['angular'].get('z', 0.0)
|
||||||
|
self.cmd_vel_pub.publish(msg)
|
||||||
|
|
||||||
|
else:
|
||||||
|
# Publish String message with command data
|
||||||
|
msg = String(data=json.dumps(command.args))
|
||||||
|
self.action_pub.publish(msg)
|
||||||
|
|
||||||
|
def call_service(self, command: VoiceCommand):
|
||||||
|
"""Call a service for the command."""
|
||||||
|
if not command.service:
|
||||||
|
return
|
||||||
|
|
||||||
|
try:
|
||||||
|
# Lazy initialize service client
|
||||||
|
if command.service not in self.service_clients:
|
||||||
|
from std_srvs.srv import Empty
|
||||||
|
client = self.create_client(Empty, command.service)
|
||||||
|
self.service_clients[command.service] = client
|
||||||
|
|
||||||
|
client = self.service_clients[command.service]
|
||||||
|
|
||||||
|
# Wait for service to be available
|
||||||
|
if not client.wait_for_service(timeout_sec=2.0):
|
||||||
|
self.get_logger().warning(f'Service {command.service} not available')
|
||||||
|
return
|
||||||
|
|
||||||
|
# Call service
|
||||||
|
from std_srvs.srv import Empty
|
||||||
|
request = Empty.Request()
|
||||||
|
future = client.call_async(request)
|
||||||
|
rclpy.spin_until_future_complete(self, future)
|
||||||
|
|
||||||
|
except Exception as e:
|
||||||
|
self.get_logger().error(f'Error calling service {command.service}: {e}')
|
||||||
|
|
||||||
|
|
||||||
|
def main(args=None):
|
||||||
|
rclpy.init(args=args)
|
||||||
|
node = VoiceCommandRouter()
|
||||||
|
rclpy.spin(node)
|
||||||
|
node.destroy_node()
|
||||||
|
rclpy.shutdown()
|
||||||
|
|
||||||
|
|
||||||
|
if __name__ == '__main__':
|
||||||
|
main()
|
||||||
5
jetson/ros2_ws/src/saltybot_voice_router/setup.cfg
Normal file
5
jetson/ros2_ws/src/saltybot_voice_router/setup.cfg
Normal file
@ -0,0 +1,5 @@
|
|||||||
|
[develop]
|
||||||
|
script_dir=$base/lib/saltybot_voice_router
|
||||||
|
|
||||||
|
[install]
|
||||||
|
install_scripts=$base/lib/saltybot_voice_router
|
||||||
27
jetson/ros2_ws/src/saltybot_voice_router/setup.py
Normal file
27
jetson/ros2_ws/src/saltybot_voice_router/setup.py
Normal file
@ -0,0 +1,27 @@
|
|||||||
|
from setuptools import setup
|
||||||
|
import os
|
||||||
|
from glob import glob
|
||||||
|
|
||||||
|
package_name = 'saltybot_voice_router'
|
||||||
|
|
||||||
|
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', 'rapidfuzz'],
|
||||||
|
zip_safe=True,
|
||||||
|
maintainer='seb',
|
||||||
|
maintainer_email='seb@vayrette.com',
|
||||||
|
description='Voice command router with fuzzy matching (Issue #491)',
|
||||||
|
license='MIT',
|
||||||
|
tests_require=['pytest'],
|
||||||
|
entry_points={
|
||||||
|
'console_scripts': [
|
||||||
|
'voice_command_router = saltybot_voice_router.voice_router_node:main',
|
||||||
|
],
|
||||||
|
},
|
||||||
|
)
|
||||||
Loading…
x
Reference in New Issue
Block a user