Fix branching and add move_arm builtin

- Branching: mark source step as completed when jumping to prevent revisiting
- Add move_arm as builtin for arm control
This commit is contained in:
2026-03-21 19:09:26 -04:00
parent 4a9abf4ff1
commit 31d2173703
2 changed files with 28 additions and 0 deletions

View File

@@ -600,6 +600,13 @@ export const WizardInterface = React.memo(function WizardInterface({
setCompletedActionsCount(0); setCompletedActionsCount(0);
setCurrentStepIndex(targetIndex); setCurrentStepIndex(targetIndex);
setLastResponse(null); setLastResponse(null);
// Mark source step as completed so it won't be revisited
setCompletedSteps((prev) => {
const next = new Set(prev);
next.add(currentStepIndex);
return next;
});
return; return;
} }
} }

View File

@@ -504,6 +504,27 @@ export class WizardRosService extends EventEmitter {
await new Promise((resolve) => setTimeout(resolve, 1000)); await new Promise((resolve) => setTimeout(resolve, 1000));
break; break;
case "move_arm":
const arm = String(parameters.arm || "right");
const prefix = arm.toLowerCase() === "left" ? "L" : "R";
this.publish("/joint_angles", "naoqi_bridge_msgs/JointAnglesWithSpeed", {
joint_names: [
`${prefix}ShoulderPitch`,
`${prefix}ShoulderRoll`,
`${prefix}ElbowYaw`,
`${prefix}ElbowRoll`,
],
joint_angles: [
Number(parameters.shoulder_pitch) || 0,
Number(parameters.shoulder_roll) || 0,
Number(parameters.elbow_yaw) || 0,
Number(parameters.elbow_roll) || 0,
],
speed: Number(parameters.speed) || 0.3,
});
await new Promise((resolve) => setTimeout(resolve, 1000));
break;
case "emergency_stop": case "emergency_stop":
this.publish("/cmd_vel", "geometry_msgs/Twist", { this.publish("/cmd_vel", "geometry_msgs/Twist", {
linear: { x: 0, y: 0, z: 0 }, linear: { x: 0, y: 0, z: 0 },