feat: add interactive terminal and dev server management

Add new features for interactive terminal sessions and dev server control:

Terminal Component:
- New Terminal.tsx component using xterm.js for full terminal emulation
- WebSocket-based PTY communication with bidirectional I/O
- Cross-platform support (Windows via winpty, Unix via built-in pty)
- Auto-reconnection with exponential backoff
- Fix duplicate WebSocket connection bug by checking CONNECTING state
- Add manual close flag to prevent auto-reconnect race conditions
- Add project tracking to avoid duplicate connects on initial activation

Dev Server Management:
- New DevServerControl.tsx for starting/stopping dev servers
- DevServerManager service for subprocess management
- WebSocket streaming of dev server output
- Project configuration service for reading package.json scripts

Backend Infrastructure:
- Terminal router with WebSocket endpoint for PTY I/O
- DevServer router for server lifecycle management
- Terminal session manager with callback-based output streaming
- Enhanced WebSocket schemas for terminal and dev server messages

UI Integration:
- New Terminal and Dev Server tabs in the main application
- Updated DebugLogViewer with improved UI and functionality
- Extended useWebSocket hook for terminal message handling

Co-Authored-By: Claude Opus 4.5 <noreply@anthropic.com>
This commit is contained in:
Auto
2026-01-12 10:35:36 +02:00
parent b1473cdfb9
commit c1985eb285
22 changed files with 3360 additions and 66 deletions

View File

@@ -34,17 +34,24 @@ from fastapi.staticfiles import StaticFiles
from .routers import (
agent_router,
assistant_chat_router,
devserver_router,
expand_project_router,
features_router,
filesystem_router,
projects_router,
settings_router,
spec_creation_router,
terminal_router,
)
from .schemas import SetupStatus
from .services.assistant_chat_session import cleanup_all_sessions as cleanup_assistant_sessions
from .services.dev_server_manager import (
cleanup_all_devservers,
cleanup_orphaned_devserver_locks,
)
from .services.expand_chat_session import cleanup_all_expand_sessions
from .services.process_manager import cleanup_all_managers, cleanup_orphaned_locks
from .services.terminal_manager import cleanup_all_terminals
from .websocket import project_websocket
# Paths
@@ -57,11 +64,14 @@ async def lifespan(app: FastAPI):
"""Lifespan context manager for startup and shutdown."""
# Startup - clean up orphaned lock files from previous runs
cleanup_orphaned_locks()
cleanup_orphaned_devserver_locks()
yield
# Shutdown - cleanup all running agents and sessions
# Shutdown - cleanup all running agents, sessions, terminals, and dev servers
await cleanup_all_managers()
await cleanup_assistant_sessions()
await cleanup_all_expand_sessions()
await cleanup_all_terminals()
await cleanup_all_devservers()
# Create FastAPI app
@@ -110,11 +120,13 @@ async def require_localhost(request: Request, call_next):
app.include_router(projects_router)
app.include_router(features_router)
app.include_router(agent_router)
app.include_router(devserver_router)
app.include_router(spec_creation_router)
app.include_router(expand_project_router)
app.include_router(filesystem_router)
app.include_router(assistant_chat_router)
app.include_router(settings_router)
app.include_router(terminal_router)
# ============================================================================

View File

@@ -7,20 +7,24 @@ FastAPI routers for different API endpoints.
from .agent import router as agent_router
from .assistant_chat import router as assistant_chat_router
from .devserver import router as devserver_router
from .expand_project import router as expand_project_router
from .features import router as features_router
from .filesystem import router as filesystem_router
from .projects import router as projects_router
from .settings import router as settings_router
from .spec_creation import router as spec_creation_router
from .terminal import router as terminal_router
__all__ = [
"projects_router",
"features_router",
"agent_router",
"devserver_router",
"spec_creation_router",
"expand_project_router",
"filesystem_router",
"assistant_chat_router",
"settings_router",
"terminal_router",
]

280
server/routers/devserver.py Normal file
View File

@@ -0,0 +1,280 @@
"""
Dev Server Router
=================
API endpoints for dev server control (start/stop) and configuration.
Uses project registry for path lookups and project_config for command detection.
"""
import re
import sys
from pathlib import Path
from fastapi import APIRouter, HTTPException
from ..schemas import (
DevServerActionResponse,
DevServerConfigResponse,
DevServerConfigUpdate,
DevServerStartRequest,
DevServerStatus,
)
from ..services.dev_server_manager import get_devserver_manager
from ..services.project_config import (
clear_dev_command,
get_dev_command,
get_project_config,
set_dev_command,
)
# Add root to path for registry import
_root = Path(__file__).parent.parent.parent
if str(_root) not in sys.path:
sys.path.insert(0, str(_root))
from registry import get_project_path as registry_get_project_path
def _get_project_path(project_name: str) -> Path | None:
"""Get project path from registry."""
return registry_get_project_path(project_name)
router = APIRouter(prefix="/api/projects/{project_name}/devserver", tags=["devserver"])
# ============================================================================
# Helper Functions
# ============================================================================
def validate_project_name(name: str) -> str:
"""Validate and sanitize project name to prevent path traversal."""
if not re.match(r'^[a-zA-Z0-9_-]{1,50}$', name):
raise HTTPException(
status_code=400,
detail="Invalid project name"
)
return name
def get_project_dir(project_name: str) -> Path:
"""
Get the validated project directory for a project name.
Args:
project_name: Name of the project
Returns:
Path to the project directory
Raises:
HTTPException: If project is not found or directory does not exist
"""
project_name = validate_project_name(project_name)
project_dir = _get_project_path(project_name)
if not project_dir:
raise HTTPException(
status_code=404,
detail=f"Project '{project_name}' not found in registry"
)
if not project_dir.exists():
raise HTTPException(
status_code=404,
detail=f"Project directory not found: {project_dir}"
)
return project_dir
def get_project_devserver_manager(project_name: str):
"""
Get the dev server process manager for a project.
Args:
project_name: Name of the project
Returns:
DevServerProcessManager instance for the project
Raises:
HTTPException: If project is not found or directory does not exist
"""
project_dir = get_project_dir(project_name)
return get_devserver_manager(project_name, project_dir)
# ============================================================================
# Endpoints
# ============================================================================
@router.get("/status", response_model=DevServerStatus)
async def get_devserver_status(project_name: str) -> DevServerStatus:
"""
Get the current status of the dev server for a project.
Returns information about whether the dev server is running,
its process ID, detected URL, and the command used to start it.
"""
manager = get_project_devserver_manager(project_name)
# Run healthcheck to detect crashed processes
await manager.healthcheck()
return DevServerStatus(
status=manager.status,
pid=manager.pid,
url=manager.detected_url,
command=manager._command,
started_at=manager.started_at,
)
@router.post("/start", response_model=DevServerActionResponse)
async def start_devserver(
project_name: str,
request: DevServerStartRequest = DevServerStartRequest(),
) -> DevServerActionResponse:
"""
Start the dev server for a project.
If a custom command is provided in the request, it will be used.
Otherwise, the effective command from the project configuration is used.
Args:
project_name: Name of the project
request: Optional start request with custom command
Returns:
Response indicating success/failure and current status
"""
manager = get_project_devserver_manager(project_name)
project_dir = get_project_dir(project_name)
# Determine which command to use
command: str | None
if request.command:
command = request.command
else:
command = get_dev_command(project_dir)
if not command:
raise HTTPException(
status_code=400,
detail="No dev command available. Configure a custom command or ensure project type can be detected."
)
# Now command is definitely str
success, message = await manager.start(command)
return DevServerActionResponse(
success=success,
status=manager.status,
message=message,
)
@router.post("/stop", response_model=DevServerActionResponse)
async def stop_devserver(project_name: str) -> DevServerActionResponse:
"""
Stop the dev server for a project.
Gracefully terminates the dev server process and all its child processes.
Args:
project_name: Name of the project
Returns:
Response indicating success/failure and current status
"""
manager = get_project_devserver_manager(project_name)
success, message = await manager.stop()
return DevServerActionResponse(
success=success,
status=manager.status,
message=message,
)
@router.get("/config", response_model=DevServerConfigResponse)
async def get_devserver_config(project_name: str) -> DevServerConfigResponse:
"""
Get the dev server configuration for a project.
Returns information about:
- detected_type: The auto-detected project type (nodejs-vite, python-django, etc.)
- detected_command: The default command for the detected type
- custom_command: Any user-configured custom command
- effective_command: The command that will actually be used (custom or detected)
Args:
project_name: Name of the project
Returns:
Configuration details for the project's dev server
"""
project_dir = get_project_dir(project_name)
config = get_project_config(project_dir)
return DevServerConfigResponse(
detected_type=config["detected_type"],
detected_command=config["detected_command"],
custom_command=config["custom_command"],
effective_command=config["effective_command"],
)
@router.patch("/config", response_model=DevServerConfigResponse)
async def update_devserver_config(
project_name: str,
update: DevServerConfigUpdate,
) -> DevServerConfigResponse:
"""
Update the dev server configuration for a project.
Set custom_command to a string to override the auto-detected command.
Set custom_command to null/None to clear the custom command and revert
to using the auto-detected command.
Args:
project_name: Name of the project
update: Configuration update containing the new custom_command
Returns:
Updated configuration details for the project's dev server
"""
project_dir = get_project_dir(project_name)
# Update the custom command
if update.custom_command is None:
# Clear the custom command
try:
clear_dev_command(project_dir)
except ValueError as e:
raise HTTPException(status_code=400, detail=str(e))
else:
# Set the custom command
try:
set_dev_command(project_dir, update.custom_command)
except ValueError as e:
raise HTTPException(status_code=400, detail=str(e))
except OSError as e:
raise HTTPException(
status_code=500,
detail=f"Failed to save configuration: {e}"
)
# Return updated config
config = get_project_config(project_dir)
return DevServerConfigResponse(
detected_type=config["detected_type"],
detected_command=config["detected_command"],
custom_command=config["custom_command"],
effective_command=config["effective_command"],
)

273
server/routers/terminal.py Normal file
View File

@@ -0,0 +1,273 @@
"""
Terminal Router
===============
WebSocket endpoint for interactive terminal I/O with PTY support.
Provides real-time bidirectional communication with terminal sessions.
"""
import asyncio
import base64
import json
import logging
import re
import sys
from pathlib import Path
from fastapi import APIRouter, WebSocket, WebSocketDisconnect
from ..services.terminal_manager import get_terminal_session
# Add project root to path for registry import
_root = Path(__file__).parent.parent.parent
if str(_root) not in sys.path:
sys.path.insert(0, str(_root))
from registry import get_project_path as registry_get_project_path
logger = logging.getLogger(__name__)
router = APIRouter(prefix="/api/terminal", tags=["terminal"])
class TerminalCloseCode:
"""WebSocket close codes for terminal endpoint."""
INVALID_PROJECT_NAME = 4000
PROJECT_NOT_FOUND = 4004
FAILED_TO_START = 4500
def _get_project_path(project_name: str) -> Path | None:
"""Get project path from registry."""
return registry_get_project_path(project_name)
def validate_project_name(name: str) -> bool:
"""
Validate project name to prevent path traversal attacks.
Allows only alphanumeric characters, underscores, and hyphens.
Maximum length of 50 characters.
Args:
name: The project name to validate
Returns:
True if valid, False otherwise
"""
return bool(re.match(r"^[a-zA-Z0-9_-]{1,50}$", name))
@router.websocket("/ws/{project_name}")
async def terminal_websocket(websocket: WebSocket, project_name: str) -> None:
"""
WebSocket endpoint for interactive terminal I/O.
Message protocol:
Client -> Server:
- {"type": "input", "data": "<base64-encoded-bytes>"} - Keyboard input
- {"type": "resize", "cols": 80, "rows": 24} - Terminal resize
- {"type": "ping"} - Keep-alive ping
Server -> Client:
- {"type": "output", "data": "<base64-encoded-bytes>"} - PTY output
- {"type": "exit", "code": 0} - Shell process exited
- {"type": "pong"} - Keep-alive response
- {"type": "error", "message": "..."} - Error message
"""
# Validate project name
if not validate_project_name(project_name):
await websocket.close(
code=TerminalCloseCode.INVALID_PROJECT_NAME, reason="Invalid project name"
)
return
# Look up project directory from registry
project_dir = _get_project_path(project_name)
if not project_dir:
await websocket.close(
code=TerminalCloseCode.PROJECT_NOT_FOUND,
reason="Project not found in registry",
)
return
if not project_dir.exists():
await websocket.close(
code=TerminalCloseCode.PROJECT_NOT_FOUND,
reason="Project directory not found",
)
return
await websocket.accept()
# Get or create terminal session for this project
session = get_terminal_session(project_name, project_dir)
# Queue for output data to send to client
output_queue: asyncio.Queue[bytes] = asyncio.Queue()
# Callback to receive terminal output and queue it for sending
def on_output(data: bytes) -> None:
"""Queue terminal output for async sending to WebSocket."""
try:
output_queue.put_nowait(data)
except asyncio.QueueFull:
logger.warning(f"Output queue full for {project_name}, dropping data")
# Register the output callback
session.add_output_callback(on_output)
# Start the terminal session if not already active
if not session.is_active:
started = await session.start()
if not started:
session.remove_output_callback(on_output)
try:
await websocket.send_json(
{"type": "error", "message": "Failed to start terminal session"}
)
except Exception:
pass
await websocket.close(
code=TerminalCloseCode.FAILED_TO_START, reason="Failed to start terminal"
)
return
# Task to send queued output to WebSocket
async def send_output_task() -> None:
"""Continuously send queued output to the WebSocket client."""
try:
while True:
# Wait for output data
data = await output_queue.get()
# Encode as base64 and send
encoded = base64.b64encode(data).decode("ascii")
await websocket.send_json({"type": "output", "data": encoded})
except asyncio.CancelledError:
raise
except WebSocketDisconnect:
raise
except Exception as e:
logger.warning(f"Error sending output for {project_name}: {e}")
raise
# Task to monitor if the terminal session exits
async def monitor_exit_task() -> None:
"""Monitor the terminal session and notify client on exit."""
try:
while session.is_active:
await asyncio.sleep(0.5)
# Session ended - send exit message
# Note: We don't have access to actual exit code from PTY
await websocket.send_json({"type": "exit", "code": 0})
except asyncio.CancelledError:
raise
except WebSocketDisconnect:
raise
except Exception as e:
logger.warning(f"Error in exit monitor for {project_name}: {e}")
# Start background tasks
output_task = asyncio.create_task(send_output_task())
exit_task = asyncio.create_task(monitor_exit_task())
try:
while True:
try:
# Receive message from client
data = await websocket.receive_text()
message = json.loads(data)
msg_type = message.get("type")
if msg_type == "ping":
await websocket.send_json({"type": "pong"})
elif msg_type == "input":
# Decode base64 input and write to PTY
encoded_data = message.get("data", "")
# Add size limit to prevent DoS
if len(encoded_data) > 65536: # 64KB limit for base64 encoded data
await websocket.send_json({"type": "error", "message": "Input too large"})
continue
if encoded_data:
try:
decoded = base64.b64decode(encoded_data)
except (ValueError, TypeError) as e:
logger.warning(f"Failed to decode base64 input: {e}")
await websocket.send_json(
{"type": "error", "message": "Invalid base64 data"}
)
continue
try:
session.write(decoded)
except Exception as e:
logger.warning(f"Failed to write to terminal: {e}")
await websocket.send_json(
{"type": "error", "message": "Failed to write to terminal"}
)
elif msg_type == "resize":
# Resize the terminal
cols = message.get("cols", 80)
rows = message.get("rows", 24)
# Validate dimensions
if isinstance(cols, int) and isinstance(rows, int):
cols = max(10, min(500, cols))
rows = max(5, min(200, rows))
session.resize(cols, rows)
else:
await websocket.send_json({"type": "error", "message": "Invalid resize dimensions"})
else:
await websocket.send_json({"type": "error", "message": f"Unknown message type: {msg_type}"})
except json.JSONDecodeError:
await websocket.send_json({"type": "error", "message": "Invalid JSON"})
except WebSocketDisconnect:
logger.info(f"Terminal WebSocket disconnected for {project_name}")
except Exception as e:
logger.exception(f"Terminal WebSocket error for {project_name}")
try:
await websocket.send_json({"type": "error", "message": f"Server error: {str(e)}"})
except Exception:
pass
finally:
# Cancel background tasks
output_task.cancel()
exit_task.cancel()
try:
await output_task
except asyncio.CancelledError:
pass
try:
await exit_task
except asyncio.CancelledError:
pass
# Remove the output callback
session.remove_output_callback(on_output)
# Only stop session if no other clients are connected
with session._callbacks_lock:
remaining_callbacks = len(session._output_callbacks)
if remaining_callbacks == 0:
await session.stop()
logger.info(f"Terminal session stopped for {project_name} (last client disconnected)")
else:
logger.info(
f"Client disconnected from {project_name}, {remaining_callbacks} clients remaining"
)

View File

@@ -308,3 +308,61 @@ class SettingsUpdate(BaseModel):
if v is not None and v not in VALID_MODELS:
raise ValueError(f"Invalid model. Must be one of: {VALID_MODELS}")
return v
# ============================================================================
# Dev Server Schemas
# ============================================================================
class DevServerStartRequest(BaseModel):
"""Request schema for starting the dev server."""
command: str | None = None # If None, uses effective command from config
class DevServerStatus(BaseModel):
"""Current dev server status."""
status: Literal["stopped", "running", "crashed"]
pid: int | None = None
url: str | None = None
command: str | None = None
started_at: datetime | None = None
class DevServerActionResponse(BaseModel):
"""Response for dev server control actions."""
success: bool
status: Literal["stopped", "running", "crashed"]
message: str = ""
class DevServerConfigResponse(BaseModel):
"""Response for dev server configuration."""
detected_type: str | None = None
detected_command: str | None = None
custom_command: str | None = None
effective_command: str | None = None
class DevServerConfigUpdate(BaseModel):
"""Request schema for updating dev server configuration."""
custom_command: str | None = None # None clears the custom command
# ============================================================================
# Dev Server WebSocket Message Schemas
# ============================================================================
class WSDevLogMessage(BaseModel):
"""WebSocket message for dev server log output."""
type: Literal["dev_log"] = "dev_log"
line: str
timestamp: datetime
class WSDevServerStatusMessage(BaseModel):
"""WebSocket message for dev server status changes."""
type: Literal["dev_server_status"] = "dev_server_status"
status: Literal["stopped", "running", "crashed"]
url: str | None = None

View File

@@ -6,5 +6,31 @@ Business logic and process management services.
"""
from .process_manager import AgentProcessManager
from .project_config import (
clear_dev_command,
detect_project_type,
get_default_dev_command,
get_dev_command,
get_project_config,
set_dev_command,
)
from .terminal_manager import (
TerminalSession,
cleanup_all_terminals,
get_terminal_session,
remove_terminal_session,
)
__all__ = ["AgentProcessManager"]
__all__ = [
"AgentProcessManager",
"TerminalSession",
"cleanup_all_terminals",
"clear_dev_command",
"detect_project_type",
"get_default_dev_command",
"get_dev_command",
"get_project_config",
"get_terminal_session",
"remove_terminal_session",
"set_dev_command",
]

View File

@@ -0,0 +1,556 @@
"""
Dev Server Process Manager
==========================
Manages the lifecycle of dev server subprocesses per project.
Provides start/stop functionality with cross-platform support via psutil.
This is a simplified version of AgentProcessManager, tailored for dev servers:
- No pause/resume (not needed for dev servers)
- URL detection from output (regex for http://localhost:XXXX patterns)
- Simpler status states: stopped, running, crashed
"""
import asyncio
import logging
import re
import subprocess
import sys
import threading
from datetime import datetime
from pathlib import Path
from typing import Awaitable, Callable, Literal, Set
import psutil
from registry import list_registered_projects
logger = logging.getLogger(__name__)
# Patterns for sensitive data that should be redacted from output
SENSITIVE_PATTERNS = [
r'sk-[a-zA-Z0-9]{20,}', # Anthropic API keys
r'ANTHROPIC_API_KEY=[^\s]+',
r'api[_-]?key[=:][^\s]+',
r'token[=:][^\s]+',
r'password[=:][^\s]+',
r'secret[=:][^\s]+',
r'ghp_[a-zA-Z0-9]{36,}', # GitHub personal access tokens
r'gho_[a-zA-Z0-9]{36,}', # GitHub OAuth tokens
r'ghs_[a-zA-Z0-9]{36,}', # GitHub server tokens
r'ghr_[a-zA-Z0-9]{36,}', # GitHub refresh tokens
r'aws[_-]?access[_-]?key[=:][^\s]+', # AWS keys
r'aws[_-]?secret[=:][^\s]+',
]
# Patterns to detect URLs in dev server output
# Matches common patterns like:
# - http://localhost:3000
# - http://127.0.0.1:5173
# - https://localhost:8080/
# - Local: http://localhost:3000
# - http://localhost:3000/api/docs
URL_PATTERNS = [
r'https?://(?:localhost|127\.0\.0\.1):\d+(?:/[^\s]*)?',
r'https?://\[::1\]:\d+(?:/[^\s]*)?', # IPv6 localhost
r'https?://0\.0\.0\.0:\d+(?:/[^\s]*)?', # Bound to all interfaces
]
def sanitize_output(line: str) -> str:
"""Remove sensitive information from output lines."""
for pattern in SENSITIVE_PATTERNS:
line = re.sub(pattern, '[REDACTED]', line, flags=re.IGNORECASE)
return line
def extract_url(line: str) -> str | None:
"""
Extract a localhost URL from an output line if present.
Returns the first URL found, or None if no URL is detected.
"""
for pattern in URL_PATTERNS:
match = re.search(pattern, line)
if match:
return match.group(0)
return None
class DevServerProcessManager:
"""
Manages dev server subprocess lifecycle for a single project.
Provides start/stop with cross-platform support via psutil.
Supports multiple output callbacks for WebSocket clients.
Detects and tracks the server URL from output.
"""
def __init__(
self,
project_name: str,
project_dir: Path,
):
"""
Initialize the dev server process manager.
Args:
project_name: Name of the project
project_dir: Absolute path to the project directory
"""
self.project_name = project_name
self.project_dir = project_dir
self.process: subprocess.Popen | None = None
self._status: Literal["stopped", "running", "crashed"] = "stopped"
self.started_at: datetime | None = None
self._output_task: asyncio.Task | None = None
self._detected_url: str | None = None
self._command: str | None = None # Store the command used to start
# Support multiple callbacks (for multiple WebSocket clients)
self._output_callbacks: Set[Callable[[str], Awaitable[None]]] = set()
self._status_callbacks: Set[Callable[[str], Awaitable[None]]] = set()
self._callbacks_lock = threading.Lock()
# Lock file to prevent multiple instances (stored in project directory)
self.lock_file = self.project_dir / ".devserver.lock"
@property
def status(self) -> Literal["stopped", "running", "crashed"]:
"""Current status of the dev server."""
return self._status
@status.setter
def status(self, value: Literal["stopped", "running", "crashed"]):
old_status = self._status
self._status = value
if old_status != value:
self._notify_status_change(value)
@property
def detected_url(self) -> str | None:
"""The URL detected from server output, if any."""
return self._detected_url
@property
def pid(self) -> int | None:
"""Process ID of the running dev server, or None if not running."""
return self.process.pid if self.process else None
def _notify_status_change(self, status: str) -> None:
"""Notify all registered callbacks of status change."""
with self._callbacks_lock:
callbacks = list(self._status_callbacks)
for callback in callbacks:
try:
# Schedule the callback in the event loop
loop = asyncio.get_running_loop()
loop.create_task(self._safe_callback(callback, status))
except RuntimeError:
# No running event loop
pass
async def _safe_callback(self, callback: Callable, *args) -> None:
"""Safely execute a callback, catching and logging any errors."""
try:
await callback(*args)
except Exception as e:
logger.warning(f"Callback error: {e}")
def add_output_callback(self, callback: Callable[[str], Awaitable[None]]) -> None:
"""Add a callback for output lines."""
with self._callbacks_lock:
self._output_callbacks.add(callback)
def remove_output_callback(self, callback: Callable[[str], Awaitable[None]]) -> None:
"""Remove an output callback."""
with self._callbacks_lock:
self._output_callbacks.discard(callback)
def add_status_callback(self, callback: Callable[[str], Awaitable[None]]) -> None:
"""Add a callback for status changes."""
with self._callbacks_lock:
self._status_callbacks.add(callback)
def remove_status_callback(self, callback: Callable[[str], Awaitable[None]]) -> None:
"""Remove a status callback."""
with self._callbacks_lock:
self._status_callbacks.discard(callback)
def _check_lock(self) -> bool:
"""
Check if another dev server is already running for this project.
Validates that the PID in the lock file belongs to a process running
in the same project directory to avoid false positives from PID recycling.
Returns:
True if we can proceed (no other server running), False otherwise.
"""
if not self.lock_file.exists():
return True
try:
pid = int(self.lock_file.read_text().strip())
if psutil.pid_exists(pid):
try:
proc = psutil.Process(pid)
if proc.is_running():
try:
# Verify the process is running in our project directory
# to avoid false positives from PID recycling
proc_cwd = Path(proc.cwd()).resolve()
if sys.platform == "win32":
# Windows paths are case-insensitive
if proc_cwd.as_posix().lower() == self.project_dir.resolve().as_posix().lower():
return False # Likely our dev server
else:
if proc_cwd == self.project_dir.resolve():
return False # Likely our dev server
except (psutil.AccessDenied, OSError):
# Cannot verify cwd, assume it's our process to be safe
return False
except (psutil.NoSuchProcess, psutil.AccessDenied):
pass
# Stale lock file - process no longer exists or is in different directory
self.lock_file.unlink(missing_ok=True)
return True
except (ValueError, OSError):
# Invalid lock file content - remove it
self.lock_file.unlink(missing_ok=True)
return True
def _create_lock(self) -> None:
"""Create lock file with current process PID."""
self.lock_file.parent.mkdir(parents=True, exist_ok=True)
if self.process:
self.lock_file.write_text(str(self.process.pid))
def _remove_lock(self) -> None:
"""Remove lock file."""
self.lock_file.unlink(missing_ok=True)
async def _broadcast_output(self, line: str) -> None:
"""Broadcast output line to all registered callbacks."""
with self._callbacks_lock:
callbacks = list(self._output_callbacks)
for callback in callbacks:
await self._safe_callback(callback, line)
async def _stream_output(self) -> None:
"""Stream process output to callbacks and detect URL."""
if not self.process or not self.process.stdout:
return
try:
loop = asyncio.get_running_loop()
while True:
# Use run_in_executor for blocking readline
line = await loop.run_in_executor(
None, self.process.stdout.readline
)
if not line:
break
decoded = line.decode("utf-8", errors="replace").rstrip()
sanitized = sanitize_output(decoded)
# Try to detect URL from output (only if not already detected)
if not self._detected_url:
url = extract_url(decoded)
if url:
self._detected_url = url
logger.info(
"Dev server URL detected for %s: %s",
self.project_name, url
)
await self._broadcast_output(sanitized)
except asyncio.CancelledError:
raise
except Exception as e:
logger.warning(f"Output streaming error: {e}")
finally:
# Check if process ended
if self.process and self.process.poll() is not None:
exit_code = self.process.returncode
if exit_code != 0 and self.status == "running":
self.status = "crashed"
elif self.status == "running":
self.status = "stopped"
self._remove_lock()
async def start(self, command: str) -> tuple[bool, str]:
"""
Start the dev server as a subprocess.
Args:
command: The shell command to run (e.g., "npm run dev")
Returns:
Tuple of (success, message)
"""
if self.status == "running":
return False, "Dev server is already running"
if not self._check_lock():
return False, "Another dev server instance is already running for this project"
# Validate that project directory exists
if not self.project_dir.exists():
return False, f"Project directory does not exist: {self.project_dir}"
self._command = command
self._detected_url = None # Reset URL detection
try:
# Determine shell based on platform
if sys.platform == "win32":
# On Windows, use cmd.exe
shell_cmd = ["cmd", "/c", command]
else:
# On Unix-like systems, use sh
shell_cmd = ["sh", "-c", command]
# Start subprocess with piped stdout/stderr
# stdin=DEVNULL prevents interactive dev servers from blocking on stdin
# On Windows, use CREATE_NO_WINDOW to prevent console window from flashing
if sys.platform == "win32":
self.process = subprocess.Popen(
shell_cmd,
stdin=subprocess.DEVNULL,
stdout=subprocess.PIPE,
stderr=subprocess.STDOUT,
cwd=str(self.project_dir),
creationflags=subprocess.CREATE_NO_WINDOW,
)
else:
self.process = subprocess.Popen(
shell_cmd,
stdin=subprocess.DEVNULL,
stdout=subprocess.PIPE,
stderr=subprocess.STDOUT,
cwd=str(self.project_dir),
)
self._create_lock()
self.started_at = datetime.now()
self.status = "running"
# Start output streaming task
self._output_task = asyncio.create_task(self._stream_output())
return True, f"Dev server started with PID {self.process.pid}"
except Exception as e:
logger.exception("Failed to start dev server")
return False, f"Failed to start dev server: {e}"
async def stop(self) -> tuple[bool, str]:
"""
Stop the dev server (SIGTERM then SIGKILL if needed).
Uses psutil to terminate the entire process tree, ensuring
child processes (like Node.js) are also terminated.
Returns:
Tuple of (success, message)
"""
if not self.process or self.status == "stopped":
return False, "Dev server is not running"
try:
# Cancel output streaming
if self._output_task:
self._output_task.cancel()
try:
await self._output_task
except asyncio.CancelledError:
pass
# Use psutil to terminate the entire process tree
# This is important for dev servers that spawn child processes
try:
parent = psutil.Process(self.process.pid)
children = parent.children(recursive=True)
# Terminate children first
for child in children:
try:
child.terminate()
except psutil.NoSuchProcess:
pass
# Terminate parent
parent.terminate()
# Wait for graceful shutdown
_, still_alive = psutil.wait_procs(
[parent] + children, timeout=5
)
# Force kill any remaining processes
for proc in still_alive:
try:
proc.kill()
except psutil.NoSuchProcess:
pass
except psutil.NoSuchProcess:
# Process already gone
pass
self._remove_lock()
self.status = "stopped"
self.process = None
self.started_at = None
self._detected_url = None
self._command = None
return True, "Dev server stopped"
except Exception as e:
logger.exception("Failed to stop dev server")
return False, f"Failed to stop dev server: {e}"
async def healthcheck(self) -> bool:
"""
Check if the dev server process is still alive.
Updates status to 'crashed' if process has died unexpectedly.
Returns:
True if healthy, False otherwise
"""
if not self.process:
return self.status == "stopped"
poll = self.process.poll()
if poll is not None:
# Process has terminated
if self.status == "running":
self.status = "crashed"
self._remove_lock()
return False
return True
def get_status_dict(self) -> dict:
"""Get current status as a dictionary."""
return {
"status": self.status,
"pid": self.pid,
"started_at": self.started_at.isoformat() if self.started_at else None,
"detected_url": self._detected_url,
"command": self._command,
}
# Global registry of dev server managers per project with thread safety
_managers: dict[str, DevServerProcessManager] = {}
_managers_lock = threading.Lock()
def get_devserver_manager(project_name: str, project_dir: Path) -> DevServerProcessManager:
"""
Get or create a dev server process manager for a project (thread-safe).
Args:
project_name: Name of the project
project_dir: Absolute path to the project directory
Returns:
DevServerProcessManager instance for the project
"""
with _managers_lock:
if project_name in _managers:
manager = _managers[project_name]
# Update project_dir in case project was moved
if manager.project_dir.resolve() != project_dir.resolve():
logger.info(
f"Project {project_name} path updated: {manager.project_dir} -> {project_dir}"
)
manager.project_dir = project_dir
manager.lock_file = project_dir / ".devserver.lock"
return manager
_managers[project_name] = DevServerProcessManager(project_name, project_dir)
return _managers[project_name]
async def cleanup_all_devservers() -> None:
"""Stop all running dev servers. Called on server shutdown."""
with _managers_lock:
managers = list(_managers.values())
for manager in managers:
try:
if manager.status != "stopped":
await manager.stop()
except Exception as e:
logger.warning(f"Error stopping dev server for {manager.project_name}: {e}")
with _managers_lock:
_managers.clear()
def cleanup_orphaned_devserver_locks() -> int:
"""
Clean up orphaned dev server lock files from previous server runs.
Scans all registered projects for .devserver.lock files and removes them
if the referenced process is no longer running.
Returns:
Number of orphaned lock files cleaned up
"""
cleaned = 0
try:
projects = list_registered_projects()
for name, info in projects.items():
project_path = Path(info.get("path", ""))
if not project_path.exists():
continue
lock_file = project_path / ".devserver.lock"
if not lock_file.exists():
continue
try:
pid_str = lock_file.read_text().strip()
pid = int(pid_str)
# Check if process is still running
if psutil.pid_exists(pid):
try:
proc = psutil.Process(pid)
if proc.is_running():
# Process is still running, don't remove
logger.info(
"Found running dev server for project '%s' (PID %d)",
name, pid
)
continue
except (psutil.NoSuchProcess, psutil.AccessDenied):
pass
# Process not running - remove stale lock
lock_file.unlink(missing_ok=True)
cleaned += 1
logger.info("Removed orphaned dev server lock file for project '%s'", name)
except (ValueError, OSError) as e:
# Invalid lock file content - remove it
logger.warning(
"Removing invalid dev server lock file for project '%s': %s", name, e
)
lock_file.unlink(missing_ok=True)
cleaned += 1
except Exception as e:
logger.error("Error during dev server orphan cleanup: %s", e)
if cleaned:
logger.info("Cleaned up %d orphaned dev server lock file(s)", cleaned)
return cleaned

View File

@@ -0,0 +1,466 @@
"""
Project Configuration Service
=============================
Handles project type detection and dev command configuration.
Detects project types by scanning for configuration files and provides
default or custom dev commands for each project.
Configuration is stored in {project_dir}/.autocoder/config.json.
"""
import json
import logging
from pathlib import Path
from typing import TypedDict
# Python 3.11+ has tomllib in the standard library
try:
import tomllib
except ImportError:
tomllib = None # type: ignore[assignment]
logger = logging.getLogger(__name__)
# =============================================================================
# Path Validation
# =============================================================================
def _validate_project_dir(project_dir: Path) -> Path:
"""
Validate and resolve the project directory.
Args:
project_dir: Path to the project directory.
Returns:
Resolved Path object.
Raises:
ValueError: If project_dir is not a valid directory.
"""
resolved = Path(project_dir).resolve()
if not resolved.exists():
raise ValueError(f"Project directory does not exist: {resolved}")
if not resolved.is_dir():
raise ValueError(f"Path is not a directory: {resolved}")
return resolved
# =============================================================================
# Type Definitions
# =============================================================================
class ProjectConfig(TypedDict):
"""Full project configuration response."""
detected_type: str | None
detected_command: str | None
custom_command: str | None
effective_command: str | None
# =============================================================================
# Project Type Definitions
# =============================================================================
# Mapping of project types to their default dev commands
PROJECT_TYPE_COMMANDS: dict[str, str] = {
"nodejs-vite": "npm run dev",
"nodejs-cra": "npm start",
"python-poetry": "poetry run python -m uvicorn main:app --reload",
"python-django": "python manage.py runserver",
"python-fastapi": "python -m uvicorn main:app --reload",
"rust": "cargo run",
"go": "go run .",
}
# =============================================================================
# Configuration File Handling
# =============================================================================
def _get_config_path(project_dir: Path) -> Path:
"""
Get the path to the project config file.
Args:
project_dir: Path to the project directory.
Returns:
Path to the .autocoder/config.json file.
"""
return project_dir / ".autocoder" / "config.json"
def _load_config(project_dir: Path) -> dict:
"""
Load the project configuration from disk.
Args:
project_dir: Path to the project directory.
Returns:
Configuration dictionary, or empty dict if file doesn't exist or is invalid.
"""
config_path = _get_config_path(project_dir)
if not config_path.exists():
return {}
try:
with open(config_path, "r", encoding="utf-8") as f:
config = json.load(f)
if not isinstance(config, dict):
logger.warning(
"Invalid config format in %s: expected dict, got %s",
config_path, type(config).__name__
)
return {}
return config
except json.JSONDecodeError as e:
logger.warning("Failed to parse config at %s: %s", config_path, e)
return {}
except OSError as e:
logger.warning("Failed to read config at %s: %s", config_path, e)
return {}
def _save_config(project_dir: Path, config: dict) -> None:
"""
Save the project configuration to disk.
Creates the .autocoder directory if it doesn't exist.
Args:
project_dir: Path to the project directory.
config: Configuration dictionary to save.
Raises:
OSError: If the file cannot be written.
"""
config_path = _get_config_path(project_dir)
# Ensure the .autocoder directory exists
config_path.parent.mkdir(parents=True, exist_ok=True)
try:
with open(config_path, "w", encoding="utf-8") as f:
json.dump(config, f, indent=2)
logger.debug("Saved config to %s", config_path)
except OSError as e:
logger.error("Failed to save config to %s: %s", config_path, e)
raise
# =============================================================================
# Project Type Detection
# =============================================================================
def _parse_package_json(project_dir: Path) -> dict | None:
"""
Parse package.json if it exists.
Args:
project_dir: Path to the project directory.
Returns:
Parsed package.json as dict, or None if not found or invalid.
"""
package_json_path = project_dir / "package.json"
if not package_json_path.exists():
return None
try:
with open(package_json_path, "r", encoding="utf-8") as f:
data = json.load(f)
if isinstance(data, dict):
return data
return None
except (json.JSONDecodeError, OSError) as e:
logger.debug("Failed to parse package.json in %s: %s", project_dir, e)
return None
def _is_poetry_project(project_dir: Path) -> bool:
"""
Check if pyproject.toml indicates a Poetry project.
Parses pyproject.toml to look for [tool.poetry] section.
Falls back to simple file existence check if tomllib is not available.
Args:
project_dir: Path to the project directory.
Returns:
True if pyproject.toml exists and contains Poetry configuration.
"""
pyproject_path = project_dir / "pyproject.toml"
if not pyproject_path.exists():
return False
# If tomllib is available (Python 3.11+), parse and check for [tool.poetry]
if tomllib is not None:
try:
with open(pyproject_path, "rb") as f:
data = tomllib.load(f)
return "poetry" in data.get("tool", {})
except Exception:
# If parsing fails, fall back to False
return False
# Fallback for older Python: simple file existence check
# This is less accurate but provides backward compatibility
return True
def detect_project_type(project_dir: Path) -> str | None:
"""
Detect the project type by scanning for configuration files.
Detection priority (first match wins):
1. package.json with scripts.dev -> nodejs-vite
2. package.json with scripts.start -> nodejs-cra
3. pyproject.toml with [tool.poetry] -> python-poetry
4. manage.py -> python-django
5. requirements.txt + (main.py or app.py) -> python-fastapi
6. Cargo.toml -> rust
7. go.mod -> go
Args:
project_dir: Path to the project directory.
Returns:
Project type string (e.g., "nodejs-vite", "python-django"),
or None if no known project type is detected.
"""
project_dir = Path(project_dir).resolve()
if not project_dir.exists() or not project_dir.is_dir():
logger.debug("Project directory does not exist: %s", project_dir)
return None
# Check for Node.js projects (package.json)
package_json = _parse_package_json(project_dir)
if package_json is not None:
scripts = package_json.get("scripts", {})
if isinstance(scripts, dict):
# Check for 'dev' script first (typical for Vite, Next.js, etc.)
if "dev" in scripts:
logger.debug("Detected nodejs-vite project in %s", project_dir)
return "nodejs-vite"
# Fall back to 'start' script (typical for CRA)
if "start" in scripts:
logger.debug("Detected nodejs-cra project in %s", project_dir)
return "nodejs-cra"
# Check for Python Poetry project (must have [tool.poetry] in pyproject.toml)
if _is_poetry_project(project_dir):
logger.debug("Detected python-poetry project in %s", project_dir)
return "python-poetry"
# Check for Django project
if (project_dir / "manage.py").exists():
logger.debug("Detected python-django project in %s", project_dir)
return "python-django"
# Check for Python FastAPI project (requirements.txt + main.py or app.py)
if (project_dir / "requirements.txt").exists():
has_main = (project_dir / "main.py").exists()
has_app = (project_dir / "app.py").exists()
if has_main or has_app:
logger.debug("Detected python-fastapi project in %s", project_dir)
return "python-fastapi"
# Check for Rust project
if (project_dir / "Cargo.toml").exists():
logger.debug("Detected rust project in %s", project_dir)
return "rust"
# Check for Go project
if (project_dir / "go.mod").exists():
logger.debug("Detected go project in %s", project_dir)
return "go"
logger.debug("No known project type detected in %s", project_dir)
return None
# =============================================================================
# Dev Command Functions
# =============================================================================
def get_default_dev_command(project_dir: Path) -> str | None:
"""
Get the auto-detected dev command for a project.
This returns the default command based on detected project type,
ignoring any custom command that may be configured.
Args:
project_dir: Path to the project directory.
Returns:
Default dev command string for the detected project type,
or None if no project type is detected.
"""
project_type = detect_project_type(project_dir)
if project_type is None:
return None
return PROJECT_TYPE_COMMANDS.get(project_type)
def get_dev_command(project_dir: Path) -> str | None:
"""
Get the effective dev command for a project.
Returns the custom command if one is configured,
otherwise returns the auto-detected default command.
Args:
project_dir: Path to the project directory.
Returns:
The effective dev command (custom if set, else detected),
or None if neither is available.
"""
project_dir = Path(project_dir).resolve()
# Check for custom command first
config = _load_config(project_dir)
custom_command = config.get("dev_command")
if custom_command and isinstance(custom_command, str):
# Type is narrowed to str by isinstance check
result: str = custom_command
return result
# Fall back to auto-detected command
return get_default_dev_command(project_dir)
def set_dev_command(project_dir: Path, command: str) -> None:
"""
Save a custom dev command for a project.
Args:
project_dir: Path to the project directory.
command: The custom dev command to save.
Raises:
ValueError: If command is empty or not a string, or if project_dir is invalid.
OSError: If the config file cannot be written.
"""
if not command or not isinstance(command, str):
raise ValueError("Command must be a non-empty string")
project_dir = _validate_project_dir(project_dir)
# Load existing config and update
config = _load_config(project_dir)
config["dev_command"] = command
_save_config(project_dir, config)
logger.info("Set custom dev command for %s: %s", project_dir.name, command)
def clear_dev_command(project_dir: Path) -> None:
"""
Remove the custom dev command, reverting to auto-detection.
If no config file exists or no custom command is set,
this function does nothing (no error is raised).
Args:
project_dir: Path to the project directory.
Raises:
ValueError: If project_dir is not a valid directory.
"""
project_dir = _validate_project_dir(project_dir)
config_path = _get_config_path(project_dir)
if not config_path.exists():
return
config = _load_config(project_dir)
if "dev_command" not in config:
return
del config["dev_command"]
# If config is now empty, delete the file
if not config:
try:
config_path.unlink(missing_ok=True)
logger.info("Removed empty config file for %s", project_dir.name)
# Also remove .autocoder directory if empty
autocoder_dir = config_path.parent
if autocoder_dir.exists() and not any(autocoder_dir.iterdir()):
autocoder_dir.rmdir()
logger.debug("Removed empty .autocoder directory for %s", project_dir.name)
except OSError as e:
logger.warning("Failed to clean up config for %s: %s", project_dir.name, e)
else:
_save_config(project_dir, config)
logger.info("Cleared custom dev command for %s", project_dir.name)
def get_project_config(project_dir: Path) -> ProjectConfig:
"""
Get the full project configuration including detection results.
This provides all relevant configuration information in a single call,
useful for displaying in a UI or debugging.
Args:
project_dir: Path to the project directory.
Returns:
ProjectConfig dict with:
- detected_type: The auto-detected project type (or None)
- detected_command: The default command for detected type (or None)
- custom_command: The user-configured custom command (or None)
- effective_command: The command that would actually be used (or None)
Raises:
ValueError: If project_dir is not a valid directory.
"""
project_dir = _validate_project_dir(project_dir)
# Detect project type and get default command
detected_type = detect_project_type(project_dir)
detected_command = PROJECT_TYPE_COMMANDS.get(detected_type) if detected_type else None
# Load custom command from config
config = _load_config(project_dir)
custom_command = config.get("dev_command")
# Validate custom_command is a string
if not isinstance(custom_command, str):
custom_command = None
# Determine effective command
effective_command = custom_command if custom_command else detected_command
return ProjectConfig(
detected_type=detected_type,
detected_command=detected_command,
custom_command=custom_command,
effective_command=effective_command,
)

View File

@@ -0,0 +1,563 @@
"""
Terminal Manager
================
Manages PTY terminal sessions per project with cross-platform support.
Uses winpty (ConPTY) on Windows and built-in pty module on Unix.
"""
import asyncio
import logging
import os
import platform
import shutil
import threading
from pathlib import Path
from typing import Callable, Set
logger = logging.getLogger(__name__)
# Platform detection
IS_WINDOWS = platform.system() == "Windows"
# Conditional imports for PTY support
# Note: Type checking is disabled for cross-platform PTY modules since mypy
# cannot properly handle conditional imports for platform-specific APIs.
if IS_WINDOWS:
try:
from winpty import PtyProcess as WinPtyProcess
WINPTY_AVAILABLE = True
except ImportError:
WinPtyProcess = None
WINPTY_AVAILABLE = False
logger.warning(
"winpty package not installed. Terminal sessions will not be available on Windows. "
"Install with: pip install pywinpty"
)
else:
# Unix systems use built-in pty module
import fcntl
import pty
import select
import signal
import struct
import termios
WINPTY_AVAILABLE = False # Not applicable on Unix
def _get_shell() -> str:
"""
Get the appropriate shell for the current platform.
Returns:
Path to shell executable
"""
if IS_WINDOWS:
# Prefer PowerShell, fall back to cmd.exe
powershell = shutil.which("powershell.exe")
if powershell:
return powershell
cmd = shutil.which("cmd.exe")
if cmd:
return cmd
# Last resort fallback
return "cmd.exe"
else:
# Unix: Use $SHELL environment variable or fall back to /bin/bash
shell = os.environ.get("SHELL")
if shell and shutil.which(shell):
return shell
# Fall back to common shells
for fallback in ["/bin/bash", "/bin/sh"]:
if os.path.exists(fallback):
return fallback
return "/bin/sh"
class TerminalSession:
"""
Manages a single PTY terminal session for a project.
Provides cross-platform PTY support with async output streaming
and multiple output callbacks for WebSocket clients.
"""
def __init__(self, project_name: str, project_dir: Path):
"""
Initialize the terminal session.
Args:
project_name: Name of the project
project_dir: Absolute path to the project directory (used as cwd)
"""
self.project_name = project_name
self.project_dir = project_dir
# PTY process references (platform-specific)
self._pty_process: "WinPtyProcess | None" = None # Windows winpty
self._master_fd: int | None = None # Unix master file descriptor
self._child_pid: int | None = None # Unix child process PID
# State tracking
self._is_active = False
self._output_task: asyncio.Task | None = None
# Output callbacks with thread-safe access
self._output_callbacks: Set[Callable[[bytes], None]] = set()
self._callbacks_lock = threading.Lock()
@property
def is_active(self) -> bool:
"""Check if the terminal session is currently active."""
return self._is_active
@property
def pid(self) -> int | None:
"""Get the PID of the PTY child process."""
if IS_WINDOWS:
if self._pty_process is not None:
try:
pid = self._pty_process.pid
return int(pid) if pid is not None else None
except Exception:
return None
return None
else:
return self._child_pid
def add_output_callback(self, callback: Callable[[bytes], None]) -> None:
"""
Add a callback to receive terminal output.
Args:
callback: Function that receives raw bytes from the PTY
"""
with self._callbacks_lock:
self._output_callbacks.add(callback)
def remove_output_callback(self, callback: Callable[[bytes], None]) -> None:
"""
Remove an output callback.
Args:
callback: The callback to remove
"""
with self._callbacks_lock:
self._output_callbacks.discard(callback)
def _broadcast_output(self, data: bytes) -> None:
"""Broadcast output data to all registered callbacks."""
with self._callbacks_lock:
callbacks = list(self._output_callbacks)
for callback in callbacks:
try:
callback(data)
except Exception as e:
logger.warning(f"Output callback error: {e}")
async def start(self, cols: int = 80, rows: int = 24) -> bool:
"""
Start the PTY terminal session.
Args:
cols: Terminal width in columns
rows: Terminal height in rows
Returns:
True if started successfully, False otherwise
"""
if self._is_active:
logger.warning(f"Terminal session already active for {self.project_name}")
return False
# Validate project directory
if not self.project_dir.exists():
logger.error(f"Project directory does not exist: {self.project_dir}")
return False
if not self.project_dir.is_dir():
logger.error(f"Project path is not a directory: {self.project_dir}")
return False
shell = _get_shell()
cwd = str(self.project_dir.resolve())
try:
if IS_WINDOWS:
return await self._start_windows(shell, cwd, cols, rows)
else:
return await self._start_unix(shell, cwd, cols, rows)
except Exception as e:
logger.exception(f"Failed to start terminal for {self.project_name}: {e}")
return False
async def _start_windows(self, shell: str, cwd: str, cols: int, rows: int) -> bool:
"""Start PTY on Windows using winpty."""
if not WINPTY_AVAILABLE:
logger.error("Cannot start terminal: winpty package not available")
# This error will be caught and sent to the client
raise RuntimeError(
"Terminal requires pywinpty on Windows. Install with: pip install pywinpty"
)
try:
# WinPtyProcess.spawn expects the shell command
self._pty_process = WinPtyProcess.spawn(
shell,
cwd=cwd,
dimensions=(rows, cols),
)
self._is_active = True
# Start output reading task
self._output_task = asyncio.create_task(self._read_output_windows())
logger.info(f"Terminal started for {self.project_name} (PID: {self.pid}, shell: {shell})")
return True
except Exception as e:
logger.exception(f"Failed to start Windows PTY: {e}")
self._pty_process = None
return False
async def _start_unix(self, shell: str, cwd: str, cols: int, rows: int) -> bool:
"""Start PTY on Unix using built-in pty module."""
# Note: This entire method uses Unix-specific APIs that don't exist on Windows.
# Type checking is disabled for these platform-specific calls.
try:
# Fork a new pseudo-terminal
pid, master_fd = pty.fork() # type: ignore[attr-defined]
if pid == 0:
# Child process - exec the shell
os.chdir(cwd)
# Set terminal size (Unix-specific modules imported at top-level)
winsize = struct.pack("HHHH", rows, cols, 0, 0)
fcntl.ioctl(0, termios.TIOCSWINSZ, winsize) # type: ignore[attr-defined]
# Execute the shell
os.execvp(shell, [shell])
os._exit(1) # Fallback if execvp returns (shouldn't happen)
else:
# Parent process
self._master_fd = master_fd
self._child_pid = pid
self._is_active = True
# Set terminal size on master (Unix-specific modules imported at top-level)
winsize = struct.pack("HHHH", rows, cols, 0, 0)
fcntl.ioctl(master_fd, termios.TIOCSWINSZ, winsize) # type: ignore[attr-defined]
# Start output reading task
self._output_task = asyncio.create_task(self._read_output_unix())
logger.info(f"Terminal started for {self.project_name} (PID: {pid}, shell: {shell})")
return True
except Exception as e:
logger.exception(f"Failed to start Unix PTY: {e}")
self._master_fd = None
self._child_pid = None
return False
async def _read_output_windows(self) -> None:
"""Read output from Windows PTY and broadcast to callbacks."""
pty = self._pty_process
if pty is None:
return
loop = asyncio.get_running_loop()
def read_data():
"""Read data from PTY, capturing pty reference to avoid race condition."""
try:
if pty.isalive():
return pty.read(4096)
except Exception:
pass
return b""
try:
while self._is_active and self._pty_process is not None:
try:
# Use run_in_executor for non-blocking read
# winpty read() is blocking, so we need to run it in executor
data = await loop.run_in_executor(None, read_data)
if data:
# winpty may return string, convert to bytes if needed
if isinstance(data, str):
data = data.encode("utf-8", errors="replace")
self._broadcast_output(data)
else:
# Check if process is still alive
if self._pty_process is None or not self._pty_process.isalive():
break
# Small delay to prevent busy loop
await asyncio.sleep(0.01)
except asyncio.CancelledError:
raise
except Exception as e:
if self._is_active:
logger.warning(f"Windows PTY read error: {e}")
break
except asyncio.CancelledError:
pass
finally:
if self._is_active:
self._is_active = False
logger.info(f"Terminal output stream ended for {self.project_name}")
async def _read_output_unix(self) -> None:
"""Read output from Unix PTY and broadcast to callbacks."""
if self._master_fd is None:
return
loop = asyncio.get_running_loop()
try:
while self._is_active and self._master_fd is not None:
try:
# Use run_in_executor with select for non-blocking read
def read_with_select():
if self._master_fd is None:
return b""
try:
# Wait up to 100ms for data
readable, _, _ = select.select([self._master_fd], [], [], 0.1)
if readable:
return os.read(self._master_fd, 4096)
return b""
except (OSError, ValueError):
return b""
data = await loop.run_in_executor(None, read_with_select)
if data:
self._broadcast_output(data)
elif not self._check_child_alive():
break
except asyncio.CancelledError:
raise
except Exception as e:
if self._is_active:
logger.warning(f"Unix PTY read error: {e}")
break
except asyncio.CancelledError:
pass
finally:
if self._is_active:
self._is_active = False
logger.info(f"Terminal output stream ended for {self.project_name}")
# Reap zombie if not already reaped
if self._child_pid is not None:
try:
os.waitpid(self._child_pid, os.WNOHANG)
except ChildProcessError:
pass
except Exception:
pass
def _check_child_alive(self) -> bool:
"""Check if the Unix child process is still alive."""
if self._child_pid is None:
return False
try:
# Use signal 0 to check if process exists without reaping it.
# This avoids race conditions with os.waitpid which can reap the process.
os.kill(self._child_pid, 0)
return True
except OSError:
return False
def write(self, data: bytes) -> None:
"""
Write input data to the PTY.
Args:
data: Raw bytes to write to the terminal
"""
if not self._is_active:
logger.warning(f"Cannot write to inactive terminal for {self.project_name}")
return
try:
if IS_WINDOWS:
if self._pty_process is not None:
# winpty expects string input
text = data.decode("utf-8", errors="replace")
self._pty_process.write(text)
else:
if self._master_fd is not None:
os.write(self._master_fd, data)
except Exception as e:
logger.warning(f"Failed to write to PTY: {e}")
def resize(self, cols: int, rows: int) -> None:
"""
Resize the terminal.
Args:
cols: New terminal width in columns
rows: New terminal height in rows
"""
if not self._is_active:
return
try:
if IS_WINDOWS:
if self._pty_process is not None:
self._pty_process.setwinsize(rows, cols)
else:
if self._master_fd is not None:
# Unix-specific modules imported at top-level
winsize = struct.pack("HHHH", rows, cols, 0, 0)
fcntl.ioctl(self._master_fd, termios.TIOCSWINSZ, winsize) # type: ignore[attr-defined]
logger.debug(f"Terminal resized for {self.project_name}: {cols}x{rows}")
except Exception as e:
logger.warning(f"Failed to resize terminal: {e}")
async def stop(self) -> None:
"""Stop the terminal session and clean up resources."""
if not self._is_active:
return
self._is_active = False
# Cancel output reading task
if self._output_task is not None:
self._output_task.cancel()
try:
await self._output_task
except asyncio.CancelledError:
pass
self._output_task = None
try:
if IS_WINDOWS:
await self._stop_windows()
else:
await self._stop_unix()
except Exception as e:
logger.warning(f"Error stopping terminal: {e}")
logger.info(f"Terminal stopped for {self.project_name}")
async def _stop_windows(self) -> None:
"""Stop Windows PTY process."""
if self._pty_process is None:
return
try:
if self._pty_process.isalive():
self._pty_process.terminate()
# Give it a moment to terminate
await asyncio.sleep(0.1)
if self._pty_process.isalive():
self._pty_process.kill()
except Exception as e:
logger.warning(f"Error terminating Windows PTY: {e}")
finally:
self._pty_process = None
async def _stop_unix(self) -> None:
"""Stop Unix PTY process."""
# Note: This method uses Unix-specific signal handling (signal imported at top-level)
# Close master file descriptor
if self._master_fd is not None:
try:
os.close(self._master_fd)
except OSError:
pass
self._master_fd = None
# Terminate child process
if self._child_pid is not None:
try:
os.kill(self._child_pid, signal.SIGTERM)
# Wait briefly for graceful shutdown
await asyncio.sleep(0.1)
# Check if still running and force kill if needed
try:
os.kill(self._child_pid, 0) # Check if process exists
# SIGKILL is Unix-specific (Windows would use SIGTERM)
os.kill(self._child_pid, signal.SIGKILL) # type: ignore[attr-defined]
except ProcessLookupError:
pass # Already terminated
# Reap the child process to prevent zombie
try:
os.waitpid(self._child_pid, 0)
except ChildProcessError:
pass
except ProcessLookupError:
pass # Already terminated
except Exception as e:
logger.warning(f"Error terminating Unix PTY child: {e}")
finally:
self._child_pid = None
# Global registry of terminal sessions per project with thread safety
_sessions: dict[str, TerminalSession] = {}
_sessions_lock = threading.Lock()
def get_terminal_session(project_name: str, project_dir: Path) -> TerminalSession:
"""
Get or create a terminal session for a project (thread-safe).
Args:
project_name: Name of the project
project_dir: Absolute path to the project directory
Returns:
TerminalSession instance for the project
"""
with _sessions_lock:
if project_name not in _sessions:
_sessions[project_name] = TerminalSession(project_name, project_dir)
return _sessions[project_name]
def remove_terminal_session(project_name: str) -> TerminalSession | None:
"""
Remove a terminal session from the registry.
Args:
project_name: Name of the project
Returns:
The removed session, or None if not found
"""
with _sessions_lock:
return _sessions.pop(project_name, None)
async def cleanup_all_terminals() -> None:
"""
Stop all active terminal sessions.
Called on server shutdown to ensure all PTY processes are terminated.
"""
with _sessions_lock:
sessions = list(_sessions.values())
for session in sessions:
try:
if session.is_active:
await session.stop()
except Exception as e:
logger.warning(f"Error stopping terminal for {session.project_name}: {e}")
with _sessions_lock:
_sessions.clear()
logger.info("All terminal sessions cleaned up")

View File

@@ -2,7 +2,7 @@
WebSocket Handlers
==================
Real-time updates for project progress and agent output.
Real-time updates for project progress, agent output, and dev server output.
"""
import asyncio
@@ -15,6 +15,7 @@ from typing import Set
from fastapi import WebSocket, WebSocketDisconnect
from .services.dev_server_manager import get_devserver_manager
from .services.process_manager import get_manager
# Lazy imports
@@ -195,16 +196,52 @@ async def project_websocket(websocket: WebSocket, project_name: str):
agent_manager.add_output_callback(on_output)
agent_manager.add_status_callback(on_status_change)
# Get dev server manager and register callbacks
devserver_manager = get_devserver_manager(project_name, project_dir)
async def on_dev_output(line: str):
"""Handle dev server output - broadcast to this WebSocket."""
try:
await websocket.send_json({
"type": "dev_log",
"line": line,
"timestamp": datetime.now().isoformat(),
})
except Exception:
pass # Connection may be closed
async def on_dev_status_change(status: str):
"""Handle dev server status change - broadcast to this WebSocket."""
try:
await websocket.send_json({
"type": "dev_server_status",
"status": status,
"url": devserver_manager.detected_url,
})
except Exception:
pass # Connection may be closed
# Register dev server callbacks
devserver_manager.add_output_callback(on_dev_output)
devserver_manager.add_status_callback(on_dev_status_change)
# Start progress polling task
poll_task = asyncio.create_task(poll_progress(websocket, project_name, project_dir))
try:
# Send initial status
# Send initial agent status
await websocket.send_json({
"type": "agent_status",
"status": agent_manager.status,
})
# Send initial dev server status
await websocket.send_json({
"type": "dev_server_status",
"status": devserver_manager.status,
"url": devserver_manager.detected_url,
})
# Send initial progress
count_passing_tests = _get_count_passing_tests()
passing, in_progress, total = count_passing_tests(project_dir)
@@ -244,9 +281,13 @@ async def project_websocket(websocket: WebSocket, project_name: str):
except asyncio.CancelledError:
pass
# Unregister callbacks
# Unregister agent callbacks
agent_manager.remove_output_callback(on_output)
agent_manager.remove_status_callback(on_status_change)
# Unregister dev server callbacks
devserver_manager.remove_output_callback(on_dev_output)
devserver_manager.remove_status_callback(on_dev_status_change)
# Disconnect from manager
await manager.disconnect(websocket, project_name)