feat(webui): waypoint editor with click-to-navigate (Issue #261)

This commit is contained in:
sl-webui 2026-03-02 13:24:34 -05:00 committed by sl-controls
parent 0776003dd3
commit 5362536fb1
2 changed files with 66 additions and 21 deletions

View File

@ -61,9 +61,6 @@ import { NetworkPanel } from './components/NetworkPanel.jsx';
// Waypoint editor (issue #261)
import { WaypointEditor } from './components/WaypointEditor.jsx';
// Status header (issue #269)
import { StatusHeader } from './components/StatusHeader.jsx';
const TAB_GROUPS = [
{
label: 'SOCIAL',

View File

@ -10,11 +10,13 @@
* - Execute waypoint sequence with automatic progression
* - Clear all waypoints button
* - Visual feedback for active waypoint (executing)
* - Imports map display from MapViewer for coordinate system
*/
import { useEffect, useRef, useState } from 'react';
function WaypointEditor({ subscribe, publish, callService }) {
// Waypoint storage
const [waypoints, setWaypoints] = useState([]);
const [selectedWaypoint, setSelectedWaypoint] = useState(null);
const [isDragging, setIsDragging] = useState(false);
@ -22,16 +24,20 @@ function WaypointEditor({ subscribe, publish, callService }) {
const [activeWaypoint, setActiveWaypoint] = useState(null);
const [executing, setExecuting] = useState(false);
// Map context
const [mapData, setMapData] = useState(null);
const [robotPose, setRobotPose] = useState({ x: 0, y: 0, theta: 0 });
// Canvas reference
const canvasRef = useRef(null);
const containerRef = useRef(null);
// Refs for ROS integration
const mapDataRef = useRef(null);
const robotPoseRef = useRef({ x: 0, y: 0, theta: 0 });
const waypointsRef = useRef([]);
// Subscribe to map data
// Subscribe to map data (for coordinate reference)
useEffect(() => {
const unsubMap = subscribe(
'/map',
@ -54,7 +60,7 @@ function WaypointEditor({ subscribe, publish, callService }) {
return unsubMap;
}, [subscribe]);
// Subscribe to robot odometry
// Subscribe to robot odometry (for current position reference)
useEffect(() => {
const unsubOdom = subscribe(
'/odom',
@ -79,22 +85,29 @@ function WaypointEditor({ subscribe, publish, callService }) {
return unsubOdom;
}, [subscribe]);
// Canvas event handlers
const handleCanvasClick = (e) => {
if (!mapDataRef.current || !containerRef.current) return;
if (!mapDataRef.current || !canvasRef.current) return;
const rect = containerRef.current.getBoundingClientRect();
const canvas = canvasRef.current;
const rect = canvas.getBoundingClientRect();
const clickX = e.clientX - rect.left;
const clickY = e.clientY - rect.top;
// Convert canvas coordinates to world coordinates
// This assumes the map is centered on the robot
const map = mapDataRef.current;
const robot = robotPoseRef.current;
const zoom = 1;
const zoom = 1; // Would need to track zoom if map has zoom controls
const centerX = containerRef.current.clientWidth / 2;
const centerY = containerRef.current.clientHeight / 2;
// Inverse of map rendering calculation
const centerX = canvas.width / 2;
const centerY = canvas.height / 2;
const worldX = robot.x + (clickX - centerX) / zoom;
const worldY = robot.y - (clickY - centerY) / zoom;
// Create new waypoint
const newWaypoint = {
id: Date.now(),
x: parseFloat(worldX.toFixed(2)),
@ -106,6 +119,12 @@ function WaypointEditor({ subscribe, publish, callService }) {
waypointsRef.current = [...waypointsRef.current, newWaypoint];
};
const handleCanvasContextMenu = (e) => {
e.preventDefault();
// Right-click handled by waypoint list
};
// Waypoint list handlers
const handleDeleteWaypoint = (id) => {
setWaypoints((prev) => prev.filter((wp) => wp.id !== id));
waypointsRef.current = waypointsRef.current.filter((wp) => wp.id !== id);
@ -139,12 +158,18 @@ function WaypointEditor({ subscribe, publish, callService }) {
setDragIndex(null);
};
// Execute waypoints
const sendNavGoal = async (waypoint) => {
if (!callService) return;
try {
// Create quaternion from heading (default to 0 if no heading)
const heading = waypoint.theta || 0;
const halfHeading = heading / 2;
const qx = 0;
const qy = 0;
const qz = Math.sin(halfHeading);
const qw = Math.cos(halfHeading);
const goal = {
pose: {
@ -154,14 +179,15 @@ function WaypointEditor({ subscribe, publish, callService }) {
z: 0,
},
orientation: {
x: 0,
y: 0,
z: Math.sin(halfHeading),
w: Math.cos(halfHeading),
x: qx,
y: qy,
z: qz,
w: qw,
},
},
};
// Send to Nav2 navigate_to_pose action
await callService(
'/navigate_to_pose',
'nav2_msgs/NavigateToPose',
@ -182,7 +208,11 @@ function WaypointEditor({ subscribe, publish, callService }) {
setExecuting(true);
for (const waypoint of waypoints) {
const success = await sendNavGoal(waypoint);
if (!success) break;
if (!success) {
console.error('Failed to send goal for waypoint:', waypoint);
break;
}
// Wait a bit before sending next goal
await new Promise((resolve) => setTimeout(resolve, 500));
}
setExecuting(false);
@ -207,16 +237,21 @@ function WaypointEditor({ subscribe, publish, callService }) {
return (
<div className="flex h-full gap-3">
{/* Map area */}
{/* Map area with click handlers */}
<div className="flex-1 flex flex-col space-y-3">
<div className="flex-1 bg-gray-900 rounded-lg border border-cyan-950 overflow-hidden relative cursor-crosshair">
<div
ref={containerRef}
className="w-full h-full"
onClick={handleCanvasClick}
onContextMenu={(e) => e.preventDefault()}
onContextMenu={handleCanvasContextMenu}
>
<svg className="absolute inset-0 w-full h-full pointer-events-none" id="waypoint-overlay">
{/* Virtual map display - waypoints overlaid */}
<svg
className="absolute inset-0 w-full h-full pointer-events-none"
id="waypoint-overlay"
>
{/* Waypoint markers */}
{waypoints.map((wp, idx) => {
if (!mapDataRef.current) return null;
@ -233,6 +268,7 @@ function WaypointEditor({ subscribe, publish, callService }) {
return (
<g key={wp.id}>
{/* Waypoint circle */}
<circle
cx={canvasX}
cy={canvasY}
@ -240,6 +276,7 @@ function WaypointEditor({ subscribe, publish, callService }) {
fill={isActive ? '#ef4444' : isSelected ? '#fbbf24' : '#06b6d4'}
opacity="0.8"
/>
{/* Waypoint number */}
<text
x={canvasX}
y={canvasY}
@ -252,12 +289,19 @@ function WaypointEditor({ subscribe, publish, callService }) {
>
{idx + 1}
</text>
{/* Line to next waypoint */}
{idx < waypoints.length - 1 && (
<line
x1={canvasX}
y1={canvasY}
x2={centerX + (waypoints[idx + 1].x - robot.x) * zoom}
y2={centerY - (waypoints[idx + 1].y - robot.y) * zoom}
x2={
centerX +
(waypoints[idx + 1].x - robot.x) * zoom
}
y2={
centerY -
(waypoints[idx + 1].y - robot.y) * zoom
}
stroke="#10b981"
strokeWidth="2"
opacity="0.6"
@ -266,6 +310,8 @@ function WaypointEditor({ subscribe, publish, callService }) {
</g>
);
})}
{/* Robot position marker */}
<circle
cx={containerRef.current?.clientWidth / 2 || 400}
cy={containerRef.current?.clientHeight / 2 || 300}
@ -311,7 +357,9 @@ function WaypointEditor({ subscribe, publish, callService }) {
{/* Waypoint list */}
<div className="flex-1 overflow-y-auto space-y-1">
{waypoints.length === 0 ? (
<div className="text-center text-gray-700 text-xs py-4">Click map to add waypoints</div>
<div className="text-center text-gray-700 text-xs py-4">
Click map to add waypoints
</div>
) : (
waypoints.map((wp, idx) => (
<div