Georg commited on
Commit ·
a75f112
1
Parent(s): 802f2c1
Implement Nova API jogging support and enhance UI controls
Browse files- Added support for bidirectional jogging control via the Nova API, allowing users to send jogging commands for joint and cartesian movements.
- Enhanced mujoco_server.py to handle new jogging commands and integrate with the Nova API for real-time control.
- Updated the UR5 environment to initialize and manage the NovaJogger for handling jogging operations.
- Improved the UI to include jogging controls for translation and rotation, providing users with intuitive interaction options.
- Enhanced README.md to document the new jogging features and usage modes, including Digital Twin, Nova IK, and Hybrid modes.
- Introduced test scripts for validating Nova API connections and jogging functionality, improving overall reliability and user experience.
- README.md +24 -10
- mujoco_server.py +230 -116
- robots/ur5/nova_api.py +13 -2
- robots/ur5/nova_jogger.py +291 -0
- robots/ur5/ur5_env.py +102 -7
- scripts/test_jogger.py +198 -0
- scripts/test_state_stream.py +97 -0
- tests/__init__.py +0 -0
- tests/test_nova_api.py +303 -0
README.md
CHANGED
|
@@ -573,10 +573,20 @@ Nova API integration provides two key features:
|
|
| 573 |
python3 scripts/test_nova_connection.py
|
| 574 |
```
|
| 575 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 576 |
### Usage Examples
|
| 577 |
|
| 578 |
-
####
|
| 579 |
-
|
| 580 |
|
| 581 |
```python
|
| 582 |
import os
|
|
@@ -598,8 +608,8 @@ env = UR5Env(
|
|
| 598 |
render_mode="human",
|
| 599 |
scene_name="scene",
|
| 600 |
nova_api_config={
|
| 601 |
-
"use_state_stream": True, #
|
| 602 |
-
"use_ik": False #
|
| 603 |
}
|
| 604 |
)
|
| 605 |
|
|
@@ -610,8 +620,8 @@ for _ in range(1000):
|
|
| 610 |
env.close()
|
| 611 |
```
|
| 612 |
|
| 613 |
-
####
|
| 614 |
-
Use Nova's IK solver while
|
| 615 |
|
| 616 |
```python
|
| 617 |
env = UR5Env(
|
|
@@ -626,19 +636,23 @@ env = UR5Env(
|
|
| 626 |
env.set_target(x=0.4, y=0.2, z=0.6)
|
| 627 |
```
|
| 628 |
|
| 629 |
-
####
|
| 630 |
-
Enable both state streaming and Nova IK:
|
| 631 |
|
| 632 |
```python
|
| 633 |
env = UR5Env(
|
| 634 |
render_mode="human",
|
| 635 |
nova_api_config={
|
| 636 |
-
"use_state_stream": True, #
|
| 637 |
-
"use_ik": True #
|
| 638 |
}
|
| 639 |
)
|
| 640 |
```
|
| 641 |
|
|
|
|
|
|
|
|
|
|
|
|
|
| 642 |
### Environment Variables Reference
|
| 643 |
|
| 644 |
| Variable | Required | Default | Description |
|
|
|
|
| 573 |
python3 scripts/test_nova_connection.py
|
| 574 |
```
|
| 575 |
|
| 576 |
+
### Usage Modes
|
| 577 |
+
|
| 578 |
+
Nova API integration supports three distinct modes:
|
| 579 |
+
|
| 580 |
+
1. **Digital Twin Mode** (State Streaming Only - Recommended): The simulation mirrors a real robot's state. Robot movements come from the physical robot via WebSocket. Local target controls are ignored. This is the default when `.env.local` is detected.
|
| 581 |
+
|
| 582 |
+
2. **Nova IK Mode** (IK Only): Use Nova's cloud-based IK solver while controlling the simulation robot locally. Useful for validating IK solutions or when you want to use Nova's kinematic model.
|
| 583 |
+
|
| 584 |
+
3. **Hybrid Mode** (Both): Uses Nova state streaming and Nova IK. Generally not recommended since the real robot is controlled externally.
|
| 585 |
+
|
| 586 |
### Usage Examples
|
| 587 |
|
| 588 |
+
#### Digital Twin Mode (State Streaming Only - Default)
|
| 589 |
+
Mirror a real robot's state in the simulation:
|
| 590 |
|
| 591 |
```python
|
| 592 |
import os
|
|
|
|
| 608 |
render_mode="human",
|
| 609 |
scene_name="scene",
|
| 610 |
nova_api_config={
|
| 611 |
+
"use_state_stream": True, # Mirror real robot state
|
| 612 |
+
"use_ik": False # Real robot controlled externally
|
| 613 |
}
|
| 614 |
)
|
| 615 |
|
|
|
|
| 620 |
env.close()
|
| 621 |
```
|
| 622 |
|
| 623 |
+
#### Nova IK Mode (IK Only)
|
| 624 |
+
Use Nova's cloud-based IK solver while controlling the simulation robot locally:
|
| 625 |
|
| 626 |
```python
|
| 627 |
env = UR5Env(
|
|
|
|
| 636 |
env.set_target(x=0.4, y=0.2, z=0.6)
|
| 637 |
```
|
| 638 |
|
| 639 |
+
#### Hybrid Mode (Not Recommended)
|
| 640 |
+
Enable both state streaming and Nova IK. Generally not useful since the real robot is controlled externally:
|
| 641 |
|
| 642 |
```python
|
| 643 |
env = UR5Env(
|
| 644 |
render_mode="human",
|
| 645 |
nova_api_config={
|
| 646 |
+
"use_state_stream": True, # Mirror real robot
|
| 647 |
+
"use_ik": True # Also use Nova IK (usually not needed)
|
| 648 |
}
|
| 649 |
)
|
| 650 |
```
|
| 651 |
|
| 652 |
+
**Note**: When state streaming is enabled, the simulation becomes a read-only digital twin that displays the real robot's movements. Local target controls and IK computations are ignored since the robot is controlled by external hardware/software.
|
| 653 |
+
|
| 654 |
+
**Sending Commands to Robot**: To send motion commands to the real robot through Nova API, use Nova's motion execution endpoints directly (not currently implemented in the web UI). The simulation is designed to visualize robot state, not to command it.
|
| 655 |
+
|
| 656 |
### Environment Variables Reference
|
| 657 |
|
| 658 |
| Variable | Required | Default | Description |
|
mujoco_server.py
CHANGED
|
@@ -170,10 +170,15 @@ def init_ur5(scene_name="scene"):
|
|
| 170 |
# Check if Nova API is configured via environment variables
|
| 171 |
nova_config = None
|
| 172 |
if os.getenv('NOVA_INSTANCE_URL') and os.getenv('NOVA_ACCESS_TOKEN'):
|
| 173 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
| 174 |
nova_config = {
|
| 175 |
"use_state_stream": True,
|
| 176 |
-
"use_ik":
|
|
|
|
| 177 |
}
|
| 178 |
|
| 179 |
if scene_name == "scene_t_push":
|
|
@@ -272,9 +277,11 @@ def broadcast_state():
|
|
| 272 |
use_orientation = env.get_use_orientation()
|
| 273 |
|
| 274 |
# Check Nova API status
|
|
|
|
| 275 |
nova_state_streaming = getattr(env, '_use_nova_state_stream', False)
|
| 276 |
nova_ik = getattr(env, '_use_nova_ik', False)
|
| 277 |
-
|
|
|
|
| 278 |
|
| 279 |
state_msg = json.dumps({
|
| 280 |
'type': 'state',
|
|
@@ -535,6 +542,22 @@ def handle_ws_message(data):
|
|
| 535 |
if env is not None and current_robot in ("ur5", "ur5_t_push"):
|
| 536 |
env.set_use_orientation(use)
|
| 537 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 538 |
|
| 539 |
def _serialize_space(space):
|
| 540 |
if hasattr(space, "low") and hasattr(space, "high"):
|
|
@@ -927,6 +950,55 @@ def index():
|
|
| 927 |
.ik-controls.active, .joint-controls.active { display: block; }
|
| 928 |
.joint-sliders .slider-row { margin-bottom: 6px; }
|
| 929 |
.joint-sliders label { width: 40px; display: inline-block; font-size: 0.75em; }
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 930 |
</style>
|
| 931 |
</head>
|
| 932 |
<body>
|
|
@@ -953,6 +1025,12 @@ def index():
|
|
| 953 |
Reward: <span id="arm_reward">-</span><br>
|
| 954 |
Mode: <span id="control_mode_display">IK</span> | Steps: <span id="arm_step_val">0</span><br>
|
| 955 |
<div style="margin-top: 8px; padding-top: 8px; border-top: 1px solid rgba(188, 190, 236, 0.2);">
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 956 |
<strong style="font-size: 0.9em;">Controllers:</strong><br>
|
| 957 |
<span style="font-size: 0.85em;">
|
| 958 |
State: <span id="nova_state_controller" style="color: var(--wb-highlight);">Internal</span><br>
|
|
@@ -1032,87 +1110,107 @@ def index():
|
|
| 1032 |
<!-- IK Controls -->
|
| 1033 |
<div class="ik-controls active" id="ik_controls">
|
| 1034 |
<div class="control-group">
|
| 1035 |
-
<label>
|
| 1036 |
-
<div class="
|
| 1037 |
-
<div class="
|
| 1038 |
-
<label>X</label>
|
| 1039 |
-
<
|
| 1040 |
-
<span class="val-display" id="
|
|
|
|
| 1041 |
</div>
|
| 1042 |
-
<div class="
|
| 1043 |
-
<label>Y</label>
|
| 1044 |
-
<
|
| 1045 |
-
<span class="val-display" id="
|
|
|
|
| 1046 |
</div>
|
| 1047 |
-
<div class="
|
| 1048 |
-
<label>Z</label>
|
| 1049 |
-
<
|
| 1050 |
-
<span class="val-display" id="
|
|
|
|
| 1051 |
</div>
|
| 1052 |
</div>
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1053 |
</div>
|
| 1054 |
<div class="control-group">
|
| 1055 |
-
<label
|
| 1056 |
-
|
| 1057 |
-
<
|
| 1058 |
-
|
| 1059 |
-
|
| 1060 |
-
|
| 1061 |
-
|
| 1062 |
-
<label>R</label>
|
| 1063 |
-
<input type="range" id="target_roll" min="-3.14" max="3.14" step="0.05" value="0.0" oninput="updateOrientation()">
|
| 1064 |
-
<span class="val-display" id="target_roll_val">0.00</span>
|
| 1065 |
</div>
|
| 1066 |
-
<div class="
|
| 1067 |
-
<label>
|
| 1068 |
-
<
|
| 1069 |
-
<span class="val-display" id="
|
|
|
|
| 1070 |
</div>
|
| 1071 |
-
<div class="
|
| 1072 |
-
<label>
|
| 1073 |
-
<
|
| 1074 |
-
<span class="val-display" id="
|
|
|
|
| 1075 |
</div>
|
| 1076 |
</div>
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1077 |
</div>
|
| 1078 |
</div>
|
| 1079 |
|
| 1080 |
<!-- Joint Controls -->
|
| 1081 |
<div class="joint-controls" id="joint_controls">
|
| 1082 |
<div class="control-group">
|
| 1083 |
-
<label>Joint Positions
|
| 1084 |
-
<div class="
|
| 1085 |
-
<div class="
|
| 1086 |
<label>J1</label>
|
| 1087 |
-
<
|
| 1088 |
<span class="val-display" id="joint_0_val">-1.57</span>
|
|
|
|
| 1089 |
</div>
|
| 1090 |
-
<div class="
|
| 1091 |
<label>J2</label>
|
| 1092 |
-
<
|
| 1093 |
<span class="val-display" id="joint_1_val">-1.57</span>
|
|
|
|
| 1094 |
</div>
|
| 1095 |
-
<div class="
|
| 1096 |
<label>J3</label>
|
| 1097 |
-
<
|
| 1098 |
<span class="val-display" id="joint_2_val">1.57</span>
|
|
|
|
| 1099 |
</div>
|
| 1100 |
-
<div class="
|
| 1101 |
<label>J4</label>
|
| 1102 |
-
<
|
| 1103 |
<span class="val-display" id="joint_3_val">-1.57</span>
|
|
|
|
| 1104 |
</div>
|
| 1105 |
-
<div class="
|
| 1106 |
<label>J5</label>
|
| 1107 |
-
<
|
| 1108 |
<span class="val-display" id="joint_4_val">-1.57</span>
|
|
|
|
| 1109 |
</div>
|
| 1110 |
-
<div class="
|
| 1111 |
<label>J6</label>
|
| 1112 |
-
<
|
| 1113 |
<span class="val-display" id="joint_5_val">0.00</span>
|
|
|
|
| 1114 |
</div>
|
| 1115 |
</div>
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1116 |
<button style="margin-top: 8px; width: 100%;" onclick="goToHome()">Go to Home Position</button>
|
| 1117 |
</div>
|
| 1118 |
</div>
|
|
@@ -1151,7 +1249,7 @@ def index():
|
|
| 1151 |
'g1': '29 DOF humanoid with RL walking policy',
|
| 1152 |
'spot': '12 DOF quadruped with trot gait controller',
|
| 1153 |
'ur5': '6 DOF robot arm with Robotiq gripper',
|
| 1154 |
-
'ur5_t_push': 'UR5e T-push task with stick tool
|
| 1155 |
};
|
| 1156 |
|
| 1157 |
const robotTitles = {
|
|
@@ -1247,37 +1345,28 @@ def index():
|
|
| 1247 |
const jp = data.joint_positions;
|
| 1248 |
document.getElementById('joint_pos_display').innerText =
|
| 1249 |
jp.map(j => j.toFixed(2)).join(', ');
|
| 1250 |
-
}
|
| 1251 |
|
| 1252 |
-
|
| 1253 |
-
if (data.joint_targets) {
|
| 1254 |
-
const jt = data.joint_targets;
|
| 1255 |
for (let i = 0; i < 6; i++) {
|
| 1256 |
-
document.getElementById('joint_' + i).
|
| 1257 |
-
document.getElementById('joint_' + i + '_val').innerText = jt[i].toFixed(2);
|
| 1258 |
}
|
| 1259 |
}
|
| 1260 |
|
| 1261 |
-
//
|
| 1262 |
-
if (data.
|
| 1263 |
-
const
|
| 1264 |
-
document.getElementById('
|
| 1265 |
-
document.getElementById('
|
| 1266 |
-
document.getElementById('
|
| 1267 |
-
document.getElementById('target_y_val').innerText = target.y.toFixed(2);
|
| 1268 |
-
document.getElementById('target_z').value = target.z;
|
| 1269 |
-
document.getElementById('target_z_val').innerText = target.z.toFixed(2);
|
| 1270 |
}
|
| 1271 |
|
| 1272 |
-
//
|
| 1273 |
-
if (data.
|
| 1274 |
-
const
|
| 1275 |
-
|
| 1276 |
-
document.getElementById('
|
| 1277 |
-
document.getElementById('
|
| 1278 |
-
document.getElementById('
|
| 1279 |
-
document.getElementById('target_yaw').value = ori.yaw;
|
| 1280 |
-
document.getElementById('target_yaw_val').innerText = ori.yaw.toFixed(2);
|
| 1281 |
}
|
| 1282 |
|
| 1283 |
// Update control mode display
|
|
@@ -1290,22 +1379,26 @@ def index():
|
|
| 1290 |
}
|
| 1291 |
}
|
| 1292 |
|
| 1293 |
-
// Sync use_orientation checkbox
|
| 1294 |
-
if (data.use_orientation !== undefined) {
|
| 1295 |
-
const checkbox = document.getElementById('use_orientation');
|
| 1296 |
-
if (checkbox.checked !== data.use_orientation) {
|
| 1297 |
-
checkbox.checked = data.use_orientation;
|
| 1298 |
-
document.getElementById('orientation_sliders').style.opacity = data.use_orientation ? '1' : '0.4';
|
| 1299 |
-
}
|
| 1300 |
-
}
|
| 1301 |
-
|
| 1302 |
// Update Nova API controller status
|
| 1303 |
if (data.nova_api) {
|
| 1304 |
const stateController = document.getElementById('nova_state_controller');
|
| 1305 |
const ikController = document.getElementById('nova_ik_controller');
|
|
|
|
| 1306 |
|
| 1307 |
if (data.nova_api.connected) {
|
| 1308 |
-
// Nova API is connected
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1309 |
if (data.nova_api.state_streaming) {
|
| 1310 |
stateController.innerText = 'Nova API';
|
| 1311 |
stateController.style.color = 'var(--wb-success)';
|
|
@@ -1322,7 +1415,8 @@ def index():
|
|
| 1322 |
ikController.style.color = 'var(--wb-highlight)';
|
| 1323 |
}
|
| 1324 |
} else {
|
| 1325 |
-
// Nova API not connected -
|
|
|
|
| 1326 |
stateController.innerText = 'Internal';
|
| 1327 |
stateController.style.color = 'var(--wb-highlight)';
|
| 1328 |
ikController.innerText = 'Internal';
|
|
@@ -1461,49 +1555,69 @@ def index():
|
|
| 1461 |
document.getElementById('joint_controls').classList.toggle('active', mode === 'joint');
|
| 1462 |
}
|
| 1463 |
|
| 1464 |
-
|
| 1465 |
-
|
| 1466 |
-
|
| 1467 |
-
|
| 1468 |
-
|
| 1469 |
-
|
| 1470 |
-
document.getElementById('
|
| 1471 |
-
|
| 1472 |
}
|
| 1473 |
|
| 1474 |
-
function
|
| 1475 |
-
|
| 1476 |
-
|
| 1477 |
-
const yaw = parseFloat(document.getElementById('target_yaw').value);
|
| 1478 |
-
document.getElementById('target_roll_val').innerText = roll.toFixed(2);
|
| 1479 |
-
document.getElementById('target_pitch_val').innerText = pitch.toFixed(2);
|
| 1480 |
-
document.getElementById('target_yaw_val').innerText = yaw.toFixed(2);
|
| 1481 |
-
send('arm_orientation', {roll, pitch, yaw});
|
| 1482 |
}
|
| 1483 |
|
| 1484 |
-
function
|
| 1485 |
-
|
| 1486 |
-
document.getElementById('
|
| 1487 |
-
send('use_orientation', {enabled});
|
| 1488 |
}
|
| 1489 |
|
| 1490 |
-
function
|
| 1491 |
-
|
| 1492 |
-
|
| 1493 |
-
|
| 1494 |
-
|
| 1495 |
-
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1496 |
}
|
| 1497 |
-
|
|
|
|
|
|
|
|
|
|
| 1498 |
}
|
| 1499 |
|
| 1500 |
function goToHome() {
|
| 1501 |
// UR5e home position - official MuJoCo Menagerie elbow-up pose
|
| 1502 |
const home = [-1.5708, -1.5708, 1.5708, -1.5708, -1.5708, 0.0];
|
| 1503 |
-
for (let i = 0; i < 6; i++) {
|
| 1504 |
-
document.getElementById('joint_' + i).value = home[i];
|
| 1505 |
-
document.getElementById('joint_' + i + '_val').innerText = home[i].toFixed(2);
|
| 1506 |
-
}
|
| 1507 |
send('joint_positions', {positions: home});
|
| 1508 |
}
|
| 1509 |
|
|
|
|
| 170 |
# Check if Nova API is configured via environment variables
|
| 171 |
nova_config = None
|
| 172 |
if os.getenv('NOVA_INSTANCE_URL') and os.getenv('NOVA_ACCESS_TOKEN'):
|
| 173 |
+
# Enable state streaming (digital twin mode) and jogging (bidirectional control)
|
| 174 |
+
# State streaming: simulation shows the real robot's state
|
| 175 |
+
# Jogging: UI can send directional jog commands to control the real robot
|
| 176 |
+
# IK is disabled because real robot is controlled via jogging API
|
| 177 |
+
print("Nova API configuration detected, enabling state streaming and jogging")
|
| 178 |
nova_config = {
|
| 179 |
"use_state_stream": True,
|
| 180 |
+
"use_ik": False, # Disabled: using jogging API instead
|
| 181 |
+
"use_jogging": True # Enable bidirectional robot control
|
| 182 |
}
|
| 183 |
|
| 184 |
if scene_name == "scene_t_push":
|
|
|
|
| 277 |
use_orientation = env.get_use_orientation()
|
| 278 |
|
| 279 |
# Check Nova API status
|
| 280 |
+
nova_client = getattr(env, '_nova_client', None)
|
| 281 |
nova_state_streaming = getattr(env, '_use_nova_state_stream', False)
|
| 282 |
nova_ik = getattr(env, '_use_nova_ik', False)
|
| 283 |
+
# Show connected if client exists (even if first state not received yet)
|
| 284 |
+
nova_connected = nova_client is not None
|
| 285 |
|
| 286 |
state_msg = json.dumps({
|
| 287 |
'type': 'state',
|
|
|
|
| 542 |
if env is not None and current_robot in ("ur5", "ur5_t_push"):
|
| 543 |
env.set_use_orientation(use)
|
| 544 |
|
| 545 |
+
# Nova jogging commands
|
| 546 |
+
elif msg_type == 'start_jog':
|
| 547 |
+
payload = data.get('data', {})
|
| 548 |
+
jog_type = payload.get('jog_type')
|
| 549 |
+
jog_params = payload.get('params', {})
|
| 550 |
+
with mujoco_lock:
|
| 551 |
+
if env is not None and current_robot in ("ur5", "ur5_t_push"):
|
| 552 |
+
success = env.start_jog(jog_type, **jog_params)
|
| 553 |
+
if not success:
|
| 554 |
+
print(f"[Server] Failed to start jog: {jog_type}, {jog_params}")
|
| 555 |
+
|
| 556 |
+
elif msg_type == 'stop_jog':
|
| 557 |
+
with mujoco_lock:
|
| 558 |
+
if env is not None and current_robot in ("ur5", "ur5_t_push"):
|
| 559 |
+
env.stop_jog()
|
| 560 |
+
|
| 561 |
|
| 562 |
def _serialize_space(space):
|
| 563 |
if hasattr(space, "low") and hasattr(space, "high"):
|
|
|
|
| 950 |
.ik-controls.active, .joint-controls.active { display: block; }
|
| 951 |
.joint-sliders .slider-row { margin-bottom: 6px; }
|
| 952 |
.joint-sliders label { width: 40px; display: inline-block; font-size: 0.75em; }
|
| 953 |
+
|
| 954 |
+
/* Jogging controls */
|
| 955 |
+
.jog-controls { margin: 10px 0; }
|
| 956 |
+
.jog-row {
|
| 957 |
+
display: flex;
|
| 958 |
+
align-items: center;
|
| 959 |
+
gap: 8px;
|
| 960 |
+
margin-bottom: 8px;
|
| 961 |
+
}
|
| 962 |
+
.jog-row label {
|
| 963 |
+
width: 30px;
|
| 964 |
+
display: inline-block;
|
| 965 |
+
font-size: 0.85em;
|
| 966 |
+
text-align: left;
|
| 967 |
+
}
|
| 968 |
+
.jog-btn {
|
| 969 |
+
width: 40px;
|
| 970 |
+
height: 40px;
|
| 971 |
+
padding: 0;
|
| 972 |
+
font-size: 1.5em;
|
| 973 |
+
font-weight: bold;
|
| 974 |
+
background: rgba(188, 190, 236, 0.15);
|
| 975 |
+
color: var(--wb-secondary);
|
| 976 |
+
border: 1px solid rgba(188, 190, 236, 0.3);
|
| 977 |
+
border-radius: 6px;
|
| 978 |
+
cursor: pointer;
|
| 979 |
+
transition: all 0.15s;
|
| 980 |
+
user-select: none;
|
| 981 |
+
-webkit-user-select: none;
|
| 982 |
+
flex-shrink: 0;
|
| 983 |
+
}
|
| 984 |
+
.jog-btn:hover {
|
| 985 |
+
background: rgba(139, 127, 239, 0.3);
|
| 986 |
+
border-color: rgba(139, 127, 239, 0.5);
|
| 987 |
+
transform: scale(1.05);
|
| 988 |
+
}
|
| 989 |
+
.jog-btn:active {
|
| 990 |
+
background: rgba(139, 127, 239, 0.5);
|
| 991 |
+
border-color: rgba(139, 127, 239, 0.7);
|
| 992 |
+
transform: scale(0.95);
|
| 993 |
+
}
|
| 994 |
+
.jog-row .val-display {
|
| 995 |
+
flex-grow: 1;
|
| 996 |
+
width: auto;
|
| 997 |
+
text-align: center;
|
| 998 |
+
font-family: monospace;
|
| 999 |
+
font-size: 0.9em;
|
| 1000 |
+
color: #fff;
|
| 1001 |
+
}
|
| 1002 |
</style>
|
| 1003 |
</head>
|
| 1004 |
<body>
|
|
|
|
| 1025 |
Reward: <span id="arm_reward">-</span><br>
|
| 1026 |
Mode: <span id="control_mode_display">IK</span> | Steps: <span id="arm_step_val">0</span><br>
|
| 1027 |
<div style="margin-top: 8px; padding-top: 8px; border-top: 1px solid rgba(188, 190, 236, 0.2);">
|
| 1028 |
+
<div id="nova_connection_badge" style="display: none; margin-bottom: 8px; padding: 6px 10px; background: rgba(76, 175, 80, 0.15); border-radius: 4px; border-left: 3px solid var(--wb-success);">
|
| 1029 |
+
<strong style="font-size: 0.85em; color: var(--wb-success);">🌐 Nova Connected</strong>
|
| 1030 |
+
<div style="font-size: 0.75em; color: rgba(255, 255, 255, 0.7); margin-top: 2px;">
|
| 1031 |
+
<span id="nova_mode_text">Digital Twin Mode</span> - Read Only
|
| 1032 |
+
</div>
|
| 1033 |
+
</div>
|
| 1034 |
<strong style="font-size: 0.9em;">Controllers:</strong><br>
|
| 1035 |
<span style="font-size: 0.85em;">
|
| 1036 |
State: <span id="nova_state_controller" style="color: var(--wb-highlight);">Internal</span><br>
|
|
|
|
| 1110 |
<!-- IK Controls -->
|
| 1111 |
<div class="ik-controls active" id="ik_controls">
|
| 1112 |
<div class="control-group">
|
| 1113 |
+
<label>Translation (XYZ)</label>
|
| 1114 |
+
<div class="jog-controls">
|
| 1115 |
+
<div class="jog-row">
|
| 1116 |
+
<label style="color: #ff6b6b; font-weight: bold;">X</label>
|
| 1117 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_translation', 'x', '-')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_translation', 'x', '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1118 |
+
<span class="val-display" id="pos_x_val">0.00</span>
|
| 1119 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_translation', 'x', '+')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_translation', 'x', '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1120 |
</div>
|
| 1121 |
+
<div class="jog-row">
|
| 1122 |
+
<label style="color: #51cf66; font-weight: bold;">Y</label>
|
| 1123 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_translation', 'y', '-')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_translation', 'y', '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1124 |
+
<span class="val-display" id="pos_y_val">0.00</span>
|
| 1125 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_translation', 'y', '+')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_translation', 'y', '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1126 |
</div>
|
| 1127 |
+
<div class="jog-row">
|
| 1128 |
+
<label style="color: #339af0; font-weight: bold;">Z</label>
|
| 1129 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_translation', 'z', '-')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_translation', 'z', '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1130 |
+
<span class="val-display" id="pos_z_val">0.00</span>
|
| 1131 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_translation', 'z', '+')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_translation', 'z', '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1132 |
</div>
|
| 1133 |
</div>
|
| 1134 |
+
<div style="margin-top: 8px;">
|
| 1135 |
+
<label style="font-size: 0.85em;">Velocity: <span id="trans_vel_val">50</span> mm/s</label>
|
| 1136 |
+
<input type="range" id="trans_velocity" min="10" max="200" step="10" value="50" oninput="updateTransVelocity()" style="width: 100%;">
|
| 1137 |
+
</div>
|
| 1138 |
</div>
|
| 1139 |
<div class="control-group">
|
| 1140 |
+
<label>Rotation (RPY)</label>
|
| 1141 |
+
<div class="jog-controls">
|
| 1142 |
+
<div class="jog-row">
|
| 1143 |
+
<label style="color: #ff6b6b; font-weight: bold;">Rx</label>
|
| 1144 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_rotation', 'x', '-')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_rotation', 'x', '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1145 |
+
<span class="val-display" id="rot_x_val">0.00</span>
|
| 1146 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_rotation', 'x', '+')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_rotation', 'x', '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
|
|
|
|
|
|
|
|
|
| 1147 |
</div>
|
| 1148 |
+
<div class="jog-row">
|
| 1149 |
+
<label style="color: #51cf66; font-weight: bold;">Ry</label>
|
| 1150 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_rotation', 'y', '-')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_rotation', 'y', '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1151 |
+
<span class="val-display" id="rot_y_val">0.00</span>
|
| 1152 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_rotation', 'y', '+')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_rotation', 'y', '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1153 |
</div>
|
| 1154 |
+
<div class="jog-row">
|
| 1155 |
+
<label style="color: #339af0; font-weight: bold;">Rz</label>
|
| 1156 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_rotation', 'z', '-')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_rotation', 'z', '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1157 |
+
<span class="val-display" id="rot_z_val">0.00</span>
|
| 1158 |
+
<button class="jog-btn" onmousedown="startJog('cartesian_rotation', 'z', '+')" onmouseup="stopJog()" ontouchstart="startJog('cartesian_rotation', 'z', '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1159 |
</div>
|
| 1160 |
</div>
|
| 1161 |
+
<div style="margin-top: 8px;">
|
| 1162 |
+
<label style="font-size: 0.85em;">Velocity: <span id="rot_vel_val">0.3</span> rad/s</label>
|
| 1163 |
+
<input type="range" id="rot_velocity" min="0.1" max="1.0" step="0.1" value="0.3" oninput="updateRotVelocity()" style="width: 100%;">
|
| 1164 |
+
</div>
|
| 1165 |
</div>
|
| 1166 |
</div>
|
| 1167 |
|
| 1168 |
<!-- Joint Controls -->
|
| 1169 |
<div class="joint-controls" id="joint_controls">
|
| 1170 |
<div class="control-group">
|
| 1171 |
+
<label>Joint Positions</label>
|
| 1172 |
+
<div class="jog-controls">
|
| 1173 |
+
<div class="jog-row">
|
| 1174 |
<label>J1</label>
|
| 1175 |
+
<button class="jog-btn" onmousedown="startJog('joint', 1, '-')" onmouseup="stopJog()" ontouchstart="startJog('joint', 1, '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1176 |
<span class="val-display" id="joint_0_val">-1.57</span>
|
| 1177 |
+
<button class="jog-btn" onmousedown="startJog('joint', 1, '+')" onmouseup="stopJog()" ontouchstart="startJog('joint', 1, '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1178 |
</div>
|
| 1179 |
+
<div class="jog-row">
|
| 1180 |
<label>J2</label>
|
| 1181 |
+
<button class="jog-btn" onmousedown="startJog('joint', 2, '-')" onmouseup="stopJog()" ontouchstart="startJog('joint', 2, '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1182 |
<span class="val-display" id="joint_1_val">-1.57</span>
|
| 1183 |
+
<button class="jog-btn" onmousedown="startJog('joint', 2, '+')" onmouseup="stopJog()" ontouchstart="startJog('joint', 2, '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1184 |
</div>
|
| 1185 |
+
<div class="jog-row">
|
| 1186 |
<label>J3</label>
|
| 1187 |
+
<button class="jog-btn" onmousedown="startJog('joint', 3, '-')" onmouseup="stopJog()" ontouchstart="startJog('joint', 3, '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1188 |
<span class="val-display" id="joint_2_val">1.57</span>
|
| 1189 |
+
<button class="jog-btn" onmousedown="startJog('joint', 3, '+')" onmouseup="stopJog()" ontouchstart="startJog('joint', 3, '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1190 |
</div>
|
| 1191 |
+
<div class="jog-row">
|
| 1192 |
<label>J4</label>
|
| 1193 |
+
<button class="jog-btn" onmousedown="startJog('joint', 4, '-')" onmouseup="stopJog()" ontouchstart="startJog('joint', 4, '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1194 |
<span class="val-display" id="joint_3_val">-1.57</span>
|
| 1195 |
+
<button class="jog-btn" onmousedown="startJog('joint', 4, '+')" onmouseup="stopJog()" ontouchstart="startJog('joint', 4, '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1196 |
</div>
|
| 1197 |
+
<div class="jog-row">
|
| 1198 |
<label>J5</label>
|
| 1199 |
+
<button class="jog-btn" onmousedown="startJog('joint', 5, '-')" onmouseup="stopJog()" ontouchstart="startJog('joint', 5, '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1200 |
<span class="val-display" id="joint_4_val">-1.57</span>
|
| 1201 |
+
<button class="jog-btn" onmousedown="startJog('joint', 5, '+')" onmouseup="stopJog()" ontouchstart="startJog('joint', 5, '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1202 |
</div>
|
| 1203 |
+
<div class="jog-row">
|
| 1204 |
<label>J6</label>
|
| 1205 |
+
<button class="jog-btn" onmousedown="startJog('joint', 6, '-')" onmouseup="stopJog()" ontouchstart="startJog('joint', 6, '-'); event.preventDefault()" ontouchend="stopJog()">−</button>
|
| 1206 |
<span class="val-display" id="joint_5_val">0.00</span>
|
| 1207 |
+
<button class="jog-btn" onmousedown="startJog('joint', 6, '+')" onmouseup="stopJog()" ontouchstart="startJog('joint', 6, '+'); event.preventDefault()" ontouchend="stopJog()">+</button>
|
| 1208 |
</div>
|
| 1209 |
</div>
|
| 1210 |
+
<div style="margin-top: 8px;">
|
| 1211 |
+
<label style="font-size: 0.85em;">Velocity: <span id="joint_vel_val">0.5</span> rad/s</label>
|
| 1212 |
+
<input type="range" id="joint_velocity" min="0.1" max="2.0" step="0.1" value="0.5" oninput="updateJointVelocity()" style="width: 100%;">
|
| 1213 |
+
</div>
|
| 1214 |
<button style="margin-top: 8px; width: 100%;" onclick="goToHome()">Go to Home Position</button>
|
| 1215 |
</div>
|
| 1216 |
</div>
|
|
|
|
| 1249 |
'g1': '29 DOF humanoid with RL walking policy',
|
| 1250 |
'spot': '12 DOF quadruped with trot gait controller',
|
| 1251 |
'ur5': '6 DOF robot arm with Robotiq gripper',
|
| 1252 |
+
'ur5_t_push': 'UR5e T-push task with stick tool'
|
| 1253 |
};
|
| 1254 |
|
| 1255 |
const robotTitles = {
|
|
|
|
| 1345 |
const jp = data.joint_positions;
|
| 1346 |
document.getElementById('joint_pos_display').innerText =
|
| 1347 |
jp.map(j => j.toFixed(2)).join(', ');
|
|
|
|
| 1348 |
|
| 1349 |
+
// Update jog button displays with actual joint positions
|
|
|
|
|
|
|
| 1350 |
for (let i = 0; i < 6; i++) {
|
| 1351 |
+
document.getElementById('joint_' + i + '_val').innerText = jp[i].toFixed(2);
|
|
|
|
| 1352 |
}
|
| 1353 |
}
|
| 1354 |
|
| 1355 |
+
// Update cartesian position displays with actual EE position
|
| 1356 |
+
if (data.end_effector) {
|
| 1357 |
+
const ee = data.end_effector;
|
| 1358 |
+
document.getElementById('pos_x_val').innerText = ee.x.toFixed(3);
|
| 1359 |
+
document.getElementById('pos_y_val').innerText = ee.y.toFixed(3);
|
| 1360 |
+
document.getElementById('pos_z_val').innerText = ee.z.toFixed(3);
|
|
|
|
|
|
|
|
|
|
| 1361 |
}
|
| 1362 |
|
| 1363 |
+
// Update rotation displays with actual EE orientation
|
| 1364 |
+
if (data.ee_orientation) {
|
| 1365 |
+
const q = data.ee_orientation;
|
| 1366 |
+
const euler = quatToEuler(q.w, q.x, q.y, q.z);
|
| 1367 |
+
document.getElementById('rot_x_val').innerText = euler[0].toFixed(2);
|
| 1368 |
+
document.getElementById('rot_y_val').innerText = euler[1].toFixed(2);
|
| 1369 |
+
document.getElementById('rot_z_val').innerText = euler[2].toFixed(2);
|
|
|
|
|
|
|
| 1370 |
}
|
| 1371 |
|
| 1372 |
// Update control mode display
|
|
|
|
| 1379 |
}
|
| 1380 |
}
|
| 1381 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1382 |
// Update Nova API controller status
|
| 1383 |
if (data.nova_api) {
|
| 1384 |
const stateController = document.getElementById('nova_state_controller');
|
| 1385 |
const ikController = document.getElementById('nova_ik_controller');
|
| 1386 |
+
const badge = document.getElementById('nova_connection_badge');
|
| 1387 |
|
| 1388 |
if (data.nova_api.connected) {
|
| 1389 |
+
// Nova API is connected - show badge
|
| 1390 |
+
badge.style.display = 'block';
|
| 1391 |
+
|
| 1392 |
+
// Update badge mode text
|
| 1393 |
+
const modeText = document.getElementById('nova_mode_text');
|
| 1394 |
+
if (data.nova_api.state_streaming && data.nova_api.ik) {
|
| 1395 |
+
modeText.innerText = 'Hybrid Mode';
|
| 1396 |
+
} else if (data.nova_api.state_streaming) {
|
| 1397 |
+
modeText.innerText = 'Digital Twin Mode';
|
| 1398 |
+
} else if (data.nova_api.ik) {
|
| 1399 |
+
modeText.innerText = 'Nova IK Mode';
|
| 1400 |
+
}
|
| 1401 |
+
|
| 1402 |
if (data.nova_api.state_streaming) {
|
| 1403 |
stateController.innerText = 'Nova API';
|
| 1404 |
stateController.style.color = 'var(--wb-success)';
|
|
|
|
| 1415 |
ikController.style.color = 'var(--wb-highlight)';
|
| 1416 |
}
|
| 1417 |
} else {
|
| 1418 |
+
// Nova API not connected - hide badge
|
| 1419 |
+
badge.style.display = 'none';
|
| 1420 |
stateController.innerText = 'Internal';
|
| 1421 |
stateController.style.color = 'var(--wb-highlight)';
|
| 1422 |
ikController.innerText = 'Internal';
|
|
|
|
| 1555 |
document.getElementById('joint_controls').classList.toggle('active', mode === 'joint');
|
| 1556 |
}
|
| 1557 |
|
| 1558 |
+
// Jogging velocities
|
| 1559 |
+
let transVelocity = 50.0; // mm/s
|
| 1560 |
+
let rotVelocity = 0.3; // rad/s
|
| 1561 |
+
let jointVelocity = 0.5; // rad/s
|
| 1562 |
+
|
| 1563 |
+
function updateTransVelocity() {
|
| 1564 |
+
transVelocity = parseFloat(document.getElementById('trans_velocity').value);
|
| 1565 |
+
document.getElementById('trans_vel_val').innerText = transVelocity.toFixed(0);
|
| 1566 |
}
|
| 1567 |
|
| 1568 |
+
function updateRotVelocity() {
|
| 1569 |
+
rotVelocity = parseFloat(document.getElementById('rot_velocity').value);
|
| 1570 |
+
document.getElementById('rot_vel_val').innerText = rotVelocity.toFixed(1);
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1571 |
}
|
| 1572 |
|
| 1573 |
+
function updateJointVelocity() {
|
| 1574 |
+
jointVelocity = parseFloat(document.getElementById('joint_velocity').value);
|
| 1575 |
+
document.getElementById('joint_vel_val').innerText = jointVelocity.toFixed(1);
|
|
|
|
| 1576 |
}
|
| 1577 |
|
| 1578 |
+
function startJog(jogType, axisOrJoint, direction) {
|
| 1579 |
+
if (jogType === 'cartesian_translation') {
|
| 1580 |
+
send('start_jog', {
|
| 1581 |
+
jog_type: 'cartesian_translation',
|
| 1582 |
+
params: {
|
| 1583 |
+
axis: axisOrJoint,
|
| 1584 |
+
direction: direction,
|
| 1585 |
+
velocity: transVelocity,
|
| 1586 |
+
tcp_id: 'Flange',
|
| 1587 |
+
coord_system_id: 'world'
|
| 1588 |
+
}
|
| 1589 |
+
});
|
| 1590 |
+
} else if (jogType === 'cartesian_rotation') {
|
| 1591 |
+
send('start_jog', {
|
| 1592 |
+
jog_type: 'cartesian_rotation',
|
| 1593 |
+
params: {
|
| 1594 |
+
axis: axisOrJoint,
|
| 1595 |
+
direction: direction,
|
| 1596 |
+
velocity: rotVelocity,
|
| 1597 |
+
tcp_id: 'Flange',
|
| 1598 |
+
coord_system_id: 'world'
|
| 1599 |
+
}
|
| 1600 |
+
});
|
| 1601 |
+
} else if (jogType === 'joint') {
|
| 1602 |
+
// Nova jogger uses 1-based joint indexing
|
| 1603 |
+
send('start_jog', {
|
| 1604 |
+
jog_type: 'joint',
|
| 1605 |
+
params: {
|
| 1606 |
+
joint: axisOrJoint, // 1-6
|
| 1607 |
+
direction: direction,
|
| 1608 |
+
velocity: jointVelocity
|
| 1609 |
+
}
|
| 1610 |
+
});
|
| 1611 |
}
|
| 1612 |
+
}
|
| 1613 |
+
|
| 1614 |
+
function stopJog() {
|
| 1615 |
+
send('stop_jog', {});
|
| 1616 |
}
|
| 1617 |
|
| 1618 |
function goToHome() {
|
| 1619 |
// UR5e home position - official MuJoCo Menagerie elbow-up pose
|
| 1620 |
const home = [-1.5708, -1.5708, 1.5708, -1.5708, -1.5708, 0.0];
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1621 |
send('joint_positions', {positions: home});
|
| 1622 |
}
|
| 1623 |
|
robots/ur5/nova_api.py
CHANGED
|
@@ -109,6 +109,7 @@ class NovaApiClient:
|
|
| 109 |
raise RuntimeError("websockets is required for Nova state streaming")
|
| 110 |
if self._state_thread is not None:
|
| 111 |
return
|
|
|
|
| 112 |
self._state_thread = threading.Thread(target=self._state_stream_loop, daemon=True)
|
| 113 |
self._state_thread.start()
|
| 114 |
|
|
@@ -129,6 +130,10 @@ class NovaApiClient:
|
|
| 129 |
return None
|
| 130 |
return dict(self._latest_state)
|
| 131 |
|
|
|
|
|
|
|
|
|
|
|
|
|
| 132 |
def inverse_kinematics(self, position_m, orientation_quat) -> Optional[list]:
|
| 133 |
model = self._ensure_motion_group_model()
|
| 134 |
if not model:
|
|
@@ -200,11 +205,17 @@ class NovaApiClient:
|
|
| 200 |
f"{self.config.controller_id}/motion-groups/{self.config.motion_group_id}/state-stream"
|
| 201 |
f"?response_rate={int(self.config.response_rate_ms)}"
|
| 202 |
)
|
|
|
|
| 203 |
headers = [("Authorization", f"Bearer {self.config.access_token}")]
|
| 204 |
try:
|
| 205 |
-
|
|
|
|
|
|
|
| 206 |
except TypeError:
|
| 207 |
-
|
|
|
|
|
|
|
|
|
|
| 208 |
|
| 209 |
def _ensure_motion_group_description(self) -> Optional[Dict[str, Any]]:
|
| 210 |
if self._motion_group_description is not None:
|
|
|
|
| 109 |
raise RuntimeError("websockets is required for Nova state streaming")
|
| 110 |
if self._state_thread is not None:
|
| 111 |
return
|
| 112 |
+
print("[Nova] Starting state stream thread...")
|
| 113 |
self._state_thread = threading.Thread(target=self._state_stream_loop, daemon=True)
|
| 114 |
self._state_thread.start()
|
| 115 |
|
|
|
|
| 130 |
return None
|
| 131 |
return dict(self._latest_state)
|
| 132 |
|
| 133 |
+
def is_state_stream_connected(self) -> bool:
|
| 134 |
+
"""Check if state stream is connected and receiving data."""
|
| 135 |
+
return self._state_ws is not None and self._latest_state is not None
|
| 136 |
+
|
| 137 |
def inverse_kinematics(self, position_m, orientation_quat) -> Optional[list]:
|
| 138 |
model = self._ensure_motion_group_model()
|
| 139 |
if not model:
|
|
|
|
| 205 |
f"{self.config.controller_id}/motion-groups/{self.config.motion_group_id}/state-stream"
|
| 206 |
f"?response_rate={int(self.config.response_rate_ms)}"
|
| 207 |
)
|
| 208 |
+
print(f"[Nova] Connecting to state stream: {url}")
|
| 209 |
headers = [("Authorization", f"Bearer {self.config.access_token}")]
|
| 210 |
try:
|
| 211 |
+
ws = connect(url, open_timeout=10, additional_headers=headers)
|
| 212 |
+
print(f"[Nova] State stream connected successfully")
|
| 213 |
+
return ws
|
| 214 |
except TypeError:
|
| 215 |
+
print(f"[Nova] Retrying connection with extra_headers parameter...")
|
| 216 |
+
ws = connect(url, open_timeout=10, extra_headers=headers)
|
| 217 |
+
print(f"[Nova] State stream connected successfully")
|
| 218 |
+
return ws
|
| 219 |
|
| 220 |
def _ensure_motion_group_description(self) -> Optional[Dict[str, Any]]:
|
| 221 |
if self._motion_group_description is not None:
|
robots/ur5/nova_jogger.py
ADDED
|
@@ -0,0 +1,291 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
"""
|
| 2 |
+
Nova Jogger Client
|
| 3 |
+
Handles bidirectional jogging control for Nova API motion groups.
|
| 4 |
+
"""
|
| 5 |
+
|
| 6 |
+
import json
|
| 7 |
+
import threading
|
| 8 |
+
import time
|
| 9 |
+
import urllib.error
|
| 10 |
+
import urllib.request
|
| 11 |
+
from typing import Optional, Literal, Dict, Any
|
| 12 |
+
|
| 13 |
+
try:
|
| 14 |
+
from websockets.sync.client import connect
|
| 15 |
+
except Exception as e:
|
| 16 |
+
print(f"[Nova Jogger] WARNING: Failed to import websockets: {type(e).__name__}: {e}")
|
| 17 |
+
connect = None
|
| 18 |
+
|
| 19 |
+
|
| 20 |
+
JoggingMode = Literal["joint", "cartesian"]
|
| 21 |
+
JogDirection = Literal["positive", "negative", "+", "-"] # Accept both formats, normalize to positive/negative
|
| 22 |
+
CartesianAxis = Literal["x", "y", "z"]
|
| 23 |
+
|
| 24 |
+
|
| 25 |
+
def _normalize_direction(direction: JogDirection) -> str:
|
| 26 |
+
"""Normalize direction to 'positive' or 'negative' format."""
|
| 27 |
+
if direction == "+":
|
| 28 |
+
return "positive"
|
| 29 |
+
elif direction == "-":
|
| 30 |
+
return "negative"
|
| 31 |
+
return direction # Already positive/negative
|
| 32 |
+
|
| 33 |
+
|
| 34 |
+
class NovaJogger:
|
| 35 |
+
"""Manages jogging operations for a Nova motion group."""
|
| 36 |
+
|
| 37 |
+
def __init__(self, instance_url: str, access_token: str, cell_id: str,
|
| 38 |
+
controller_id: str, motion_group_id: str):
|
| 39 |
+
self.instance_url = instance_url
|
| 40 |
+
self.access_token = access_token
|
| 41 |
+
self.cell_id = cell_id
|
| 42 |
+
self.controller_id = controller_id
|
| 43 |
+
self.motion_group_id = motion_group_id
|
| 44 |
+
|
| 45 |
+
self._jogger_ws = None
|
| 46 |
+
self._current_mode: Optional[JoggingMode] = None
|
| 47 |
+
self._lock = threading.Lock()
|
| 48 |
+
self._connected = False
|
| 49 |
+
self._receive_thread = None
|
| 50 |
+
self._stop_thread = False
|
| 51 |
+
|
| 52 |
+
def _receive_loop(self):
|
| 53 |
+
"""Background thread to receive WebSocket messages."""
|
| 54 |
+
while not self._stop_thread and self._jogger_ws is not None:
|
| 55 |
+
try:
|
| 56 |
+
# Receive messages with timeout to allow checking stop flag
|
| 57 |
+
message = self._jogger_ws.recv(timeout=0.5)
|
| 58 |
+
if message:
|
| 59 |
+
# Parse and handle jogger responses/events if needed
|
| 60 |
+
try:
|
| 61 |
+
data = json.loads(message)
|
| 62 |
+
msg_type = data.get("type")
|
| 63 |
+
# Log any errors or important events
|
| 64 |
+
if msg_type == "error":
|
| 65 |
+
print(f"[Nova Jogger] Error from server: {data.get('message')}")
|
| 66 |
+
except json.JSONDecodeError:
|
| 67 |
+
pass # Ignore non-JSON messages
|
| 68 |
+
except TimeoutError:
|
| 69 |
+
continue # Timeout is expected, just loop again
|
| 70 |
+
except Exception as e:
|
| 71 |
+
if not self._stop_thread:
|
| 72 |
+
print(f"[Nova Jogger] Receive error: {e}")
|
| 73 |
+
break
|
| 74 |
+
|
| 75 |
+
def connect(self) -> bool:
|
| 76 |
+
"""Connect to the jogger WebSocket endpoint."""
|
| 77 |
+
if connect is None:
|
| 78 |
+
raise RuntimeError("websockets package required for jogging")
|
| 79 |
+
|
| 80 |
+
# Note: We'll connect to specific endpoints when mode is set
|
| 81 |
+
# This just marks us as ready to connect
|
| 82 |
+
self._connected = True
|
| 83 |
+
print("[Nova Jogger] Ready to connect (will connect on first jog command)")
|
| 84 |
+
return True
|
| 85 |
+
|
| 86 |
+
def _ensure_websocket_for_mode(self, mode: JoggingMode, tcp_id: str = "Flange",
|
| 87 |
+
coord_system_id: str = "world") -> bool:
|
| 88 |
+
"""Ensure WebSocket is connected for the specified mode."""
|
| 89 |
+
if not self._connected:
|
| 90 |
+
print("[Nova Jogger] Not connected")
|
| 91 |
+
return False
|
| 92 |
+
|
| 93 |
+
# If mode changed, close old websocket
|
| 94 |
+
if self._current_mode != mode and self._jogger_ws is not None:
|
| 95 |
+
try:
|
| 96 |
+
self.stop()
|
| 97 |
+
self._jogger_ws.close()
|
| 98 |
+
except:
|
| 99 |
+
pass
|
| 100 |
+
self._jogger_ws = None
|
| 101 |
+
self._current_mode = None
|
| 102 |
+
|
| 103 |
+
# Connect to appropriate endpoint if needed
|
| 104 |
+
if self._jogger_ws is None:
|
| 105 |
+
try:
|
| 106 |
+
ws_url = self.instance_url.replace("https://", "wss://").replace("http://", "ws://")
|
| 107 |
+
|
| 108 |
+
if mode == "joint":
|
| 109 |
+
url = f"{ws_url}/api/v1/cells/{self.cell_id}/motion-groups/move-joint"
|
| 110 |
+
else: # cartesian
|
| 111 |
+
url = f"{ws_url}/api/v1/cells/{self.cell_id}/motion-groups/move-tcp"
|
| 112 |
+
self._tcp_id = tcp_id
|
| 113 |
+
self._coord_system_id = coord_system_id
|
| 114 |
+
|
| 115 |
+
print(f"[Nova Jogger] Connecting to {mode} endpoint: {url}")
|
| 116 |
+
headers = [("Authorization", f"Bearer {self.access_token}")]
|
| 117 |
+
self._jogger_ws = connect(url, open_timeout=10, additional_headers=headers)
|
| 118 |
+
|
| 119 |
+
# Start receive loop
|
| 120 |
+
self._stop_thread = False
|
| 121 |
+
self._receive_thread = threading.Thread(target=self._receive_loop, daemon=True)
|
| 122 |
+
self._receive_thread.start()
|
| 123 |
+
|
| 124 |
+
self._current_mode = mode
|
| 125 |
+
print(f"[Nova Jogger] Connected to {mode} endpoint")
|
| 126 |
+
return True
|
| 127 |
+
|
| 128 |
+
except Exception as e:
|
| 129 |
+
print(f"[Nova Jogger] Failed to connect to {mode} endpoint: {e}")
|
| 130 |
+
return False
|
| 131 |
+
|
| 132 |
+
return True
|
| 133 |
+
|
| 134 |
+
def set_jogging_mode(self, mode: JoggingMode, tcp_id: str = "Flange",
|
| 135 |
+
coord_system_id: str = "world") -> bool:
|
| 136 |
+
"""Set the jogging mode (joint or cartesian)."""
|
| 137 |
+
return self._ensure_websocket_for_mode(mode, tcp_id, coord_system_id)
|
| 138 |
+
|
| 139 |
+
def start_joint_jog(self, joint: int, direction: JogDirection,
|
| 140 |
+
velocity_rads_per_sec: float = 0.5) -> bool:
|
| 141 |
+
"""Start jogging a specific joint using continuous velocity commands."""
|
| 142 |
+
if not self._ensure_websocket_for_mode("joint"):
|
| 143 |
+
return False
|
| 144 |
+
|
| 145 |
+
try:
|
| 146 |
+
# Create velocity array with all joints (assume 6 joints for UR5)
|
| 147 |
+
joint_velocities = [0.0] * 6
|
| 148 |
+
|
| 149 |
+
# Set velocity for specified joint based on direction
|
| 150 |
+
if direction == "+" or direction == "positive":
|
| 151 |
+
joint_velocities[joint] = velocity_rads_per_sec
|
| 152 |
+
else:
|
| 153 |
+
joint_velocities[joint] = -velocity_rads_per_sec
|
| 154 |
+
|
| 155 |
+
# Send velocity command (matching nova-js format)
|
| 156 |
+
command = {
|
| 157 |
+
"motion_group": self.motion_group_id,
|
| 158 |
+
"joint_velocities": joint_velocities
|
| 159 |
+
}
|
| 160 |
+
self._jogger_ws.send(json.dumps(command))
|
| 161 |
+
print(f"[Nova Jogger] Joint {joint} jogging at {joint_velocities[joint]:.2f} rad/s")
|
| 162 |
+
return True
|
| 163 |
+
|
| 164 |
+
except Exception as e:
|
| 165 |
+
print(f"[Nova Jogger] Failed to start joint jog: {e}")
|
| 166 |
+
return False
|
| 167 |
+
|
| 168 |
+
def start_cartesian_translation(self, axis: CartesianAxis, direction: JogDirection,
|
| 169 |
+
velocity_mm_per_sec: float = 50.0,
|
| 170 |
+
tcp_id: str = "Flange",
|
| 171 |
+
coord_system_id: str = "world") -> bool:
|
| 172 |
+
"""Start jogging in cartesian translation using continuous velocity commands."""
|
| 173 |
+
if not self._ensure_websocket_for_mode("cartesian", tcp_id, coord_system_id):
|
| 174 |
+
return False
|
| 175 |
+
|
| 176 |
+
try:
|
| 177 |
+
# Create direction vector
|
| 178 |
+
position_direction = {"x": 0, "y": 0, "z": 0}
|
| 179 |
+
if direction == "+" or direction == "positive":
|
| 180 |
+
position_direction[axis] = 1
|
| 181 |
+
else:
|
| 182 |
+
position_direction[axis] = -1
|
| 183 |
+
|
| 184 |
+
# Send velocity command (matching nova-js format)
|
| 185 |
+
command = {
|
| 186 |
+
"motion_group": self.motion_group_id,
|
| 187 |
+
"position_direction": position_direction,
|
| 188 |
+
"rotation_direction": {"x": 0, "y": 0, "z": 0},
|
| 189 |
+
"position_velocity": velocity_mm_per_sec,
|
| 190 |
+
"rotation_velocity": 0,
|
| 191 |
+
"tcp": tcp_id,
|
| 192 |
+
"coordinate_system": coord_system_id
|
| 193 |
+
}
|
| 194 |
+
self._jogger_ws.send(json.dumps(command))
|
| 195 |
+
print(f"[Nova Jogger] Cartesian {axis.upper()} translation at {velocity_mm_per_sec} mm/s (dir: {position_direction[axis]})")
|
| 196 |
+
return True
|
| 197 |
+
|
| 198 |
+
except Exception as e:
|
| 199 |
+
print(f"[Nova Jogger] Failed to start cartesian translation: {e}")
|
| 200 |
+
return False
|
| 201 |
+
|
| 202 |
+
def start_cartesian_rotation(self, axis: CartesianAxis, direction: JogDirection,
|
| 203 |
+
velocity_rads_per_sec: float = 0.3,
|
| 204 |
+
tcp_id: str = "Flange",
|
| 205 |
+
coord_system_id: str = "world") -> bool:
|
| 206 |
+
"""Start jogging in cartesian rotation using continuous velocity commands."""
|
| 207 |
+
if not self._ensure_websocket_for_mode("cartesian", tcp_id, coord_system_id):
|
| 208 |
+
return False
|
| 209 |
+
|
| 210 |
+
try:
|
| 211 |
+
# Create direction vector
|
| 212 |
+
rotation_direction = {"x": 0, "y": 0, "z": 0}
|
| 213 |
+
if direction == "+" or direction == "positive":
|
| 214 |
+
rotation_direction[axis] = 1
|
| 215 |
+
else:
|
| 216 |
+
rotation_direction[axis] = -1
|
| 217 |
+
|
| 218 |
+
# Send velocity command (matching nova-js format)
|
| 219 |
+
command = {
|
| 220 |
+
"motion_group": self.motion_group_id,
|
| 221 |
+
"position_direction": {"x": 0, "y": 0, "z": 0},
|
| 222 |
+
"rotation_direction": rotation_direction,
|
| 223 |
+
"position_velocity": 0,
|
| 224 |
+
"rotation_velocity": velocity_rads_per_sec,
|
| 225 |
+
"tcp": tcp_id,
|
| 226 |
+
"coordinate_system": coord_system_id
|
| 227 |
+
}
|
| 228 |
+
self._jogger_ws.send(json.dumps(command))
|
| 229 |
+
print(f"[Nova Jogger] Cartesian {axis.upper()} rotation at {velocity_rads_per_sec} rad/s (dir: {rotation_direction[axis]})")
|
| 230 |
+
return True
|
| 231 |
+
|
| 232 |
+
except Exception as e:
|
| 233 |
+
print(f"[Nova Jogger] Failed to start cartesian rotation: {e}")
|
| 234 |
+
return False
|
| 235 |
+
|
| 236 |
+
def stop(self) -> bool:
|
| 237 |
+
"""Stop any active jogging movement by sending zero velocities."""
|
| 238 |
+
if not self._connected or self._jogger_ws is None:
|
| 239 |
+
return False
|
| 240 |
+
|
| 241 |
+
try:
|
| 242 |
+
if self._current_mode == "joint":
|
| 243 |
+
# Send zero velocities for all joints
|
| 244 |
+
command = {
|
| 245 |
+
"motion_group": self.motion_group_id,
|
| 246 |
+
"joint_velocities": [0.0] * 6
|
| 247 |
+
}
|
| 248 |
+
elif self._current_mode == "cartesian":
|
| 249 |
+
# Send zero velocities for cartesian
|
| 250 |
+
command = {
|
| 251 |
+
"motion_group": self.motion_group_id,
|
| 252 |
+
"position_direction": {"x": 0, "y": 0, "z": 0},
|
| 253 |
+
"rotation_direction": {"x": 0, "y": 0, "z": 0},
|
| 254 |
+
"position_velocity": 0,
|
| 255 |
+
"rotation_velocity": 0,
|
| 256 |
+
"tcp": getattr(self, '_tcp_id', 'Flange'),
|
| 257 |
+
"coordinate_system": getattr(self, '_coord_system_id', 'world')
|
| 258 |
+
}
|
| 259 |
+
else:
|
| 260 |
+
return False
|
| 261 |
+
|
| 262 |
+
self._jogger_ws.send(json.dumps(command))
|
| 263 |
+
print("[Nova Jogger] Stopped (zero velocities sent)")
|
| 264 |
+
return True
|
| 265 |
+
|
| 266 |
+
except Exception as e:
|
| 267 |
+
print(f"[Nova Jogger] Failed to stop: {e}")
|
| 268 |
+
return False
|
| 269 |
+
|
| 270 |
+
def disconnect(self):
|
| 271 |
+
"""Disconnect from the jogger."""
|
| 272 |
+
# Stop the receive thread first
|
| 273 |
+
self._stop_thread = True
|
| 274 |
+
if self._receive_thread is not None:
|
| 275 |
+
self._receive_thread.join(timeout=2.0)
|
| 276 |
+
self._receive_thread = None
|
| 277 |
+
|
| 278 |
+
if self._jogger_ws:
|
| 279 |
+
try:
|
| 280 |
+
self.stop()
|
| 281 |
+
self._jogger_ws.close()
|
| 282 |
+
except Exception as e:
|
| 283 |
+
print(f"[Nova Jogger] Error during disconnect: {e}")
|
| 284 |
+
finally:
|
| 285 |
+
self._jogger_ws = None
|
| 286 |
+
self._connected = False
|
| 287 |
+
self._current_mode = None
|
| 288 |
+
|
| 289 |
+
def is_connected(self) -> bool:
|
| 290 |
+
"""Check if jogger is connected."""
|
| 291 |
+
return self._connected and self._jogger_ws is not None
|
robots/ur5/ur5_env.py
CHANGED
|
@@ -18,8 +18,10 @@ IKController = _ik_module.IKController
|
|
| 18 |
|
| 19 |
try:
|
| 20 |
import nova_api
|
|
|
|
| 21 |
except Exception:
|
| 22 |
nova_api = None
|
|
|
|
| 23 |
|
| 24 |
|
| 25 |
class UR5Env(gym.Env):
|
|
@@ -132,8 +134,10 @@ class UR5Env(gym.Env):
|
|
| 132 |
|
| 133 |
# Initialize Nova API attributes FIRST (before any methods that might call _sync_nova_state)
|
| 134 |
self._nova_client = None
|
|
|
|
| 135 |
self._use_nova_state_stream = False
|
| 136 |
self._use_nova_ik = False
|
|
|
|
| 137 |
self._last_nova_sequence = None
|
| 138 |
|
| 139 |
# IK controller for end-effector control
|
|
@@ -181,10 +185,11 @@ class UR5Env(gym.Env):
|
|
| 181 |
|
| 182 |
use_state = bool(nova_api_config.get("use_state_stream"))
|
| 183 |
use_ik = bool(nova_api_config.get("use_ik"))
|
| 184 |
-
|
|
|
|
| 185 |
|
| 186 |
-
if not (use_state or use_ik):
|
| 187 |
-
print("[Nova] Neither state streaming nor
|
| 188 |
return
|
| 189 |
|
| 190 |
try:
|
|
@@ -217,19 +222,46 @@ class UR5Env(gym.Env):
|
|
| 217 |
self._nova_client = nova_api.NovaApiClient(config)
|
| 218 |
self._use_nova_state_stream = use_state
|
| 219 |
self._use_nova_ik = use_ik
|
| 220 |
-
|
|
|
|
| 221 |
|
| 222 |
if self._use_nova_state_stream:
|
| 223 |
print("[Nova] Starting state stream...")
|
| 224 |
self._nova_client.start_state_stream()
|
| 225 |
print("[Nova] State stream started successfully")
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 226 |
except Exception as exc:
|
| 227 |
print(f"[Nova] ERROR: Failed to initialize Nova API integration: {exc}")
|
| 228 |
import traceback
|
| 229 |
traceback.print_exc()
|
| 230 |
self._nova_client = None
|
|
|
|
| 231 |
self._use_nova_state_stream = False
|
| 232 |
self._use_nova_ik = False
|
|
|
|
| 233 |
|
| 234 |
def _reset_freejoint(self, joint_name: str, pos, quat):
|
| 235 |
"""Reset a freejoint pose by name if it exists."""
|
|
@@ -304,6 +336,61 @@ class UR5Env(gym.Env):
|
|
| 304 |
"""Get current control mode."""
|
| 305 |
return self._control_mode
|
| 306 |
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 307 |
def set_joint_positions(self, positions, update_ik_target=True):
|
| 308 |
"""Set target joint positions directly (bypasses IK).
|
| 309 |
|
|
@@ -473,7 +560,9 @@ class UR5Env(gym.Env):
|
|
| 473 |
|
| 474 |
def step_with_controller(self, dt: float = 0.002):
|
| 475 |
"""Step using controller (IK or direct joint control)."""
|
| 476 |
-
if self._use_nova_state_stream
|
|
|
|
|
|
|
| 477 |
return self._get_obs()
|
| 478 |
|
| 479 |
if self._control_mode == 'ik':
|
|
@@ -504,6 +593,9 @@ class UR5Env(gym.Env):
|
|
| 504 |
return None
|
| 505 |
|
| 506 |
def close(self):
|
|
|
|
|
|
|
|
|
|
| 507 |
if self._nova_client is not None:
|
| 508 |
self._nova_client.stop()
|
| 509 |
self._nova_client = None
|
|
@@ -542,11 +634,14 @@ class UR5Env(gym.Env):
|
|
| 542 |
if not state:
|
| 543 |
return False
|
| 544 |
|
| 545 |
-
|
|
|
|
|
|
|
|
|
|
| 546 |
if sequence is not None and sequence == self._last_nova_sequence:
|
| 547 |
return False
|
| 548 |
|
| 549 |
-
joint_positions =
|
| 550 |
if not joint_positions or len(joint_positions) < 6:
|
| 551 |
return False
|
| 552 |
|
|
|
|
| 18 |
|
| 19 |
try:
|
| 20 |
import nova_api
|
| 21 |
+
import nova_jogger
|
| 22 |
except Exception:
|
| 23 |
nova_api = None
|
| 24 |
+
nova_jogger = None
|
| 25 |
|
| 26 |
|
| 27 |
class UR5Env(gym.Env):
|
|
|
|
| 134 |
|
| 135 |
# Initialize Nova API attributes FIRST (before any methods that might call _sync_nova_state)
|
| 136 |
self._nova_client = None
|
| 137 |
+
self._nova_jogger = None
|
| 138 |
self._use_nova_state_stream = False
|
| 139 |
self._use_nova_ik = False
|
| 140 |
+
self._use_nova_jogging = False
|
| 141 |
self._last_nova_sequence = None
|
| 142 |
|
| 143 |
# IK controller for end-effector control
|
|
|
|
| 185 |
|
| 186 |
use_state = bool(nova_api_config.get("use_state_stream"))
|
| 187 |
use_ik = bool(nova_api_config.get("use_ik"))
|
| 188 |
+
use_jogging = bool(nova_api_config.get("use_jogging"))
|
| 189 |
+
print(f"[Nova] use_state_stream={use_state}, use_ik={use_ik}, use_jogging={use_jogging}")
|
| 190 |
|
| 191 |
+
if not (use_state or use_ik or use_jogging):
|
| 192 |
+
print("[Nova] Neither state streaming, IK, nor jogging requested, skipping configuration")
|
| 193 |
return
|
| 194 |
|
| 195 |
try:
|
|
|
|
| 222 |
self._nova_client = nova_api.NovaApiClient(config)
|
| 223 |
self._use_nova_state_stream = use_state
|
| 224 |
self._use_nova_ik = use_ik
|
| 225 |
+
self._use_nova_jogging = use_jogging
|
| 226 |
+
print(f"[Nova] Client created successfully. State streaming: {use_state}, IK: {use_ik}, Jogging: {use_jogging}")
|
| 227 |
|
| 228 |
if self._use_nova_state_stream:
|
| 229 |
print("[Nova] Starting state stream...")
|
| 230 |
self._nova_client.start_state_stream()
|
| 231 |
print("[Nova] State stream started successfully")
|
| 232 |
+
print("[Nova] WARNING: State streaming enabled - simulation is now a digital twin.")
|
| 233 |
+
print("[Nova] Robot state comes from Nova API, local targets/IK are ignored.")
|
| 234 |
+
|
| 235 |
+
if self._use_nova_jogging:
|
| 236 |
+
if nova_jogger is None:
|
| 237 |
+
print("[Nova] ERROR: Jogging requested but nova_jogger module unavailable")
|
| 238 |
+
self._use_nova_jogging = False
|
| 239 |
+
else:
|
| 240 |
+
print("[Nova] Creating NovaJogger...")
|
| 241 |
+
self._nova_jogger = nova_jogger.NovaJogger(
|
| 242 |
+
instance_url=config.instance_url,
|
| 243 |
+
access_token=config.access_token,
|
| 244 |
+
cell_id=config.cell_id,
|
| 245 |
+
controller_id=config.controller_id,
|
| 246 |
+
motion_group_id=config.motion_group_id
|
| 247 |
+
)
|
| 248 |
+
if self._nova_jogger.connect():
|
| 249 |
+
print("[Nova] Jogger connected successfully")
|
| 250 |
+
print("[Nova] Jogging enabled - UI can send directional jog commands")
|
| 251 |
+
else:
|
| 252 |
+
print("[Nova] ERROR: Failed to connect jogger")
|
| 253 |
+
self._nova_jogger = None
|
| 254 |
+
self._use_nova_jogging = False
|
| 255 |
+
|
| 256 |
except Exception as exc:
|
| 257 |
print(f"[Nova] ERROR: Failed to initialize Nova API integration: {exc}")
|
| 258 |
import traceback
|
| 259 |
traceback.print_exc()
|
| 260 |
self._nova_client = None
|
| 261 |
+
self._nova_jogger = None
|
| 262 |
self._use_nova_state_stream = False
|
| 263 |
self._use_nova_ik = False
|
| 264 |
+
self._use_nova_jogging = False
|
| 265 |
|
| 266 |
def _reset_freejoint(self, joint_name: str, pos, quat):
|
| 267 |
"""Reset a freejoint pose by name if it exists."""
|
|
|
|
| 336 |
"""Get current control mode."""
|
| 337 |
return self._control_mode
|
| 338 |
|
| 339 |
+
def start_jog(self, jog_type: str, **kwargs) -> bool:
|
| 340 |
+
"""Start Nova jogging command.
|
| 341 |
+
|
| 342 |
+
Args:
|
| 343 |
+
jog_type: 'joint', 'cartesian_translation', or 'cartesian_rotation'
|
| 344 |
+
**kwargs: Parameters for the jog command (joint, axis, direction, velocity, etc.)
|
| 345 |
+
|
| 346 |
+
Returns:
|
| 347 |
+
True if command sent successfully
|
| 348 |
+
"""
|
| 349 |
+
if not self._use_nova_jogging or self._nova_jogger is None:
|
| 350 |
+
print("[Nova] Jogging not enabled or jogger not connected")
|
| 351 |
+
return False
|
| 352 |
+
|
| 353 |
+
try:
|
| 354 |
+
if jog_type == 'joint':
|
| 355 |
+
return self._nova_jogger.start_joint_jog(
|
| 356 |
+
joint=kwargs.get('joint', 0),
|
| 357 |
+
direction=kwargs.get('direction', '+'),
|
| 358 |
+
velocity_rads_per_sec=kwargs.get('velocity', 0.5)
|
| 359 |
+
)
|
| 360 |
+
elif jog_type == 'cartesian_translation':
|
| 361 |
+
return self._nova_jogger.start_cartesian_translation(
|
| 362 |
+
axis=kwargs.get('axis', 'x'),
|
| 363 |
+
direction=kwargs.get('direction', '+'),
|
| 364 |
+
velocity_mm_per_sec=kwargs.get('velocity', 50.0),
|
| 365 |
+
tcp_id=kwargs.get('tcp_id', 'Flange'),
|
| 366 |
+
coord_system_id=kwargs.get('coord_system_id', 'world')
|
| 367 |
+
)
|
| 368 |
+
elif jog_type == 'cartesian_rotation':
|
| 369 |
+
return self._nova_jogger.start_cartesian_rotation(
|
| 370 |
+
axis=kwargs.get('axis', 'x'),
|
| 371 |
+
direction=kwargs.get('direction', '+'),
|
| 372 |
+
velocity_rads_per_sec=kwargs.get('velocity', 0.3),
|
| 373 |
+
tcp_id=kwargs.get('tcp_id', 'Flange'),
|
| 374 |
+
coord_system_id=kwargs.get('coord_system_id', 'world')
|
| 375 |
+
)
|
| 376 |
+
else:
|
| 377 |
+
print(f"[Nova] Unknown jog type: {jog_type}")
|
| 378 |
+
return False
|
| 379 |
+
except Exception as e:
|
| 380 |
+
print(f"[Nova] Error starting jog: {e}")
|
| 381 |
+
return False
|
| 382 |
+
|
| 383 |
+
def stop_jog(self) -> bool:
|
| 384 |
+
"""Stop any active Nova jogging movement."""
|
| 385 |
+
if not self._use_nova_jogging or self._nova_jogger is None:
|
| 386 |
+
return False
|
| 387 |
+
|
| 388 |
+
try:
|
| 389 |
+
return self._nova_jogger.stop()
|
| 390 |
+
except Exception as e:
|
| 391 |
+
print(f"[Nova] Error stopping jog: {e}")
|
| 392 |
+
return False
|
| 393 |
+
|
| 394 |
def set_joint_positions(self, positions, update_ik_target=True):
|
| 395 |
"""Set target joint positions directly (bypasses IK).
|
| 396 |
|
|
|
|
| 560 |
|
| 561 |
def step_with_controller(self, dt: float = 0.002):
|
| 562 |
"""Step using controller (IK or direct joint control)."""
|
| 563 |
+
if self._use_nova_state_stream:
|
| 564 |
+
# In digital twin mode, always sync from Nova (don't do local control)
|
| 565 |
+
self._sync_nova_state()
|
| 566 |
return self._get_obs()
|
| 567 |
|
| 568 |
if self._control_mode == 'ik':
|
|
|
|
| 593 |
return None
|
| 594 |
|
| 595 |
def close(self):
|
| 596 |
+
if self._nova_jogger is not None:
|
| 597 |
+
self._nova_jogger.disconnect()
|
| 598 |
+
self._nova_jogger = None
|
| 599 |
if self._nova_client is not None:
|
| 600 |
self._nova_client.stop()
|
| 601 |
self._nova_client = None
|
|
|
|
| 634 |
if not state:
|
| 635 |
return False
|
| 636 |
|
| 637 |
+
# Nova API wraps state in a "result" field
|
| 638 |
+
result = state.get("result", state)
|
| 639 |
+
|
| 640 |
+
sequence = result.get("sequence_number")
|
| 641 |
if sequence is not None and sequence == self._last_nova_sequence:
|
| 642 |
return False
|
| 643 |
|
| 644 |
+
joint_positions = result.get("joint_position")
|
| 645 |
if not joint_positions or len(joint_positions) < 6:
|
| 646 |
return False
|
| 647 |
|
scripts/test_jogger.py
ADDED
|
@@ -0,0 +1,198 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
"""Test Nova Jogger WebSocket connection and commands."""
|
| 3 |
+
|
| 4 |
+
import os
|
| 5 |
+
import sys
|
| 6 |
+
import time
|
| 7 |
+
import json
|
| 8 |
+
from pathlib import Path
|
| 9 |
+
|
| 10 |
+
# Add parent directory to path
|
| 11 |
+
sys.path.insert(0, str(Path(__file__).parent.parent))
|
| 12 |
+
|
| 13 |
+
# Load .env.local
|
| 14 |
+
def load_env_file(filepath):
|
| 15 |
+
"""Simple .env file loader."""
|
| 16 |
+
if not filepath.exists():
|
| 17 |
+
return {}
|
| 18 |
+
env_vars = {}
|
| 19 |
+
with open(filepath, 'r') as f:
|
| 20 |
+
for line in f:
|
| 21 |
+
line = line.strip()
|
| 22 |
+
if line and not line.startswith('#') and '=' in line:
|
| 23 |
+
key, value = line.split('=', 1)
|
| 24 |
+
env_vars[key.strip()] = value.strip()
|
| 25 |
+
os.environ[key.strip()] = value.strip()
|
| 26 |
+
return env_vars
|
| 27 |
+
|
| 28 |
+
|
| 29 |
+
def main():
|
| 30 |
+
# Load .env.local
|
| 31 |
+
env_path = Path(__file__).parent.parent / ".env.local"
|
| 32 |
+
if not env_path.exists():
|
| 33 |
+
print(f"Error: {env_path} not found")
|
| 34 |
+
return 1
|
| 35 |
+
|
| 36 |
+
print(f"Loading environment from {env_path}")
|
| 37 |
+
env_vars = load_env_file(env_path)
|
| 38 |
+
|
| 39 |
+
# Try to import websockets
|
| 40 |
+
try:
|
| 41 |
+
from websockets.sync.client import connect
|
| 42 |
+
print("✓ websockets module imported successfully")
|
| 43 |
+
except ImportError as e:
|
| 44 |
+
print(f"✗ Failed to import websockets: {e}")
|
| 45 |
+
print("Install with: pip install websockets")
|
| 46 |
+
return 1
|
| 47 |
+
|
| 48 |
+
# Get config
|
| 49 |
+
instance_url = os.getenv("NOVA_INSTANCE_URL")
|
| 50 |
+
access_token = os.getenv("NOVA_ACCESS_TOKEN")
|
| 51 |
+
cell_id = os.getenv("NOVA_CELL_ID", "cell")
|
| 52 |
+
motion_group_id = os.getenv("NOVA_MOTION_GROUP_ID")
|
| 53 |
+
|
| 54 |
+
if not all([instance_url, access_token, motion_group_id]):
|
| 55 |
+
print("✗ Missing required environment variables")
|
| 56 |
+
return 1
|
| 57 |
+
|
| 58 |
+
# Convert HTTP to WebSocket URL
|
| 59 |
+
ws_url = instance_url.replace("https://", "wss://").replace("http://", "ws://")
|
| 60 |
+
|
| 61 |
+
# Try nova-js style endpoints (continuous velocity)
|
| 62 |
+
url_joint = f"{ws_url}/api/v1/cells/{cell_id}/motion-groups/move-joint"
|
| 63 |
+
url_tcp = f"{ws_url}/api/v1/cells/{cell_id}/motion-groups/move-tcp"
|
| 64 |
+
|
| 65 |
+
print(f"\nTesting Nova Jogger WebSocket connection (nova-js style)...")
|
| 66 |
+
print(f"Joint endpoint: {url_joint}")
|
| 67 |
+
print(f"TCP endpoint: {url_tcp}")
|
| 68 |
+
print()
|
| 69 |
+
|
| 70 |
+
# Try to connect to joint endpoint
|
| 71 |
+
headers = [("Authorization", f"Bearer {access_token}")]
|
| 72 |
+
ws = None
|
| 73 |
+
url = None
|
| 74 |
+
|
| 75 |
+
try:
|
| 76 |
+
print("Connecting to joint endpoint...")
|
| 77 |
+
ws = connect(url_joint, open_timeout=10, additional_headers=headers)
|
| 78 |
+
url = url_joint
|
| 79 |
+
print("✓ WebSocket connected to joint endpoint successfully!")
|
| 80 |
+
except Exception as e:
|
| 81 |
+
print(f"✗ Joint endpoint failed: {e}")
|
| 82 |
+
print("\nTrying TCP endpoint...")
|
| 83 |
+
try:
|
| 84 |
+
ws = connect(url_tcp, open_timeout=10, additional_headers=headers)
|
| 85 |
+
url = url_tcp
|
| 86 |
+
print("✓ WebSocket connected to TCP endpoint successfully!")
|
| 87 |
+
except Exception as e2:
|
| 88 |
+
print(f"✗ Both endpoints failed. TCP error: {e2}")
|
| 89 |
+
return 1
|
| 90 |
+
|
| 91 |
+
try:
|
| 92 |
+
|
| 93 |
+
# Check if server sends an initial message
|
| 94 |
+
print("\nWaiting for initial server message...")
|
| 95 |
+
try:
|
| 96 |
+
initial_msg = ws.recv(timeout=2.0)
|
| 97 |
+
print(f" Initial message: {initial_msg}")
|
| 98 |
+
except TimeoutError:
|
| 99 |
+
print(" No initial message (timeout)")
|
| 100 |
+
|
| 101 |
+
# Test 1: Start joint jogging (nova-js style)
|
| 102 |
+
if "move-joint" in url:
|
| 103 |
+
print("\n[Test 1] Starting joint jog (J0+)...")
|
| 104 |
+
jog_cmd = {
|
| 105 |
+
"motion_group": motion_group_id,
|
| 106 |
+
"joint_velocities": [0.1, 0.0, 0.0, 0.0, 0.0, 0.0]
|
| 107 |
+
}
|
| 108 |
+
ws.send(json.dumps(jog_cmd))
|
| 109 |
+
print(f" Sent: {json.dumps(jog_cmd)}")
|
| 110 |
+
|
| 111 |
+
# Try to receive response with timeout
|
| 112 |
+
try:
|
| 113 |
+
response = ws.recv(timeout=2.0)
|
| 114 |
+
print(f" Response: {response}")
|
| 115 |
+
except TimeoutError:
|
| 116 |
+
print(" No response received (timeout after 2s)")
|
| 117 |
+
|
| 118 |
+
# Let it jog briefly
|
| 119 |
+
print(" Jogging for 1 second...")
|
| 120 |
+
time.sleep(1.0)
|
| 121 |
+
|
| 122 |
+
# Test 2: Stop jogging (send zero velocities)
|
| 123 |
+
print("\n[Test 2] Stopping jog (zero velocities)...")
|
| 124 |
+
stop_cmd = {
|
| 125 |
+
"motion_group": motion_group_id,
|
| 126 |
+
"joint_velocities": [0.0, 0.0, 0.0, 0.0, 0.0, 0.0]
|
| 127 |
+
}
|
| 128 |
+
ws.send(json.dumps(stop_cmd))
|
| 129 |
+
print(f" Sent: {json.dumps(stop_cmd)}")
|
| 130 |
+
|
| 131 |
+
try:
|
| 132 |
+
response = ws.recv(timeout=2.0)
|
| 133 |
+
print(f" Response: {response}")
|
| 134 |
+
except TimeoutError:
|
| 135 |
+
print(" No response received (timeout after 2s)")
|
| 136 |
+
|
| 137 |
+
else: # TCP endpoint
|
| 138 |
+
print("\n[Test 1] Starting TCP translation (X+)...")
|
| 139 |
+
jog_cmd = {
|
| 140 |
+
"motion_group": motion_group_id,
|
| 141 |
+
"position_direction": {"x": 1, "y": 0, "z": 0},
|
| 142 |
+
"rotation_direction": {"x": 0, "y": 0, "z": 0},
|
| 143 |
+
"position_velocity": 10.0,
|
| 144 |
+
"rotation_velocity": 0.0,
|
| 145 |
+
"tcp": "Flange",
|
| 146 |
+
"coordinate_system": "world"
|
| 147 |
+
}
|
| 148 |
+
ws.send(json.dumps(jog_cmd))
|
| 149 |
+
print(f" Sent: {json.dumps(jog_cmd)}")
|
| 150 |
+
|
| 151 |
+
# Try to receive response
|
| 152 |
+
try:
|
| 153 |
+
response = ws.recv(timeout=2.0)
|
| 154 |
+
print(f" Response: {response}")
|
| 155 |
+
except TimeoutError:
|
| 156 |
+
print(" No response received (timeout after 2s)")
|
| 157 |
+
|
| 158 |
+
# Let it jog briefly
|
| 159 |
+
print(" Jogging for 1 second...")
|
| 160 |
+
time.sleep(1.0)
|
| 161 |
+
|
| 162 |
+
# Test 2: Stop jogging
|
| 163 |
+
print("\n[Test 2] Stopping jog (zero velocities)...")
|
| 164 |
+
stop_cmd = {
|
| 165 |
+
"motion_group": motion_group_id,
|
| 166 |
+
"position_direction": {"x": 0, "y": 0, "z": 0},
|
| 167 |
+
"rotation_direction": {"x": 0, "y": 0, "z": 0},
|
| 168 |
+
"position_velocity": 0,
|
| 169 |
+
"rotation_velocity": 0,
|
| 170 |
+
"tcp": "Flange",
|
| 171 |
+
"coordinate_system": "world"
|
| 172 |
+
}
|
| 173 |
+
ws.send(json.dumps(stop_cmd))
|
| 174 |
+
print(f" Sent: {json.dumps(stop_cmd)}")
|
| 175 |
+
|
| 176 |
+
try:
|
| 177 |
+
response = ws.recv(timeout=2.0)
|
| 178 |
+
print(f" Response: {response}")
|
| 179 |
+
except TimeoutError:
|
| 180 |
+
print(" No response received (timeout after 2s)")
|
| 181 |
+
|
| 182 |
+
# Close connection
|
| 183 |
+
print("\n[Test 3] Closing connection...")
|
| 184 |
+
ws.close()
|
| 185 |
+
print("✓ Connection closed successfully")
|
| 186 |
+
|
| 187 |
+
print("\n✓ All jogger tests completed!")
|
| 188 |
+
return 0
|
| 189 |
+
|
| 190 |
+
except Exception as e:
|
| 191 |
+
print(f"✗ Test failed: {type(e).__name__}: {e}")
|
| 192 |
+
import traceback
|
| 193 |
+
traceback.print_exc()
|
| 194 |
+
return 1
|
| 195 |
+
|
| 196 |
+
|
| 197 |
+
if __name__ == "__main__":
|
| 198 |
+
sys.exit(main())
|
scripts/test_state_stream.py
ADDED
|
@@ -0,0 +1,97 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
"""Test Nova API state stream WebSocket connection."""
|
| 3 |
+
|
| 4 |
+
import os
|
| 5 |
+
import sys
|
| 6 |
+
from pathlib import Path
|
| 7 |
+
|
| 8 |
+
# Add parent directory to path
|
| 9 |
+
sys.path.insert(0, str(Path(__file__).parent.parent))
|
| 10 |
+
|
| 11 |
+
# Simple .env loader
|
| 12 |
+
def load_env_file(filepath):
|
| 13 |
+
"""Simple .env file loader."""
|
| 14 |
+
if not filepath.exists():
|
| 15 |
+
return {}
|
| 16 |
+
env_vars = {}
|
| 17 |
+
with open(filepath, 'r') as f:
|
| 18 |
+
for line in f:
|
| 19 |
+
line = line.strip()
|
| 20 |
+
if line and not line.startswith('#') and '=' in line:
|
| 21 |
+
key, value = line.split('=', 1)
|
| 22 |
+
env_vars[key.strip()] = value.strip()
|
| 23 |
+
os.environ[key.strip()] = value.strip()
|
| 24 |
+
return env_vars
|
| 25 |
+
|
| 26 |
+
|
| 27 |
+
def main():
|
| 28 |
+
# Load .env.local
|
| 29 |
+
env_path = Path(__file__).parent.parent / ".env.local"
|
| 30 |
+
if not env_path.exists():
|
| 31 |
+
print(f"Error: {env_path} not found")
|
| 32 |
+
return 1
|
| 33 |
+
|
| 34 |
+
print(f"Loading environment from {env_path}")
|
| 35 |
+
env_vars = load_env_file(env_path)
|
| 36 |
+
|
| 37 |
+
# Try to import websockets
|
| 38 |
+
try:
|
| 39 |
+
from websockets.sync.client import connect
|
| 40 |
+
print("✓ websockets module imported successfully")
|
| 41 |
+
except ImportError as e:
|
| 42 |
+
print(f"✗ Failed to import websockets: {e}")
|
| 43 |
+
print("Install with: pip install websockets")
|
| 44 |
+
return 1
|
| 45 |
+
|
| 46 |
+
# Get config
|
| 47 |
+
instance_url = os.getenv("NOVA_INSTANCE_URL")
|
| 48 |
+
access_token = os.getenv("NOVA_ACCESS_TOKEN")
|
| 49 |
+
cell_id = os.getenv("NOVA_CELL_ID", "cell")
|
| 50 |
+
controller_id = os.getenv("NOVA_CONTROLLER_ID")
|
| 51 |
+
motion_group_id = os.getenv("NOVA_MOTION_GROUP_ID")
|
| 52 |
+
response_rate = os.getenv("NOVA_RESPONSE_RATE_MS", "200")
|
| 53 |
+
|
| 54 |
+
if not all([instance_url, access_token, controller_id, motion_group_id]):
|
| 55 |
+
print("✗ Missing required environment variables")
|
| 56 |
+
return 1
|
| 57 |
+
|
| 58 |
+
# Convert HTTP to WebSocket URL
|
| 59 |
+
ws_url = instance_url.replace("https://", "wss://").replace("http://", "ws://")
|
| 60 |
+
url = (
|
| 61 |
+
f"{ws_url}/api/v2/cells/{cell_id}/controllers/"
|
| 62 |
+
f"{controller_id}/motion-groups/{motion_group_id}/state-stream"
|
| 63 |
+
f"?response_rate={response_rate}"
|
| 64 |
+
)
|
| 65 |
+
|
| 66 |
+
print(f"\nTesting WebSocket state stream connection...")
|
| 67 |
+
print(f"URL: {url}")
|
| 68 |
+
print()
|
| 69 |
+
|
| 70 |
+
# Try to connect
|
| 71 |
+
headers = [("Authorization", f"Bearer {access_token}")]
|
| 72 |
+
try:
|
| 73 |
+
print("Connecting...")
|
| 74 |
+
ws = connect(url, open_timeout=10, additional_headers=headers)
|
| 75 |
+
print("✓ WebSocket connected successfully!")
|
| 76 |
+
|
| 77 |
+
print("\nReceiving messages (will stop after 5 messages)...")
|
| 78 |
+
count = 0
|
| 79 |
+
for message in ws:
|
| 80 |
+
count += 1
|
| 81 |
+
print(f"Message {count}: {len(message)} bytes")
|
| 82 |
+
if count >= 5:
|
| 83 |
+
break
|
| 84 |
+
|
| 85 |
+
ws.close()
|
| 86 |
+
print("\n✓ State stream test successful!")
|
| 87 |
+
return 0
|
| 88 |
+
|
| 89 |
+
except Exception as e:
|
| 90 |
+
print(f"✗ Connection failed: {type(e).__name__}: {e}")
|
| 91 |
+
import traceback
|
| 92 |
+
traceback.print_exc()
|
| 93 |
+
return 1
|
| 94 |
+
|
| 95 |
+
|
| 96 |
+
if __name__ == "__main__":
|
| 97 |
+
sys.exit(main())
|
tests/__init__.py
ADDED
|
File without changes
|
tests/test_nova_api.py
ADDED
|
@@ -0,0 +1,303 @@
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
|
| 1 |
+
#!/usr/bin/env python3
|
| 2 |
+
"""Unit tests for Nova API client."""
|
| 3 |
+
|
| 4 |
+
import os
|
| 5 |
+
import sys
|
| 6 |
+
import time
|
| 7 |
+
import unittest
|
| 8 |
+
from pathlib import Path
|
| 9 |
+
from unittest.mock import Mock, patch, MagicMock
|
| 10 |
+
|
| 11 |
+
# Add parent directory to path
|
| 12 |
+
sys.path.insert(0, str(Path(__file__).parent.parent))
|
| 13 |
+
|
| 14 |
+
# Load .env.local for tests
|
| 15 |
+
def load_env_file(filepath):
|
| 16 |
+
"""Simple .env file loader."""
|
| 17 |
+
if not filepath.exists():
|
| 18 |
+
return {}
|
| 19 |
+
env_vars = {}
|
| 20 |
+
with open(filepath, 'r') as f:
|
| 21 |
+
for line in f:
|
| 22 |
+
line = line.strip()
|
| 23 |
+
if line and not line.startswith('#') and '=' in line:
|
| 24 |
+
key, value = line.split('=', 1)
|
| 25 |
+
env_vars[key.strip()] = value.strip()
|
| 26 |
+
os.environ[key.strip()] = value.strip()
|
| 27 |
+
return env_vars
|
| 28 |
+
|
| 29 |
+
env_path = Path(__file__).parent.parent / ".env.local"
|
| 30 |
+
if env_path.exists():
|
| 31 |
+
load_env_file(env_path)
|
| 32 |
+
|
| 33 |
+
from robots.ur5 import nova_api
|
| 34 |
+
|
| 35 |
+
|
| 36 |
+
class TestNovaApiConfig(unittest.TestCase):
|
| 37 |
+
"""Test Nova API configuration."""
|
| 38 |
+
|
| 39 |
+
def test_config_from_env(self):
|
| 40 |
+
"""Test creating config from environment variables."""
|
| 41 |
+
# Should succeed if .env.local is properly configured
|
| 42 |
+
try:
|
| 43 |
+
config = nova_api.NovaApiConfig.from_env()
|
| 44 |
+
self.assertIsNotNone(config.instance_url)
|
| 45 |
+
self.assertIsNotNone(config.access_token)
|
| 46 |
+
self.assertIsNotNone(config.controller_id)
|
| 47 |
+
self.assertIsNotNone(config.motion_group_id)
|
| 48 |
+
print(f"✓ Config created: {config.instance_url}")
|
| 49 |
+
except ValueError as e:
|
| 50 |
+
self.skipTest(f"Skipping: {e}")
|
| 51 |
+
|
| 52 |
+
def test_config_validation(self):
|
| 53 |
+
"""Test config validation with missing variables."""
|
| 54 |
+
with patch.dict(os.environ, {}, clear=True):
|
| 55 |
+
with self.assertRaises(ValueError) as ctx:
|
| 56 |
+
nova_api.NovaApiConfig.from_env()
|
| 57 |
+
self.assertIn("Missing required environment variables", str(ctx.exception))
|
| 58 |
+
|
| 59 |
+
|
| 60 |
+
class TestNovaApiClient(unittest.TestCase):
|
| 61 |
+
"""Test Nova API client functionality."""
|
| 62 |
+
|
| 63 |
+
@classmethod
|
| 64 |
+
def setUpClass(cls):
|
| 65 |
+
"""Set up test fixtures."""
|
| 66 |
+
try:
|
| 67 |
+
cls.config = nova_api.NovaApiConfig.from_env()
|
| 68 |
+
cls.skip_integration = False
|
| 69 |
+
except ValueError:
|
| 70 |
+
cls.skip_integration = True
|
| 71 |
+
|
| 72 |
+
def test_client_creation(self):
|
| 73 |
+
"""Test creating Nova API client."""
|
| 74 |
+
if self.skip_integration:
|
| 75 |
+
self.skipTest("No Nova configuration available")
|
| 76 |
+
|
| 77 |
+
client = nova_api.NovaApiClient(self.config)
|
| 78 |
+
self.assertIsNotNone(client)
|
| 79 |
+
self.assertEqual(client.config, self.config)
|
| 80 |
+
print("✓ Client created successfully")
|
| 81 |
+
|
| 82 |
+
def test_motion_group_description(self):
|
| 83 |
+
"""Test fetching motion group description."""
|
| 84 |
+
if self.skip_integration:
|
| 85 |
+
self.skipTest("No Nova configuration available")
|
| 86 |
+
|
| 87 |
+
client = nova_api.NovaApiClient(self.config)
|
| 88 |
+
description = client._ensure_motion_group_description()
|
| 89 |
+
|
| 90 |
+
self.assertIsNotNone(description)
|
| 91 |
+
self.assertIn("tcps", description)
|
| 92 |
+
print(f"✓ Motion group description: {description.get('motion_group_model')}")
|
| 93 |
+
print(f" Available TCPs: {list(description.get('tcps', {}).keys())}")
|
| 94 |
+
|
| 95 |
+
def test_inverse_kinematics(self):
|
| 96 |
+
"""Test inverse kinematics computation."""
|
| 97 |
+
if self.skip_integration:
|
| 98 |
+
self.skipTest("No Nova configuration available")
|
| 99 |
+
|
| 100 |
+
client = nova_api.NovaApiClient(self.config)
|
| 101 |
+
|
| 102 |
+
# Test IK for a reachable position
|
| 103 |
+
position = [0.4, 0.0, 0.4] # meters
|
| 104 |
+
orientation = [1.0, 0.0, 0.0, 0.0] # quaternion (w, x, y, z)
|
| 105 |
+
|
| 106 |
+
start = time.time()
|
| 107 |
+
solution = client.inverse_kinematics(position, orientation)
|
| 108 |
+
duration = time.time() - start
|
| 109 |
+
|
| 110 |
+
self.assertIsNotNone(solution)
|
| 111 |
+
self.assertEqual(len(solution), 6)
|
| 112 |
+
print(f"✓ IK solution computed in {duration*1000:.1f}ms")
|
| 113 |
+
print(f" Joint angles: {[f'{j:.3f}' for j in solution]}")
|
| 114 |
+
|
| 115 |
+
def test_state_stream_connection(self):
|
| 116 |
+
"""Test state stream WebSocket connection."""
|
| 117 |
+
if self.skip_integration:
|
| 118 |
+
self.skipTest("No Nova configuration available")
|
| 119 |
+
|
| 120 |
+
# Check if websockets is available
|
| 121 |
+
try:
|
| 122 |
+
from websockets.sync.client import connect
|
| 123 |
+
except ImportError:
|
| 124 |
+
self.skipTest("websockets package not installed")
|
| 125 |
+
|
| 126 |
+
client = nova_api.NovaApiClient(self.config)
|
| 127 |
+
|
| 128 |
+
# Start state stream
|
| 129 |
+
print(" Starting state stream...")
|
| 130 |
+
start = time.time()
|
| 131 |
+
client.start_state_stream()
|
| 132 |
+
|
| 133 |
+
# Wait for first state (with timeout)
|
| 134 |
+
timeout = 5.0
|
| 135 |
+
while time.time() - start < timeout:
|
| 136 |
+
state = client.get_latest_state()
|
| 137 |
+
if state is not None:
|
| 138 |
+
duration = time.time() - start
|
| 139 |
+
print(f"✓ State stream connected in {duration*1000:.1f}ms")
|
| 140 |
+
print(f" Received state with {len(state)} fields")
|
| 141 |
+
|
| 142 |
+
# Check for expected fields (Nova API wraps in "result")
|
| 143 |
+
result = state.get("result", state)
|
| 144 |
+
self.assertIn("joint_position", result)
|
| 145 |
+
joints = result["joint_position"]
|
| 146 |
+
print(f" Joint positions: {[f'{j:.3f}' for j in joints[:6]]}")
|
| 147 |
+
|
| 148 |
+
client.stop()
|
| 149 |
+
return
|
| 150 |
+
time.sleep(0.1)
|
| 151 |
+
|
| 152 |
+
client.stop()
|
| 153 |
+
self.fail(f"No state received within {timeout}s")
|
| 154 |
+
|
| 155 |
+
def test_state_stream_non_blocking(self):
|
| 156 |
+
"""Test that state stream doesn't block main thread."""
|
| 157 |
+
if self.skip_integration:
|
| 158 |
+
self.skipTest("No Nova configuration available")
|
| 159 |
+
|
| 160 |
+
try:
|
| 161 |
+
from websockets.sync.client import connect
|
| 162 |
+
except ImportError:
|
| 163 |
+
self.skipTest("websockets package not installed")
|
| 164 |
+
|
| 165 |
+
client = nova_api.NovaApiClient(self.config)
|
| 166 |
+
|
| 167 |
+
# Measure time to start stream (should be very fast if non-blocking)
|
| 168 |
+
start = time.time()
|
| 169 |
+
client.start_state_stream()
|
| 170 |
+
duration = time.time() - start
|
| 171 |
+
|
| 172 |
+
# Should complete in under 1 second (0.5s sleep + overhead)
|
| 173 |
+
self.assertLess(duration, 1.0,
|
| 174 |
+
f"State stream start took {duration}s, should be < 1s")
|
| 175 |
+
print(f"✓ State stream started in {duration*1000:.1f}ms (non-blocking)")
|
| 176 |
+
|
| 177 |
+
# Verify we can do other work immediately
|
| 178 |
+
start = time.time()
|
| 179 |
+
for _ in range(10):
|
| 180 |
+
time.sleep(0.01)
|
| 181 |
+
work_duration = time.time() - start
|
| 182 |
+
|
| 183 |
+
self.assertLess(work_duration, 0.2, "Main thread was blocked")
|
| 184 |
+
print(f"✓ Main thread remained responsive ({work_duration*1000:.1f}ms for 10x10ms sleeps)")
|
| 185 |
+
|
| 186 |
+
client.stop()
|
| 187 |
+
|
| 188 |
+
|
| 189 |
+
class TestNovaApiPerformance(unittest.TestCase):
|
| 190 |
+
"""Test performance characteristics."""
|
| 191 |
+
|
| 192 |
+
@classmethod
|
| 193 |
+
def setUpClass(cls):
|
| 194 |
+
"""Set up test fixtures."""
|
| 195 |
+
try:
|
| 196 |
+
cls.config = nova_api.NovaApiConfig.from_env()
|
| 197 |
+
cls.skip_integration = False
|
| 198 |
+
except ValueError:
|
| 199 |
+
cls.skip_integration = True
|
| 200 |
+
|
| 201 |
+
def test_ik_latency(self):
|
| 202 |
+
"""Measure IK computation latency."""
|
| 203 |
+
if self.skip_integration:
|
| 204 |
+
self.skipTest("No Nova configuration available")
|
| 205 |
+
|
| 206 |
+
client = nova_api.NovaApiClient(self.config)
|
| 207 |
+
|
| 208 |
+
# Warm up (first request may be slower)
|
| 209 |
+
client.inverse_kinematics([0.4, 0.0, 0.4], [1.0, 0.0, 0.0, 0.0])
|
| 210 |
+
|
| 211 |
+
# Measure multiple IK calls
|
| 212 |
+
latencies = []
|
| 213 |
+
for i in range(10):
|
| 214 |
+
# Vary the position slightly
|
| 215 |
+
pos = [0.4 + i*0.01, 0.0, 0.4]
|
| 216 |
+
start = time.time()
|
| 217 |
+
solution = client.inverse_kinematics(pos, [1.0, 0.0, 0.0, 0.0])
|
| 218 |
+
latency = time.time() - start
|
| 219 |
+
latencies.append(latency)
|
| 220 |
+
self.assertIsNotNone(solution)
|
| 221 |
+
|
| 222 |
+
avg_latency = sum(latencies) / len(latencies)
|
| 223 |
+
max_latency = max(latencies)
|
| 224 |
+
|
| 225 |
+
print(f"✓ IK latency: avg={avg_latency*1000:.1f}ms, max={max_latency*1000:.1f}ms")
|
| 226 |
+
|
| 227 |
+
# Warn if latency is high
|
| 228 |
+
if avg_latency > 0.5:
|
| 229 |
+
print(f" WARNING: High IK latency may affect real-time performance")
|
| 230 |
+
|
| 231 |
+
def test_state_stream_rate(self):
|
| 232 |
+
"""Measure state stream update rate."""
|
| 233 |
+
if self.skip_integration:
|
| 234 |
+
self.skipTest("No Nova configuration available")
|
| 235 |
+
|
| 236 |
+
try:
|
| 237 |
+
from websockets.sync.client import connect
|
| 238 |
+
except ImportError:
|
| 239 |
+
self.skipTest("websockets package not installed")
|
| 240 |
+
|
| 241 |
+
client = nova_api.NovaApiClient(self.config)
|
| 242 |
+
client.start_state_stream()
|
| 243 |
+
|
| 244 |
+
# Wait for stream to stabilize
|
| 245 |
+
time.sleep(1.0)
|
| 246 |
+
|
| 247 |
+
# Collect timestamps of state updates
|
| 248 |
+
timestamps = []
|
| 249 |
+
prev_state = None
|
| 250 |
+
|
| 251 |
+
for _ in range(20): # Collect 20 updates
|
| 252 |
+
state = client.get_latest_state()
|
| 253 |
+
if state is not None and state != prev_state:
|
| 254 |
+
timestamps.append(time.time())
|
| 255 |
+
prev_state = dict(state) # Make a copy
|
| 256 |
+
time.sleep(0.05) # Check every 50ms
|
| 257 |
+
|
| 258 |
+
client.stop()
|
| 259 |
+
|
| 260 |
+
# Calculate update intervals
|
| 261 |
+
if len(timestamps) >= 2:
|
| 262 |
+
intervals = [timestamps[i+1] - timestamps[i]
|
| 263 |
+
for i in range(len(timestamps)-1)]
|
| 264 |
+
avg_interval = sum(intervals) / len(intervals)
|
| 265 |
+
rate = 1.0 / avg_interval if avg_interval > 0 else 0
|
| 266 |
+
|
| 267 |
+
print(f"✓ State stream rate: {rate:.1f} Hz (interval={avg_interval*1000:.1f}ms)")
|
| 268 |
+
print(f" Expected: ~{1000/self.config.response_rate_ms:.1f} Hz")
|
| 269 |
+
else:
|
| 270 |
+
self.fail(f"Only received {len(timestamps)} state updates")
|
| 271 |
+
|
| 272 |
+
|
| 273 |
+
def run_tests():
|
| 274 |
+
"""Run all tests and print summary."""
|
| 275 |
+
# Create test suite
|
| 276 |
+
loader = unittest.TestLoader()
|
| 277 |
+
suite = unittest.TestSuite()
|
| 278 |
+
|
| 279 |
+
suite.addTests(loader.loadTestsFromTestCase(TestNovaApiConfig))
|
| 280 |
+
suite.addTests(loader.loadTestsFromTestCase(TestNovaApiClient))
|
| 281 |
+
suite.addTests(loader.loadTestsFromTestCase(TestNovaApiPerformance))
|
| 282 |
+
|
| 283 |
+
# Run tests with verbose output
|
| 284 |
+
runner = unittest.TextTestRunner(verbosity=2)
|
| 285 |
+
result = runner.run(suite)
|
| 286 |
+
|
| 287 |
+
# Print summary
|
| 288 |
+
print("\n" + "=" * 60)
|
| 289 |
+
if result.wasSuccessful():
|
| 290 |
+
print("✓ ALL TESTS PASSED")
|
| 291 |
+
else:
|
| 292 |
+
print("✗ SOME TESTS FAILED")
|
| 293 |
+
if result.failures:
|
| 294 |
+
print(f" Failures: {len(result.failures)}")
|
| 295 |
+
if result.errors:
|
| 296 |
+
print(f" Errors: {len(result.errors)}")
|
| 297 |
+
print("=" * 60)
|
| 298 |
+
|
| 299 |
+
return 0 if result.wasSuccessful() else 1
|
| 300 |
+
|
| 301 |
+
|
| 302 |
+
if __name__ == "__main__":
|
| 303 |
+
sys.exit(run_tests())
|