| |
| """ |
| Skynet Sidecar Application |
| |
| A lightweight Python application that runs alongside ROS2 components to: |
| 1. Register the component with Skynet |
| 2. Send periodic heartbeats |
| 3. Poll for and execute commands |
| 4. Report command status back to Skynet |
| 5. Control ROS2 services via supervisord |
| """ |
|
|
| import asyncio |
| import logging |
| import sys |
| import time |
| import subprocess |
| import os |
| from dataclasses import dataclass |
| from typing import Dict, List, Any |
| from enum import Enum |
|
|
| import requests |
| import rclpy |
| from rclpy.node import Node |
| from rclpy.parameter import Parameter |
|
|
|
|
| class ComponentType(Enum): |
| CONTROL = "control" |
| DATA = "data" |
| DATA_CAPTURE = "data_capture" |
| EMBODIMENT = "embodiment" |
| ORCHESTRATION = "orchestration" |
| UNKNOWN = "unknown" |
|
|
|
|
| class ComponentStatus(Enum): |
| ONLINE = "online" |
| OFFLINE = "offline" |
| STARTING = "starting" |
| ERROR = "error" |
| MAINTENANCE = "maintenance" |
|
|
|
|
| class CommandStatus(Enum): |
| PENDING = "PENDING" |
| EXECUTING = "EXECUTING" |
| COMPLETED = "COMPLETED" |
| FAILED = "FAILED" |
| CANCELLED = "CANCELLED" |
|
|
|
|
| @dataclass |
| class ComponentConfig: |
| """Configuration for the ROS2 component being managed by this sidecar""" |
| id: str |
| name: str |
| type: ComponentType |
| description: str = "" |
| host: str = "localhost" |
| port: int = 8080 |
| endpoint: str = "" |
| ros_domain_id: int = 0 |
| published_topics: List[str] = None |
| subscribed_topics: List[str] = None |
| version: str = "1.0.0" |
| metadata: Dict[str, Any] = None |
|
|
| def __post_init__(self): |
| if self.published_topics is None: |
| self.published_topics = [] |
| if self.subscribed_topics is None: |
| self.subscribed_topics = [] |
| if self.metadata is None: |
| self.metadata = {} |
|
|
|
|
| @dataclass |
| class SkynetConfig: |
| """Configuration for Skynet server connection""" |
| base_url: str = "http://localhost:8080" |
| heartbeat_interval: int = 30 |
| command_poll_interval: int = 5 |
| timeout: int = 10 |
| max_retries: int = 3 |
|
|
|
|
| class SidecarApp: |
| """Main sidecar application that manages communication between ROS2 component and Skynet""" |
|
|
| def __init__(self): |
| self.running = False |
| self.skynet_connected = False |
| self.session = requests.Session() |
| self.session.headers.update({'Content-Type': 'application/json'}) |
|
|
| |
| self.ros2_processes: Dict[str, subprocess.Popen] = {} |
|
|
| |
| logging.basicConfig( |
| level=logging.INFO, |
| format='%(asctime)s - %(name)s - %(levelname)s - %(message)s', |
| handlers=[ |
| logging.StreamHandler(), |
| logging.FileHandler('/app/logs/sidecar.log') |
| ] |
| ) |
| self.logger = logging.getLogger(__name__) |
|
|
| |
| self._load_config() |
|
|
| |
| self.ros2_env = os.environ.copy() |
| self.ros2_env.update({ |
| 'ROS_DOMAIN_ID': str(os.getenv('ROS_DOMAIN_ID', '0')), |
| 'RMW_IMPLEMENTATION': os.getenv('RMW_IMPLEMENTATION', 'rmw_cyclonedx_cpp'), |
| 'LD_LIBRARY_PATH': '/opt/ros/humble/lib:' + self.ros2_env.get('LD_LIBRARY_PATH', ''), |
| 'PYTHONPATH': '/opt/ros/humble/lib/python3.10/site-packages:' + self.ros2_env.get('PYTHONPATH', ''), |
| 'PATH': '/opt/ros/humble/bin:' + self.ros2_env.get('PATH', ''), |
| }) |
|
|
| def _load_config(self): |
| """Load configuration from environment variables""" |
| try: |
| |
| self.component_config = ComponentConfig( |
| id=os.getenv('COMPONENT_ID', 'unknown-component'), |
| name=os.getenv('COMPONENT_NAME', 'Unknown Component'), |
| type=ComponentType(os.getenv('COMPONENT_TYPE', 'unknown')), |
| description=os.getenv('COMPONENT_DESCRIPTION', ''), |
| host=os.getenv('COMPONENT_HOST', 'localhost'), |
| port=int(os.getenv('COMPONENT_PORT', '8080')), |
| endpoint=os.getenv('COMPONENT_ENDPOINT', ''), |
| ros_domain_id=int(os.getenv('ROS_DOMAIN_ID', '0')), |
| published_topics=os.getenv('COMPONENT_PUBLISHED_TOPICS', '').split(',') if os.getenv('COMPONENT_PUBLISHED_TOPICS') else [], |
| subscribed_topics=os.getenv('COMPONENT_SUBSCRIBED_TOPICS', '').split(',') if os.getenv('COMPONENT_SUBSCRIBED_TOPICS') else [], |
| version=os.getenv('COMPONENT_VERSION', '1.0.0'), |
| metadata={} |
| ) |
|
|
| |
| self.skynet_config = SkynetConfig( |
| base_url=os.getenv('SKYNET_BASE_URL', 'http://localhost:8080'), |
| heartbeat_interval=int(os.getenv('HEARTBEAT_INTERVAL', '30')), |
| command_poll_interval=int(os.getenv('COMMAND_POLL_INTERVAL', '5')), |
| timeout=int(os.getenv('SKYNET_TIMEOUT', '10')), |
| max_retries=int(os.getenv('SKYNET_MAX_RETRIES', '3')) |
| ) |
|
|
| self.logger.info(f"Loaded configuration for component: {self.component_config.name}") |
|
|
| except Exception as e: |
| self.logger.error(f"Error loading configuration from environment variables: {e}") |
| sys.exit(1) |
|
|
| def _signal_handler(self, signum, frame): |
| """Handle shutdown signals gracefully""" |
| self.logger.info(f"Received signal {signum}, shutting down gracefully...") |
| self.running = False |
|
|
| async def start(self): |
| """Start the sidecar application""" |
| self.logger.info("Starting Skynet Sidecar Application") |
|
|
| |
| try: |
| rclpy.init() |
| |
| sanitized_id = self.component_config.id.replace('-', '_').replace(' ', '_') |
| self.ros_node = Node(f"sidecar_{sanitized_id}") |
| self.logger.info("ROS2 node initialized") |
| except Exception as e: |
| self.logger.error(f"Failed to initialize ROS2: {e}") |
| return |
|
|
| self.running = True |
|
|
| tasks = [ |
| asyncio.create_task(self._ros_spin_loop()), |
| asyncio.create_task(self._skynet_connection_loop()) |
| ] |
|
|
| try: |
| await asyncio.gather(*tasks) |
| except Exception as e: |
| self.logger.error(f"Error in main loop: {e}") |
| finally: |
| await self._shutdown() |
|
|
| async def _skynet_connection_loop(self): |
| """Manage Skynet connection, registration, and related tasks""" |
| heartbeat_task = None |
| command_poll_task = None |
| |
| while self.running: |
| try: |
| if not self.skynet_connected: |
| |
| if await self._register_with_skynet(): |
| self.skynet_connected = True |
| self.logger.info("Successfully connected to Skynet - enabling Skynet features") |
| |
| |
| heartbeat_task = asyncio.create_task(self._heartbeat_loop()) |
| command_poll_task = asyncio.create_task(self._command_poll_loop()) |
| else: |
| |
| await asyncio.sleep(30) |
| continue |
| |
| |
| if self.skynet_connected: |
| await asyncio.sleep(self.skynet_config.heartbeat_interval) |
| |
| |
| if (heartbeat_task and heartbeat_task.done()) or (command_poll_task and command_poll_task.done()): |
| self.logger.warning("Skynet connection lost - switching to standalone mode") |
| self.skynet_connected = False |
| |
| |
| if heartbeat_task and not heartbeat_task.done(): |
| heartbeat_task.cancel() |
| if command_poll_task and not command_poll_task.done(): |
| command_poll_task.cancel() |
| |
| heartbeat_task = None |
| command_poll_task = None |
| |
| except Exception as e: |
| self.logger.error(f"Error in Skynet connection loop: {e}") |
| await asyncio.sleep(5) |
|
|
| async def _register_with_skynet(self) -> bool: |
| """Register this component with Skynet""" |
| registration_data = { |
| 'id': self.component_config.id, |
| 'name': self.component_config.name, |
| 'type': self.component_config.type.value, |
| 'description': self.component_config.description, |
| 'host': self.component_config.host, |
| 'port': self.component_config.port, |
| 'endpoint': self.component_config.endpoint, |
| 'rosDomainId': self.component_config.ros_domain_id, |
| 'publishedTopics': self.component_config.published_topics, |
| 'subscribedTopics': self.component_config.subscribed_topics, |
| 'version': self.component_config.version, |
| 'metadata': self.component_config.metadata |
| } |
|
|
| url = f"{self.skynet_config.base_url}/api/v1/components/register" |
|
|
| try: |
| response = self.session.post( |
| url, |
| json=registration_data, |
| timeout=self.skynet_config.timeout |
| ) |
|
|
| if response.status_code in [200, 201]: |
| self.logger.info("Successfully registered with Skynet") |
| return True |
| else: |
| self.logger.error(f"Registration failed: {response.status_code} - {response.text}") |
| return False |
|
|
| except Exception as e: |
| self.logger.error(f"Error registering with Skynet: {e}") |
| return False |
|
|
| async def _heartbeat_loop(self): |
| """Send periodic heartbeats to Skynet""" |
| while self.running: |
| try: |
| await self._send_heartbeat() |
| await asyncio.sleep(self.skynet_config.heartbeat_interval) |
| except Exception as e: |
| self.logger.error(f"Error in heartbeat loop: {e}") |
| await asyncio.sleep(5) |
|
|
| async def _send_heartbeat(self): |
| """Send a heartbeat to Skynet""" |
| heartbeat_data = { |
| 'componentId': self.component_config.id |
| } |
|
|
| url = f"{self.skynet_config.base_url}/api/v1/components/heartbeat" |
|
|
| try: |
| response = self.session.post( |
| url, |
| json=heartbeat_data, |
| timeout=self.skynet_config.timeout |
| ) |
|
|
| if response.status_code == 200: |
| self.logger.debug("Heartbeat sent successfully") |
| else: |
| self.logger.warning(f"Heartbeat failed: {response.status_code}") |
|
|
| except Exception as e: |
| self.logger.error(f"Error sending heartbeat: {e}") |
|
|
| async def _command_poll_loop(self): |
| """Poll Skynet for pending commands""" |
| while self.running: |
| try: |
| await self._poll_and_execute_commands() |
| await asyncio.sleep(self.skynet_config.command_poll_interval) |
| except Exception as e: |
| self.logger.error(f"Error in command poll loop: {e}") |
| await asyncio.sleep(5) |
|
|
| async def _poll_and_execute_commands(self): |
| """Poll for commands and execute them""" |
| url = f"{self.skynet_config.base_url}/api/v1/sidecar/{self.component_config.id}/heartbeat-poll" |
|
|
| try: |
| response = self.session.post(url, timeout=self.skynet_config.timeout) |
|
|
| if response.status_code == 200: |
| data = response.json() |
| commands = data.get('pendingCommands', []) |
|
|
| if commands: |
| self.logger.debug(f"Found {len(commands)} pending commands") |
|
|
| for command in commands: |
| await self._execute_command(command) |
|
|
| else: |
| self.logger.warning(f"Command poll failed: {response.status_code} - {response.text}") |
|
|
| except Exception as e: |
| self.logger.error(f"Error polling for commands: {e}") |
|
|
| async def _execute_command(self, command: Dict[str, Any]): |
| """Execute a command from Skynet""" |
| command_id = command.get('id') |
| action = command.get('action') |
| command_type = command.get('commandType', 'CUSTOM') |
| parameters = command.get('parameters', {}) |
|
|
| self.logger.info(f"Executing command {command_id}: {action}") |
|
|
| |
| await self._update_command_status(command_id, CommandStatus.EXECUTING) |
|
|
| try: |
| |
| result = await self._handle_ros_command(action, command_type, parameters) |
|
|
| |
| await self._update_command_status( |
| command_id, |
| CommandStatus.COMPLETED, |
| result=str(result) |
| ) |
|
|
| except Exception as e: |
| self.logger.error(f"Command {command_id} failed: {e}") |
| await self._update_command_status( |
| command_id, |
| CommandStatus.FAILED, |
| error_message=str(e) |
| ) |
|
|
| async def _handle_ros_command(self, action: str, command_type: str, parameters: Dict[str, Any]) -> Any: |
| """Handle ROS2-specific command execution""" |
|
|
| |
| if action == "start": |
| return await self._start_primary_service(parameters) |
| elif action == "stop": |
| return await self._stop_primary_service() |
| elif action == "status": |
| return await self._get_service_status() |
|
|
| else: |
| raise ValueError(f"Unknown action: {action}") |
|
|
| |
| |
| |
|
|
| async def _start_primary_service(self, parameters: Dict[str, Any] = None) -> str: |
| """Start the primary service for this component type""" |
| if parameters is None: |
| parameters = {} |
|
|
| component_type = os.getenv('COMPONENT_TYPE', 'control') |
|
|
| if component_type == 'control': |
| service_name = "joint_jogger" |
| elif component_type == 'embodiment': |
| service_name = "embodiment_controller" |
| elif component_type == 'data_capture': |
| service_name = 'data_capture' |
| else: |
| raise ValueError(f"Unknown component type '{component_type}' - don't know which service to start") |
| |
| return await self._start_service(service_name, parameters) |
|
|
| async def _stop_primary_service(self) -> str: |
| """Stop the primary service for this component type""" |
| component_type = os.getenv('COMPONENT_TYPE', 'control') |
|
|
| if component_type == 'control': |
| service_name = "joint_jogger" |
| elif component_type == 'embodiment': |
| service_name = "embodiment_controller" |
| elif component_type == 'data_capture': |
| service_name = 'data_capture' |
| else: |
| raise ValueError(f"Unknown component type '{component_type}' - don't know which service to stop") |
|
|
| return await self._stop_service(service_name) |
|
|
| |
| |
| |
|
|
| async def _start_service(self, service_name: str, parameters: Dict[str, Any] = None) -> str: |
| """Start a ROS2 service as a subprocess""" |
| if parameters is None: |
| parameters = {} |
| self.logger.info(f"Starting ROS2 service: {service_name}") |
|
|
| |
| if service_name in self.ros2_processes: |
| if self.ros2_processes[service_name].poll() is None: |
| return f"Service {service_name} is already running" |
| else: |
| |
| del self.ros2_processes[service_name] |
|
|
| try: |
| |
| if service_name == "joint_jogger": |
| cmd = [ |
| 'bash', '-c', |
| '. /opt/ros/humble/setup.bash && . /opt/ros/humble/install/setup.bash && ' |
| 'ros2 run leader_follower joint_jogger ' |
| '--ros-args -p publish_rate:=10.0' |
| ] |
| elif service_name == "embodiment_controller": |
| cmd = [ |
| 'bash', '-c', |
| '. /opt/ros/humble/setup.bash && . /opt/ros/humble/install/setup.bash && ' |
| 'ros2 run buster_embodiment embodiment_controller ' |
| '--ros-args -p robot_name:=buster' |
| ] |
| elif service_name == "data_capture": |
| |
| experiment_id = parameters.get('experiment_id', 'default_experiment') |
| episode_number = parameters.get('episode_number', 1) |
|
|
| cmd = [ |
| 'bash', '-c', |
| '. /opt/ros/humble/setup.bash && . /opt/ros/humble/install/setup.bash && ' |
| 'cd /bags && ' |
| f'ros2 run capture data_capture_service ' |
| f'--ros-args -p config_file:=/app/config/capture_config.yaml ' |
| f'-p experiment_id:={experiment_id} -p episode_number:={episode_number} ' |
| f'-p bag_prefix:=runaround_capture' |
| ] |
| else: |
| raise ValueError(f"Unknown service: {service_name}") |
|
|
| |
| process = subprocess.Popen( |
| cmd, |
| env=self.ros2_env, |
| stdout=subprocess.PIPE, |
| stderr=subprocess.PIPE, |
| text=True, |
| cwd='/app' |
| ) |
|
|
| |
| self.ros2_processes[service_name] = process |
|
|
| |
| await asyncio.sleep(2) |
|
|
| |
| if process.poll() is None: |
| self.logger.info(f"Successfully started ROS2 service: {service_name} (PID: {process.pid})") |
| return f"Service {service_name} started successfully (PID: {process.pid})" |
| else: |
| |
| stdout, stderr = process.communicate() |
| error_msg = f"Service {service_name} failed to start. STDERR: {stderr}" |
| self.logger.error(error_msg) |
| del self.ros2_processes[service_name] |
| raise RuntimeError(error_msg) |
|
|
| except Exception as e: |
| error_msg = f"Error starting service {service_name}: {str(e)}" |
| self.logger.error(error_msg) |
| raise RuntimeError(error_msg) |
|
|
| async def _stop_service(self, service_name: str) -> str: |
| """Stop a ROS2 service subprocess""" |
| self.logger.info(f"Stopping ROS2 service: {service_name}") |
|
|
| if service_name not in self.ros2_processes: |
| return f"Service {service_name} is not running" |
|
|
| try: |
| process = self.ros2_processes[service_name] |
|
|
| |
| if process.poll() is not None: |
| |
| del self.ros2_processes[service_name] |
| return f"Service {service_name} was already stopped" |
|
|
| |
| process.terminate() |
|
|
| |
| try: |
| process.wait(timeout=10) |
| self.logger.info(f"Service {service_name} terminated gracefully") |
| except subprocess.TimeoutExpired: |
| |
| self.logger.warning(f"Service {service_name} didn't terminate gracefully, force killing") |
| process.kill() |
| process.wait() |
|
|
| |
| del self.ros2_processes[service_name] |
|
|
| return f"Service {service_name} stopped successfully" |
|
|
| except Exception as e: |
| error_msg = f"Error stopping service {service_name}: {str(e)}" |
| self.logger.error(error_msg) |
| raise RuntimeError(error_msg) |
|
|
| async def _get_service_status(self) -> Dict[str, Any]: |
| """Get status of all managed ROS2 services""" |
| self.logger.info("Getting ROS2 service status") |
|
|
| services = {} |
|
|
| |
| for service_name, process in list(self.ros2_processes.items()): |
| if process.poll() is None: |
| services[service_name] = { |
| "status": "RUNNING", |
| "pid": process.pid |
| } |
| else: |
| services[service_name] = { |
| "status": "STOPPED", |
| "return_code": process.returncode |
| } |
| |
| del self.ros2_processes[service_name] |
|
|
| |
| |
| component_type = os.getenv('COMPONENT_TYPE', 'control') |
| known_services = [] |
|
|
| if component_type == 'control': |
| known_services.append("joint_jogger") |
| elif component_type == 'embodiment': |
| known_services.append("embodiment_controller") |
| elif component_type == 'data_capture': |
| known_services.append("data_capture") |
|
|
| for service_name in known_services: |
| if service_name not in services: |
| services[service_name] = { |
| "status": "STOPPED", |
| "pid": None |
| } |
|
|
| result = { |
| "ros2_services": services, |
| "total_services": len(services), |
| "running_services": len([s for s in services.values() if s["status"] == "RUNNING"]) |
| } |
|
|
| |
| self.logger.info(f"Service status result: {result}") |
| return result |
|
|
| |
| |
| |
|
|
| async def _update_command_status(self, command_id: str, status: CommandStatus, |
| result: str = None, error_message: str = None): |
| """Update command status in Skynet""" |
| status_data = { |
| 'commandId': command_id, |
| 'status': status.value |
| } |
|
|
| if result: |
| status_data['result'] = result |
| if error_message: |
| status_data['errorMessage'] = error_message |
|
|
| url = f"{self.skynet_config.base_url}/api/v1/sidecar/commands/{command_id}/status" |
|
|
| try: |
| response = self.session.post( |
| url, |
| json=status_data, |
| timeout=self.skynet_config.timeout |
| ) |
|
|
| if response.status_code == 200: |
| self.logger.debug(f"Updated command {command_id} status to {status.value}") |
| else: |
| self.logger.warning(f"Failed to update command status: {response.status_code}") |
|
|
| except Exception as e: |
| self.logger.error(f"Error updating command status: {e}") |
|
|
| async def _ros_spin_loop(self): |
| """Keep ROS2 node spinning""" |
| while self.running: |
| try: |
| rclpy.spin_once(self.ros_node, timeout_sec=0.1) |
| await asyncio.sleep(0.01) |
| except Exception as e: |
| self.logger.error(f"Error in ROS spin loop: {e}") |
| await asyncio.sleep(1) |
|
|
| async def _shutdown(self): |
| """Cleanup and shutdown""" |
| self.logger.info("Shutting down sidecar...") |
|
|
| |
| if hasattr(self, 'skynet_connected') and self.skynet_connected: |
| try: |
| url = f"{self.skynet_config.base_url}/api/v1/components/{self.component_config.id}" |
| self.session.delete(url, timeout=5) |
| self.logger.info("Unregistered from Skynet") |
| except Exception as e: |
| self.logger.warning(f"Failed to unregister from Skynet: {e}") |
| else: |
| self.logger.debug("Skynet not connected - skipping unregistration") |
|
|
| |
| if self.ros_node: |
| self.ros_node.destroy_node() |
| rclpy.shutdown() |
|
|
| |
| self.session.close() |
|
|
| self.logger.info("Sidecar shutdown complete") |
|
|
|
|
| async def main(): |
| """Main entry point""" |
| import argparse |
|
|
| parser = argparse.ArgumentParser(description='Skynet Sidecar Application') |
| parser.add_argument( |
| '--log-level', |
| choices=['DEBUG', 'INFO', 'WARNING', 'ERROR'], |
| default='INFO', |
| help='Logging level' |
| ) |
|
|
| args = parser.parse_args() |
|
|
| |
| logging.getLogger().setLevel(getattr(logging, args.log_level)) |
|
|
| |
| sidecar = SidecarApp() |
| await sidecar.start() |
|
|
|
|
| if __name__ == "__main__": |
| asyncio.run(main()) |
|
|