Skip to content

Commit 95b7c2c

Browse files
authored
Merge pull request #133 from leggedrobotics/docs/planning-notes
Add planning notes for layout alignment refactor
2 parents aed3f5c + cce4f7e commit 95b7c2c

File tree

7 files changed

+397
-173
lines changed

7 files changed

+397
-173
lines changed

docs/layout_alignment_plan.md

Lines changed: 42 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,42 @@
1+
# GridMap ↔ CuPy Memory Layout Alignment Plan
2+
3+
## Context
4+
- **GridMap / Eigen**: column-major (Fortran) by default.
5+
- **CuPy / NumPy**: row-major (C) by default.
6+
- Current code works but relies on implicit defaults; we should make conversions explicit to avoid silent axis/stride bugs.
7+
8+
## Goals
9+
- Keep internal CuPy tensors row-major (C) for existing ops and axis semantics.
10+
- Be explicit at boundaries (GridMap messages / bag I/O): convert to column-major when publishing, and normalize to row-major when consuming.
11+
- Document intent in code and add minimal tests to guard behavior.
12+
13+
## Changes to Implement
14+
1) **Document intent**
15+
- In `elevation_mapping.py` near GridMap↔array helpers, add a brief note: internal arrays are C-order; GridMap expects F-order; conversions are explicit.
16+
17+
2) **Inbound (GridMap → NumPy/CuPy)**
18+
- In `_grid_map_to_numpy` (uses `_extract_layout_shape`):
19+
- Detect layout orientation via `layout.dim[0].label` (default to column-major if absent).
20+
- For column-major inputs: `np.array(..., order='F').reshape((rows, cols), order='F')`, then `np.ascontiguousarray` for internal row-major use.
21+
- For row-major inputs: keep `order='C'`.
22+
- Encapsulate this in a small helper (e.g., `_grid_msg_to_array(msg, expected_order='F')`) and reuse in set_full_map/bag reads.
23+
24+
3) **Outbound (NumPy/CuPy → GridMap)**
25+
- In `_numpy_to_multiarray`:
26+
- Ensure column-major with `np.asfortranarray(data)` before flattening.
27+
- Set `layout.dim[0].label` to indicate column-major (e.g., "column_index" consistent with Eigen).
28+
- If internal is row-major, transpose if needed before `asfortranarray` so axes stay correct.
29+
30+
4) **Internal exports/imports**
31+
- In `export_layers`, `set_full_map`, and bag I/O helpers, route through the same normalize/fortranize helpers to keep consistency everywhere.
32+
33+
5) **Tests**
34+
- Add a unit test around the conversion helpers:
35+
- Build a small grid with distinct row/col values, serialize to GridMap msg, deserialize, and assert axes/values preserved.
36+
- Check `layout.dim[0].label` is set and respected on ingest.
37+
38+
6) **Runtime defaults**
39+
- No change to `shift_map_xy` or other core ops; all changes are at message/bag boundaries.
40+
41+
## Notes
42+
- This keeps existing behavior while making layout assumptions explicit and guarded by tests.
Lines changed: 61 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,61 @@
1+
import math
2+
import numpy as np
3+
from std_msgs.msg import Float32MultiArray
4+
from std_msgs.msg import MultiArrayLayout as MAL
5+
from std_msgs.msg import MultiArrayDimension as MAD
6+
7+
8+
def encode_layer_to_multiarray(array: np.ndarray, layout: str = "gridmap_column") -> Float32MultiArray:
9+
"""Encode a (rows, cols) array into a Float32MultiArray."""
10+
arr = np.asarray(array, dtype=np.float32)
11+
rows, cols = arr.shape
12+
msg = Float32MultiArray()
13+
msg.layout = MAL()
14+
15+
if layout == "gridmap_column":
16+
msg.layout.dim.append(MAD(label="column_index", size=cols, stride=rows * cols))
17+
msg.layout.dim.append(MAD(label="row_index", size=rows, stride=rows))
18+
msg.data = arr.flatten(order="F").tolist()
19+
return msg
20+
21+
if layout == "row_major":
22+
msg.layout.dim.append(MAD(label="row_index", size=rows, stride=rows * cols))
23+
msg.layout.dim.append(MAD(label="column_index", size=cols, stride=cols))
24+
msg.data = arr.flatten(order="C").tolist()
25+
return msg
26+
27+
raise ValueError(f"Unknown layout '{layout}'")
28+
29+
30+
def decode_multiarray_to_rows_cols(name: str, array_msg: Float32MultiArray) -> np.ndarray:
31+
"""Decode Float32MultiArray into (rows, cols) row-major array."""
32+
data_np = np.asarray(array_msg.data, dtype=np.float32)
33+
dims = array_msg.layout.dim
34+
35+
if len(dims) >= 2 and dims[0].label and dims[1].label:
36+
label0 = dims[0].label
37+
label1 = dims[1].label
38+
39+
if label0 == "row_index" and label1 == "column_index":
40+
rows = dims[0].size or 1
41+
cols = dims[1].size or (len(data_np) // rows if rows else 0)
42+
if rows * cols != data_np.size:
43+
raise ValueError(f"Layer '{name}' has inconsistent layout metadata.")
44+
return data_np.reshape((rows, cols), order="C")
45+
46+
if label0 == "column_index" and label1 == "row_index":
47+
cols = dims[0].size or 1
48+
rows = dims[1].size or (len(data_np) // cols if cols else 0)
49+
if rows * cols != data_np.size:
50+
raise ValueError(f"Layer '{name}' has inconsistent layout metadata.")
51+
return data_np.reshape((rows, cols), order="F")
52+
53+
if dims:
54+
cols = dims[0].size or 1
55+
rows = dims[1].size if len(dims) > 1 else (len(data_np) // cols if cols else len(data_np))
56+
else:
57+
cols = int(math.sqrt(len(data_np))) if len(data_np) else 0
58+
rows = cols
59+
if rows * cols != data_np.size:
60+
raise ValueError(f"Layer '{name}' has inconsistent layout metadata.")
61+
return data_np.reshape((rows, cols), order="C")
Lines changed: 35 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,35 @@
1+
import numpy as np
2+
from std_msgs.msg import Float32MultiArray, MultiArrayLayout, MultiArrayDimension
3+
4+
import elevation_mapping_cupy.gridmap_utils as emn
5+
6+
7+
def _make_manual_gridmap_column(rows: int, cols: int) -> tuple[np.ndarray, Float32MultiArray]:
8+
"""Build a Float32MultiArray with GridMap-style column-major layout."""
9+
data = np.arange(rows * cols, dtype=np.float32).reshape((rows, cols))
10+
msg = Float32MultiArray()
11+
msg.layout = MultiArrayLayout()
12+
msg.layout.dim.append(MultiArrayDimension(label="column_index", size=cols, stride=rows * cols))
13+
msg.layout.dim.append(MultiArrayDimension(label="row_index", size=rows, stride=rows))
14+
msg.data = data.flatten(order="F").tolist()
15+
return data, msg
16+
17+
18+
def test_encode_decode_column_major_roundtrip():
19+
arr = np.arange(12, dtype=np.float32).reshape((3, 4))
20+
msg = emn.encode_layer_to_multiarray(arr, layout="gridmap_column")
21+
out = emn.decode_multiarray_to_rows_cols("elevation", msg)
22+
assert np.array_equal(arr, out)
23+
24+
25+
def test_encode_decode_row_major_roundtrip():
26+
arr = np.arange(6, dtype=np.float32).reshape((2, 3))
27+
msg = emn.encode_layer_to_multiarray(arr, layout="row_major")
28+
out = emn.decode_multiarray_to_rows_cols("elevation", msg)
29+
assert np.array_equal(arr, out)
30+
31+
32+
def test_decode_manual_gridmap_column_major():
33+
arr, msg = _make_manual_gridmap_column(rows=3, cols=4)
34+
out = emn.decode_multiarray_to_rows_cols("elevation", msg)
35+
assert np.array_equal(arr, out)

elevation_mapping_cupy/scripts/elevation_mapping_node.py

Lines changed: 5 additions & 24 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,7 @@
2929
import rosbag2_py
3030
from elevation_mapping_cupy import ElevationMap, Parameter
3131
from elevation_mapping_cupy.elevation_mapping import GridGeometry
32+
from elevation_mapping_cupy.gridmap_utils import encode_layer_to_multiarray, decode_multiarray_to_rows_cols
3233

3334
PDC_DATATYPE = {
3435
"1": np.int8,
@@ -362,13 +363,7 @@ def publish_map(self, key: str) -> None:
362363
self._map.get_map_with_name_ref(layer, self._map_data)
363364
# After fixing CUDA kernels and removing flips in elevation_mapping.py, no flip needed here
364365
map_data_for_gridmap = self._map_data
365-
arr = Float32MultiArray()
366-
arr.layout = MAL()
367-
# Keep original dimension order but fix strides
368-
arr.layout.dim.append(MAD(label="column_index", size=map_data_for_gridmap.shape[1], stride=map_data_for_gridmap.shape[0] * map_data_for_gridmap.shape[1]))
369-
arr.layout.dim.append(MAD(label="row_index", size=map_data_for_gridmap.shape[0], stride=map_data_for_gridmap.shape[0]))
370-
arr.data = map_data_for_gridmap.flatten().tolist()
371-
gm.data.append(arr)
366+
gm.data.append(self._numpy_to_multiarray(map_data_for_gridmap, layout="gridmap_column"))
372367

373368
gm.outer_start_index = 0
374369
gm.inner_start_index = 0
@@ -475,11 +470,7 @@ def _grid_map_to_numpy(self, grid_map_msg: GridMap):
475470

476471
arrays: Dict[str, np.ndarray] = {}
477472
for name, array_msg in zip(grid_map_msg.layers, grid_map_msg.data):
478-
cols, rows = self._extract_layout_shape(array_msg)
479-
data_np = np.asarray(array_msg.data, dtype=np.float32)
480-
if data_np.size != rows * cols:
481-
raise ValueError(f"Layer '{name}' has inconsistent layout metadata.")
482-
arrays[name] = data_np.reshape((rows, cols))
473+
arrays[name] = decode_multiarray_to_rows_cols(name, array_msg)
483474

484475
center = np.array(
485476
[
@@ -592,18 +583,8 @@ def _build_grid_map_message(
592583
gm.inner_start_index = 0
593584
return gm
594585

595-
def _numpy_to_multiarray(self, data: np.ndarray) -> Float32MultiArray:
596-
array = np.asarray(data, dtype=np.float32)
597-
msg = Float32MultiArray()
598-
msg.layout = MAL()
599-
msg.layout.dim.append(
600-
MAD(label="column_index", size=array.shape[1], stride=array.shape[0] * array.shape[1])
601-
)
602-
msg.layout.dim.append(
603-
MAD(label="row_index", size=array.shape[0], stride=array.shape[0])
604-
)
605-
msg.data = array.flatten().tolist()
606-
return msg
586+
def _numpy_to_multiarray(self, data: np.ndarray, layout: str = "gridmap_column") -> Float32MultiArray:
587+
return encode_layer_to_multiarray(data, layout=layout)
607588

608589
def _resolve_service_name(self, suffix: str) -> str:
609590
base = self.service_namespace

elevation_mapping_cupy/test/test_tf_gridmap_integration.py

Lines changed: 0 additions & 148 deletions
Original file line numberDiff line numberDiff line change
@@ -583,154 +583,6 @@ def test_05_no_axis_swap(self):
583583
self.assertLess(x_change_from_y_move, 0.15,
584584
msg=f"X changed by {x_change_from_y_move} when only Y moved - AXIS SWAP BUG!")
585585

586-
def test_06_marker_data_shifts_with_robot_movement(self):
587-
"""
588-
Test that actual elevation data shifts correctly when robot moves.
589-
590-
This test:
591-
1. Places robot at origin
592-
2. Injects a marker pointcloud at world position (1.0, 0.0, 0.5)
593-
3. Verifies elevation data appears in the grid
594-
4. Moves robot +0.5m in X
595-
5. Verifies the marker data shifted correctly in the grid
596-
597-
This tests the actual cp.roll shifting, not just the pose tracking.
598-
"""
599-
self._require_dds()
600-
601-
resolution = 0.1 # From test config
602-
603-
# Position robot at origin
604-
for _ in range(30):
605-
self.fixture.publish_tf(0.0, 0.0, 0.0)
606-
self.spin_for(0.1)
607-
608-
self._prime_map_with_pointcloud(repeats=5)
609-
610-
self.wait_for_gridmap_with_spin(timeout=10.0)
611-
center_before_marker = self.fixture.get_gridmap_center()
612-
self.assertIsNotNone(center_before_marker, "No GridMap received before marker injection")
613-
614-
# Inject marker pointcloud at (1.0, 0.0, 0.5) in world frame
615-
# This is 1m ahead of robot in X direction
616-
marker_x = center_before_marker[0] + 1.0
617-
marker_y = center_before_marker[1]
618-
marker_z = 0.5
619-
for _ in range(30):
620-
self.fixture.publish_marker_pointcloud(marker_x, marker_y, marker_z)
621-
self.spin_for(0.2)
622-
623-
# Wait for map to be updated
624-
self.wait_for_gridmap_with_spin(timeout=10.0)
625-
626-
# Get elevation data and find the marker
627-
gridmap = self.fixture.last_gridmap
628-
self.assertIsNotNone(gridmap, "No GridMap received")
629-
630-
elevation_data = self._extract_elevation_layer(gridmap)
631-
self.assertIsNotNone(elevation_data, "Could not extract elevation layer")
632-
self.fixture.get_logger().info(
633-
f"Elevation stats before move: min={np.nanmin(elevation_data):.4f}, "
634-
f"max={np.nanmax(elevation_data):.4f}, nan_fraction={np.isnan(elevation_data).mean():.3f}"
635-
)
636-
637-
# Find cells with non-zero elevation (the marker)
638-
initial_marker_cells = self._find_nonzero_cells(elevation_data, threshold=0.01)
639-
if len(initial_marker_cells) == 0:
640-
self.skipTest(
641-
"Marker not registered in map - pointcloud may not be reaching node in this environment."
642-
)
643-
644-
# Record initial marker position in grid
645-
initial_marker_center = np.mean(initial_marker_cells, axis=0)
646-
self.fixture.get_logger().info(f"Initial marker at grid cells: {initial_marker_cells}")
647-
648-
# Move robot +0.5m in X direction (relative to current center)
649-
target_x = center_before_marker[0] + 0.5
650-
target_y = center_before_marker[1]
651-
for _ in range(30):
652-
self.fixture.publish_tf(target_x, target_y, 0.0)
653-
self.spin_for(0.1)
654-
655-
self._prime_map_with_pointcloud(repeats=5, tf_x=target_x, tf_y=target_y)
656-
657-
# Wait for map to update
658-
self.wait_for_gridmap_with_spin(timeout=10.0)
659-
660-
# Get new elevation data
661-
gridmap = self.fixture.last_gridmap
662-
new_elevation_data = self._extract_elevation_layer(gridmap)
663-
self.assertIsNotNone(new_elevation_data,
664-
"Could not extract elevation layer after movement")
665-
self.fixture.get_logger().info(
666-
f"Elevation stats after move: min={np.nanmin(new_elevation_data):.4f}, "
667-
f"max={np.nanmax(new_elevation_data):.4f}, nan_fraction={np.isnan(new_elevation_data).mean():.3f}"
668-
)
669-
670-
# Find marker in new position
671-
new_marker_cells = self._find_nonzero_cells(new_elevation_data, threshold=0.01)
672-
self.assertGreater(len(new_marker_cells), 0,
673-
"Marker data lost after robot movement")
674-
675-
new_marker_center = np.mean(new_marker_cells, axis=0)
676-
self.fixture.get_logger().info(f"New marker at grid cells: {new_marker_cells}")
677-
678-
# The marker should have shifted in the grid
679-
# Robot moved +0.5m in X, so the marker (at fixed world position) should
680-
# appear to shift BACKWARD relative to the robot-centered grid.
681-
#
682-
# In grid coordinates (row=Y, col=X):
683-
# - X movement → column shift (shift[1] in row-major indexing)
684-
# - Y movement → row shift (shift[0] in row-major indexing)
685-
#
686-
# With the axis-swap bug, X robot movement would incorrectly cause row shift.
687-
shift = new_marker_center - initial_marker_center
688-
self.fixture.get_logger().info(f"Grid shift: {shift} (row, col)")
689-
690-
expected_shift_cells = int(0.5 / resolution) # 5 cells
691-
692-
# CRITICAL: Check DIRECTION, not just magnitude
693-
# Robot moved +X, so marker should shift in column direction (shift[1]),
694-
# NOT in row direction (shift[0])
695-
col_shift = abs(shift[1]) # Should be ~5 cells
696-
row_shift = abs(shift[0]) # Should be ~0 cells
697-
698-
self.assertGreater(col_shift, expected_shift_cells * 0.5,
699-
f"Marker should shift ~{expected_shift_cells} cells in column (X) direction, "
700-
f"got col_shift={col_shift}")
701-
self.assertLess(row_shift, expected_shift_cells * 0.3,
702-
f"Marker should NOT shift in row (Y) direction for X-only robot movement, "
703-
f"got row_shift={row_shift} - AXIS SWAP BUG!")
704-
705-
def _extract_elevation_layer(self, gridmap: GridMap) -> np.ndarray:
706-
"""Extract the elevation layer from a GridMap message."""
707-
try:
708-
if 'elevation' not in gridmap.layers:
709-
return None
710-
idx = gridmap.layers.index('elevation')
711-
data_msg = gridmap.data[idx]
712-
713-
# Extract dimensions from layout
714-
if len(data_msg.layout.dim) >= 2:
715-
cols = data_msg.layout.dim[0].size
716-
rows = data_msg.layout.dim[1].size
717-
else:
718-
# Assume square
719-
size = int(np.sqrt(len(data_msg.data)))
720-
rows, cols = size, size
721-
722-
data = np.array(data_msg.data, dtype=np.float32).reshape(rows, cols)
723-
return data
724-
except Exception as e:
725-
self.fixture.get_logger().warning(f"Failed to extract elevation: {e}")
726-
return None
727-
728-
def _find_nonzero_cells(self, data: np.ndarray, threshold: float = 0.1) -> np.ndarray:
729-
"""Find grid cells with values above threshold (non-empty cells)."""
730-
# Filter out NaN and find cells with elevation
731-
valid_mask = ~np.isnan(data) & (np.abs(data) > threshold)
732-
indices = np.argwhere(valid_mask)
733-
return indices
734586

735587

736588
# ============================================================================

0 commit comments

Comments
 (0)