fix: align calibration convention metadata and remove conversion path
This commit is contained in:
@@ -17,6 +17,7 @@
|
||||
{"id":"py_workspace-ecz","title":"Update visualization conventions docs with alignment details","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-08T07:47:49.633647436Z","created_by":"crosstyan","updated_at":"2026-02-08T07:48:25.728323257Z","closed_at":"2026-02-08T07:48:25.728323257Z","close_reason":"Added alignment methodology section to docs"}
|
||||
{"id":"py_workspace-ee1","title":"Implement depth-mode argument resolution in calibrate_extrinsics.py","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-07T06:31:03.430147225Z","created_by":"crosstyan","updated_at":"2026-02-07T06:33:43.204825053Z","closed_at":"2026-02-07T06:33:43.204825053Z","close_reason":"Implemented depth-mode argument resolution logic and verified with multiple test cases."}
|
||||
{"id":"py_workspace-f23","title":"Add --origin-axes-scale option to visualize_extrinsics.py","status":"closed","priority":2,"issue_type":"feature","owner":"crosstyan@outlook.com","created_at":"2026-02-08T05:37:35.228917793Z","created_by":"crosstyan","updated_at":"2026-02-08T05:38:31.173898101Z","closed_at":"2026-02-08T05:38:31.173898101Z","close_reason":"Implemented --origin-axes-scale option and verified with rendering."}
|
||||
{"id":"py_workspace-gii","title":"Implement Y-down auto-align and add metadata to extrinsics output","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-09T04:10:40.0580733Z","created_by":"crosstyan","updated_at":"2026-02-09T04:11:31.853050842Z","closed_at":"2026-02-09T04:11:31.853050842Z","close_reason":"Implemented Y-down auto-align and added metadata to extrinsics output JSON."}
|
||||
{"id":"py_workspace-gv2","title":"Create apply_calibration_to_fusion_config.py script","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-09T03:20:08.635031083Z","created_by":"crosstyan","updated_at":"2026-02-09T03:21:20.005139771Z","closed_at":"2026-02-09T03:21:20.005139771Z","close_reason":"Script created and verified with smoke test and type checking."}
|
||||
{"id":"py_workspace-j8b","title":"Research scipy.optimize.least_squares robust optimization for depth residuals","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-07T04:54:04.720996955Z","created_by":"crosstyan","updated_at":"2026-02-07T04:55:22.995644Z","closed_at":"2026-02-07T04:55:22.995644Z","close_reason":"Research completed and recommendations provided."}
|
||||
{"id":"py_workspace-kpa","title":"Unit Hardening (P0)","status":"closed","priority":0,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-07T05:01:46.342605011Z","created_by":"crosstyan","updated_at":"2026-02-07T05:01:51.303022101Z","closed_at":"2026-02-07T05:01:51.303022101Z","close_reason":"Implemented unit hardening in SVOReader: set coordinate_units=METER and guarded manual conversion in _retrieve_depth. Added depth sanity logs."}
|
||||
@@ -26,6 +27,7 @@
|
||||
{"id":"py_workspace-lo0","title":"Add --cv-to-opengl option to apply_calibration_to_fusion_config.py","status":"closed","priority":2,"issue_type":"feature","owner":"crosstyan@outlook.com","created_at":"2026-02-09T03:33:40.435844317Z","created_by":"crosstyan","updated_at":"2026-02-09T03:34:37.514923778Z","closed_at":"2026-02-09T03:34:37.514923778Z","close_reason":"Added --cv-to-opengl option with matrix conversion logic and documentation."}
|
||||
{"id":"py_workspace-nlu","title":"Produce A/B visualization comparison for CV world basis","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-08T03:50:56.386223999Z","created_by":"crosstyan","updated_at":"2026-02-08T03:52:41.232154353Z","closed_at":"2026-02-08T03:52:41.232154353Z","close_reason":"Generated A/B comparison images and analyzed visual differences. Source files remain unchanged."}
|
||||
{"id":"py_workspace-nvw","title":"Update documentation for robust depth refinement","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-07T05:41:32.963615133Z","created_by":"crosstyan","updated_at":"2026-02-07T05:43:55.707975317Z","closed_at":"2026-02-07T05:43:55.707975317Z","close_reason":"Documentation updated with robust refinement details"}
|
||||
{"id":"py_workspace-nxy","title":"Remove --cv-to-opengl option from apply_calibration_to_fusion_config.py","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-09T04:01:56.334044487Z","created_by":"crosstyan","updated_at":"2026-02-09T04:02:55.01899015Z","closed_at":"2026-02-09T04:02:55.01899015Z","close_reason":"Removed --cv-to-opengl option and associated logic as requested."}
|
||||
{"id":"py_workspace-q4w","title":"Add type hints and folder-aware --svo input in calibrate_extrinsics.py","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-06T10:01:13.943518267Z","created_by":"crosstyan","updated_at":"2026-02-06T10:03:09.855307397Z","closed_at":"2026-02-06T10:03:09.855307397Z","close_reason":"Implemented type hints and directory expansion for --svo"}
|
||||
{"id":"py_workspace-q8j","title":"Add script to visualize generated camera extrinsics","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-07T08:22:35.151648893Z","created_by":"crosstyan","updated_at":"2026-02-07T08:27:27.034717788Z","closed_at":"2026-02-07T08:27:27.034717788Z","close_reason":"Implemented visualize_extrinsics.py utility script and verified with example data."}
|
||||
{"id":"py_workspace-qf9","title":"Implement RMSE-based fallback for depth pooling","status":"closed","priority":2,"issue_type":"task","owner":"crosstyan@outlook.com","created_at":"2026-02-07T09:03:17.759148159Z","created_by":"crosstyan","updated_at":"2026-02-07T09:06:33.106901615Z","closed_at":"2026-02-07T09:06:33.106901615Z","close_reason":"Implemented RMSE-based fallback and verified with tests"}
|
||||
|
||||
@@ -38,7 +38,6 @@ Usage Example:
|
||||
import json
|
||||
import click
|
||||
import sys
|
||||
import numpy as np
|
||||
|
||||
|
||||
def validate_pose_string(pose_str: str) -> bool:
|
||||
@@ -77,25 +76,14 @@ def validate_pose_string(pose_str: str) -> bool:
|
||||
default=False,
|
||||
help="Fail if a calibration serial is missing in fusion config.",
|
||||
)
|
||||
@click.option(
|
||||
"--cv-to-opengl",
|
||||
is_flag=True,
|
||||
default=False,
|
||||
help="Convert poses from OpenCV convention (Y-down, Z-forward) to OpenGL convention (Y-up, Z-backward).",
|
||||
)
|
||||
def main(
|
||||
calibration_json: str,
|
||||
fusion_config_json: str,
|
||||
output_json: str,
|
||||
strict: bool,
|
||||
cv_to_opengl: bool,
|
||||
) -> None:
|
||||
"""
|
||||
Apply calibration poses to a ZED Fusion configuration file.
|
||||
|
||||
If --cv-to-opengl is set, the T_world_from_cam matrix is converted from
|
||||
OpenCV convention to OpenGL convention using T_gl = S @ T_cv @ S,
|
||||
where S = diag(1, -1, -1, 1).
|
||||
"""
|
||||
with open(calibration_json, "r") as f:
|
||||
calib_data: dict[str, dict[str, str]] = json.load(f)
|
||||
@@ -126,29 +114,6 @@ def main(
|
||||
)
|
||||
sys.exit(1)
|
||||
|
||||
if cv_to_opengl:
|
||||
# Convert OpenCV to OpenGL convention
|
||||
# S = diag(1, -1, -1, 1)
|
||||
# T_gl = S @ T_cv @ S
|
||||
try:
|
||||
vals = [float(p) for p in pose_str.split()]
|
||||
t_cv = np.array(vals).reshape((4, 4))
|
||||
|
||||
# Validate it's a proper transform (roughly)
|
||||
det = np.linalg.det(t_cv[:3, :3])
|
||||
if not np.isclose(abs(det), 1.0, atol=1e-3):
|
||||
click.echo(
|
||||
f"Warning: Pose for {serial} may not be a valid rotation matrix (det={det:.4f})",
|
||||
err=True,
|
||||
)
|
||||
|
||||
s = np.diag([1, -1, -1, 1])
|
||||
t_gl = s @ t_cv @ s
|
||||
pose_str = " ".join(f"{x:.8f}" for x in t_gl.flatten())
|
||||
except Exception as e:
|
||||
click.echo(f"Error converting pose for serial {serial}: {e}", err=True)
|
||||
sys.exit(1)
|
||||
|
||||
if serial in fusion_data:
|
||||
if "FusionConfiguration" in fusion_data[serial]:
|
||||
fusion_data[serial]["FusionConfiguration"]["pose"] = pose_str
|
||||
|
||||
@@ -383,9 +383,9 @@ def apply_depth_verify_refine_postprocess(
|
||||
results[str(serial)]["depth_pool"] = pool_metadata
|
||||
|
||||
improvement = verify_res.rmse - verify_res_post.rmse
|
||||
results[str(serial)]["refine_depth"][
|
||||
"improvement_rmse"
|
||||
] = improvement
|
||||
results[str(serial)]["refine_depth"]["improvement_rmse"] = (
|
||||
improvement
|
||||
)
|
||||
|
||||
click.echo(
|
||||
f"Camera {serial} refined: RMSE={verify_res_post.rmse:.3f}m "
|
||||
@@ -1116,18 +1116,47 @@ def main(
|
||||
)
|
||||
|
||||
if ground_normal is not None:
|
||||
R_align: Mat33 = rotation_align_vectors(ground_normal, np.array([0, 1, 0]))
|
||||
logger.info(f"Computed alignment rotation for face '{target_face}'")
|
||||
target_axis = np.array([0, -1, 0])
|
||||
R_align: Mat33 = rotation_align_vectors(ground_normal, target_axis)
|
||||
logger.info(
|
||||
f"Computed alignment rotation for face '{target_face}' to target {target_axis}"
|
||||
)
|
||||
|
||||
alignment_meta = {
|
||||
"target_face": target_face,
|
||||
"ground_normal_before": ground_normal.tolist(),
|
||||
"target_axis": target_axis.tolist(),
|
||||
"alignment_rotation": R_align.flatten().tolist(),
|
||||
}
|
||||
|
||||
for serial, data in results.items():
|
||||
T_mean: Mat44 = np.fromstring(data["pose"], sep=" ").reshape(4, 4)
|
||||
T_aligned = apply_alignment_to_pose(T_mean, R_align)
|
||||
data["pose"] = " ".join(f"{x:.6f}" for x in T_aligned.flatten())
|
||||
logger.debug(f"Applied alignment to camera {serial}")
|
||||
|
||||
results["_meta"] = {
|
||||
"pose_convention": "world_from_cam",
|
||||
"frame_convention": "opencv_y_down",
|
||||
"auto_aligned": True,
|
||||
"gravity_direction_world": [0, 1, 0],
|
||||
"alignment": alignment_meta,
|
||||
}
|
||||
else:
|
||||
click.echo(
|
||||
"Warning: Could not determine ground normal. Skipping alignment."
|
||||
)
|
||||
results["_meta"] = {
|
||||
"pose_convention": "world_from_cam",
|
||||
"frame_convention": "opencv_y_down",
|
||||
"auto_aligned": False,
|
||||
}
|
||||
else:
|
||||
results["_meta"] = {
|
||||
"pose_convention": "world_from_cam",
|
||||
"frame_convention": "opencv_y_down",
|
||||
"auto_aligned": False,
|
||||
}
|
||||
|
||||
# 6. Save to JSON
|
||||
with open(output, "w") as f:
|
||||
|
||||
@@ -28,6 +28,18 @@ problem caused by trying to make Plotly (which defaults to Y-up) display OpenCV
|
||||
|
||||
---
|
||||
|
||||
## Current Policy Checklist (2026-02-09)
|
||||
|
||||
For engineers maintaining or using these tools:
|
||||
|
||||
- [x] **`calibrate_extrinsics.py`**: Outputs `T_world_from_cam` (OpenCV). Auto-aligns to **Y-down** (gravity along +Y). Writes `_meta` block.
|
||||
- [x] **`visualize_extrinsics.py`**: Renders raw JSON data. Ignores `_meta`. Sets view camera up to `-Y`.
|
||||
- [x] **`apply_calibration_to_fusion_config.py`**: Direct pose copy only. No `--cv-to-opengl` conversion.
|
||||
- [x] **`compare_pose_sets.py`**: Symmetric inputs (`--pose-a-json`, `--pose-b-json`). Heuristic parsing.
|
||||
- [x] **Conventions**: Always OpenCV frame (+X Right, +Y Down, +Z Forward). Units in meters.
|
||||
|
||||
---
|
||||
|
||||
## Ground Truth Conventions
|
||||
|
||||
### 1. Calibration Output: `world_from_cam`
|
||||
@@ -65,7 +77,40 @@ Every camera's local frame follows the OpenCV pinhole convention:
|
||||
The frustum is drawn along the camera's local +Z axis. The four corners of the
|
||||
frustum's far plane are at `(±w, ±h, frustum_scale)` in camera-local coordinates.
|
||||
|
||||
### 3. Plotly Scene/Camera Interpretation Pitfalls
|
||||
### 3. Metadata & Auto-Alignment (`_meta`)
|
||||
|
||||
`calibrate_extrinsics.py` now writes a `_meta` key to the output JSON. This metadata
|
||||
describes the conventions used but is **optional** for consumers (like the visualizer)
|
||||
which may ignore it.
|
||||
|
||||
```json
|
||||
{
|
||||
"_meta": {
|
||||
"pose_convention": "world_from_cam",
|
||||
"frame_convention": "opencv",
|
||||
"auto_aligned": true,
|
||||
"gravity_direction_world": [0.0, 1.0, 0.0],
|
||||
"alignment": { ... }
|
||||
},
|
||||
"SN123": { ... }
|
||||
}
|
||||
```
|
||||
|
||||
- `pose_convention`: Always `world_from_cam`.
|
||||
- `frame_convention`: Always `opencv` (+X Right, +Y Down, +Z Forward).
|
||||
- `auto_aligned`: `true` if `--auto-align` was used.
|
||||
- `gravity_direction_world`: The vector in world space that points "down" (gravity).
|
||||
- For **Y-down** (current default), this is `[0, 1, 0]`.
|
||||
- For **Y-up** (legacy/Fusion), this would be `[0, -1, 0]`.
|
||||
|
||||
**Auto-Alignment Target**:
|
||||
The `--auto-align` flag now targets a **Y-down** world frame by default (`target_axis=[0, -1, 0]`
|
||||
in internal logic, resulting in gravity pointing +Y).
|
||||
- **Old behavior**: Targeted Y-up (gravity along -Y).
|
||||
- **New behavior**: Targets Y-down (gravity along +Y) to match the OpenCV camera frame convention.
|
||||
- **Result**: The ground plane is still XZ, but "up" is -Y and "down" is +Y.
|
||||
|
||||
### 4. Plotly Scene/Camera Interpretation Pitfalls
|
||||
|
||||
Plotly's 3D scene has its own camera model that controls **how you view** the data:
|
||||
|
||||
@@ -148,6 +193,23 @@ reference. All commits are on `visualize_extrinsics.py`.
|
||||
|
||||
---
|
||||
|
||||
## Known Pitfalls & Common Confusions
|
||||
|
||||
1. **Y-Up vs Y-Down**:
|
||||
- **OpenCV/ArUco**: Y is **Down**. Gravity is `[0, 1, 0]`.
|
||||
- **OpenGL/Fusion**: Y is **Up**. Gravity is `[0, -1, 0]`.
|
||||
- **Pitfall**: Assuming "Y is vertical" is ambiguous. You must know the sign.
|
||||
|
||||
2. **Frame Mismatch vs Origin Mismatch**:
|
||||
- Two pose sets can have the **same convention** (e.g., both Y-down) but different **world origins** (e.g., one at marker, one at camera 1).
|
||||
- **Fix**: Use `compare_pose_sets.py` to align them rigidly before comparing errors.
|
||||
|
||||
3. **Visualizer "Inversion"**:
|
||||
- The visualizer sets `camera.up = {y:-1}`. This makes the scene look "normal" (floor at bottom) even though the data is Y-down.
|
||||
- **Pitfall**: Don't try to "fix" the data to match the view. The view is already compensating for the data.
|
||||
|
||||
---
|
||||
|
||||
## Canonical Rules Going Forward
|
||||
|
||||
1. **Single convention**: All visualization data is in OpenCV frame. No basis switching.
|
||||
|
||||
@@ -17,7 +17,7 @@
|
||||
}
|
||||
},
|
||||
"override_gravity": false,
|
||||
"pose": "-0.920142 -0.007144 -0.391519 2.737071 0.020828 -0.999311 -0.030716 0.998234 -0.391030 -0.036418 0.919657 -4.506511 0.000000 0.000000 0.000000 1.000000",
|
||||
"pose": "0.920142 0.007144 0.391519 -2.737071 -0.020828 0.999311 0.030716 -0.998234 -0.391030 -0.036418 0.919657 -4.506511 0.000000 0.000000 0.000000 1.000000",
|
||||
"serial_number": 41831756
|
||||
}
|
||||
},
|
||||
@@ -39,7 +39,7 @@
|
||||
}
|
||||
},
|
||||
"override_gravity": false,
|
||||
"pose": "-0.605210 -0.049218 -0.794543 4.775046 -0.000054 -0.998084 0.061868 1.091021 -0.796066 0.037486 0.604048 -3.432319 0.000000 0.000000 0.000000 1.000000",
|
||||
"pose": "0.605210 0.049218 0.794543 -4.775046 0.000054 0.998084 -0.061868 -1.091021 -0.796066 0.037486 0.604048 -3.432319 0.000000 0.000000 0.000000 1.000000",
|
||||
"serial_number": 44289123
|
||||
}
|
||||
},
|
||||
@@ -61,7 +61,7 @@
|
||||
}
|
||||
},
|
||||
"override_gravity": false,
|
||||
"pose": "0.644946 -0.017302 0.764033 -1.445382 0.003236 -0.999673 -0.025370 1.093303 0.764222 0.018835 -0.644679 2.324294 0.000000 0.000000 0.000000 1.000000",
|
||||
"pose": "-0.644946 0.017302 -0.764033 1.445382 -0.003236 0.999673 0.025370 -1.093303 0.764222 0.018835 -0.644679 2.324294 0.000000 0.000000 0.000000 1.000000",
|
||||
"serial_number": 44435674
|
||||
}
|
||||
},
|
||||
@@ -83,7 +83,7 @@
|
||||
}
|
||||
},
|
||||
"override_gravity": false,
|
||||
"pose": "0.590968 0.031646 -0.806074 4.336595 0.012877 -0.999473 -0.029798 1.141728 -0.806592 0.007230 -0.591065 2.475000 0.000000 0.000000 0.000000 1.000000",
|
||||
"pose": "-0.590968 -0.031646 0.806074 -4.336595 -0.012877 0.999473 0.029798 -1.141728 -0.806592 0.007230 -0.591065 2.475000 0.000000 0.000000 0.000000 1.000000",
|
||||
"serial_number": 46195029
|
||||
}
|
||||
}
|
||||
|
||||
Reference in New Issue
Block a user