Skip to content

Conversation

@Fredrikhb
Copy link

@Fredrikhb Fredrikhb commented Sep 23, 2025

This is a fix specifically for how cp.roll is being used. (This intentionally excludes my other orientation fix (transpose on publish, polygon x/y., which fixes the rotation of the whole elevation grid.)

Problem: As the robot moves, the entire elevation layer creeps diagonally and stretches features.

Cause: cp.roll(..., axis=(1,2)) expects shifts as [rows(y), cols(x)]. Code used [dx, dy] inside the methods "move" and "move_to".

Fix: Pass [dy, dx] as argument to shift_map_xy instead of [dx, dy].

Evidence: before fix, map shifts diagonally on each update call. Origin of the whole elevation_map_raw becomes gradually shifted and features gets stretched into ridges as a result. After fix, map remains anchored to map frame and features are accurately captured where they are. Origin of elevation_map_raw remains consistent with base_link.

Both pictures are taken at exactly 10.0 seconds of simulation time, without and with fix respectively.

Before:
image

After:
image

gerni17 and others added 30 commits December 8, 2022 13:51
… that contain different fields e.g. rings. Added also configuration for anymal bag and anymal sim
…pping_semantic_cupy into dev/refine_pointcloud
jwag and others added 29 commits February 14, 2025 16:30
fix import of param file
 fixing published map topic namespacing
Got rid of some unused parameters
…make_python.

Currently requires comment in and out parts of package.xml
Idea is that if you don't want the cpp package you could just use the python one without building using cmake
Still debugging issue with ament_python_install_package()
- Fixed CUDA kernels to use proper Row-Major convention (Row=Y, Col=X)
- Updated is_inside() and get_idx() functions in all kernels
- Fixed normal vector calculation (removed swapped components)
- Adjusted data flipping for correct GridMap publishing
- Kept 180-degree rotation in internal representation
- Removed extra flip in elevation_mapping_ros.py

The elevation map now correctly aligns with LiDAR data.
- Reset map_frame to 'map' and base_frame to 'base_link' (standard ROS)
- Reset map_length to 15.0m default
- Reset use_sim_time default to 'false'
- Excavator-specific configs remain in mole_perception_bringup
- Handle both dict and structured array formats from ros2_numpy
- Support Livox MID-360's combined 'xyz' field instead of separate x,y,z
- Add robust error handling for various point cloud structures
- Prevent KeyError when processing Livox lidar data
- Fix 'Layer rgb is not in the map' error spam by adding special handling for RGB layer requests
- Add max_filter plugin from main branch for filling invalid cells with maximum values
- RGB layer now properly retrieves data from semantic layers using color fusion

These changes eliminate the repetitive error messages and add the max_filter functionality that was missing in the ROS2 branch.
- Change executable from 'elevation_mapping_node' to 'elevation_mapping_node.py' in launch files
- Use pure Python implementation instead of C++ wrapper to avoid API mismatches
- Ensures compatibility with latest Python API changes
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment

Labels

None yet

Projects

None yet

Development

Successfully merging this pull request may close these issues.