A collection of custom RViz plugins for visualizing geometry data structures and enhanced point cloud displays. This package provides specialized visualization tools for occupancy trees, enhanced point clouds with normal vectors, and other geometric data.
![]() |
![]() |
![]() |
![]() |
- ROS Support: Compatible with both ROS1 and ROS2
- Enhanced Point Cloud Visualization: Display point clouds with normal vectors and improved performance
- Occupancy Tree Visualization: Visualize quadtrees and octrees as grids or occupancy maps
- Custom Geometry Message Support: Specialized displays for erl_geometry_msgs
Enhanced point cloud visualization with support for displaying normal vectors and improved rendering performance.
Features:
- Display normal vectors from point cloud data
- Configurable normal vector properties (length, width, color, stride)
- Multiple color modes for normals (constant color, rainbow)
- Improved rendering performance over standard PointCloud2 display
Message Type: sensor_msgs/PointCloud2
Visualizes 2D grid maps with support for multiple data types and flexible value encoding.
Features:
- Support for multiple data encodings (INT8, UINT8, INT16, UINT16, INT32, UINT32, FLOAT32, FLOAT64)
- Rich color scheme options (map, costmap, raw, jet, hot, cool, rainbow, spring, summer, autumn, winter, viridis, and reversed variants)
- Binary representation mode with configurable threshold
- Automatic or manual min/max value scaling for color mapping
- Incremental map updates support
- Configurable transparency and rendering order
- Transform timestamp control
Message Type: erl_geometry_msgs/GridMapMsg
Visualizes occupancy quadtrees (2D) or octrees (3D) as individual grid cells.
Features:
- Display occupancy probability as colored grid cells
- Support for both 2D quadtrees and 3D octrees
- Configurable tree depth visualization
- Height filtering for 3D trees
Message Type: erl_geometry_msgs/OccupancyTreeMsg
Converts occupancy trees into standard occupancy grid maps for visualization.
Features:
- Convert quadtree/octree to 2D occupancy grid
- Configurable tree depth and height filtering
- Standard occupancy map visualization
- Compatible with navigation stack displays
Message Type: erl_geometry_msgs/OccupancyTreeMsg
mkdir -p <your_workspace>/src && \
vcs import --input https://raw.githubusercontent.com/ExistentialRobotics/erl_geometry_rviz_plugin/refs/heads/main/erl_geometry_rviz_plugin.repos <your_workspace>/src- ROS1 Noetic or ROS2 Humble
- C++17 compatible compiler
- CMake 3.24 or higher
This package depends on the following ERL packages:
erl_cmake_toolserl_commonerl_covarianceerl_geometry
# Ubuntu 20.04
wget -qO - https://raw.githubusercontent.com/ExistentialRobotics/erl_common/refs/heads/main/scripts/setup_ubuntu_20.04.bash | bash
wget -qO - https://raw.githubusercontent.com/ExistentialRobotics/erl_geometry/refs/heads/main/scripts/setup_ubuntu_20.04.bash | bash
# Ubuntu 22.04, 24.04
wget -qO - https://raw.githubusercontent.com/ExistentialRobotics/erl_common/refs/heads/main/scripts/setup_ubuntu_22.04_24.04.bash | bash
wget -qO - https://raw.githubusercontent.com/ExistentialRobotics/erl_geometry/refs/heads/main/scripts/setup_ubuntu_22.04_24.04.bash | bashROS dependencies:
-
ROS1
# Install ROS1 dependencies sudo apt install ros-noetic-rviz \ ros-noetic-pluginlib \ ros-noetic-std-msgs \ ros-noetic-nav-msgs \ ros-noetic-geometry-msgs \ ros-noetic-sensor-msgs \ ros-noetic-tf2-ros # Install OGRE development libraries sudo apt install libogre-1.9-dev qtbase5-dev
-
ROS2
# Install ROS2 dependencies export ROS_DISTRO=humble # or your desired ROS2 distro sudo apt install ros-$ROS_DISTRO-rviz2 \ ros-$ROS_DISTRO-rviz-common \ ros-$ROS_DISTRO-rviz-rendering \ ros-$ROS_DISTRO-rviz-default-plugins \ ros-$ROS_DISTRO-pluginlib \ ros-$ROS_DISTRO-std-msgs \ ros-$ROS_DISTRO-nav-msgs \ ros-$ROS_DISTRO-geometry-msgs \ ros-$ROS_DISTRO-sensor-msgs \ ros-$ROS_DISTRO-tf2-ros # Install development tools sudo apt install libogre-1.9-dev qtbase5-dev
cd <your_workspace>
# for ROS1
catkin build erl_geometry_ros
source devel/setup.bash
# for ROS2
colcon build --packages-up-to erl_geometry_ros
source install/setup.bashFirst, remember to source your workspace.
ROS1 - Loading Plugins
- Launch RViz:
rosrun rviz rviz - Click "Add" in the Displays panel
- Select "By display type" tab
- Find plugins under:
erl_geometry_rviz_plugin/OccupancyTreeGriderl_geometry_rviz_plugin/OccupancyTreeMaperl_geometry_rviz_plugin/BetterPointCloud2erl_geometry_rviz_plugin/GridMapDisplay
ROS2 - Loading Plugins
- Launch RViz2:
ros2 run rviz2 rviz2 - Click "Add" in the Displays panel
- Select "By display type" tab
- Find plugins under:
erl_geometry_rviz_plugin/OccupancyTreeGriderl_geometry_rviz_plugin/OccupancyTreeMaperl_geometry_rviz_plugin/BetterPointCloud2erl_geometry_rviz_plugin/GridMapDisplay
The package includes test launch files to demonstrate plugin functionality:
ROS1
roslaunch erl_geometry_rviz_plugin test_rviz_plugin_better_point_cloud2_display.launchROS2
ros2 launch erl_geometry_rviz_plugin test_rviz_plugin_better_point_cloud2_display_launch.pyROS1
roslaunch erl_geometry_rviz_plugin test_rviz_plugin_occupancy_tree_display.launchROS2
ros2 launch erl_geometry_rviz_plugin test_rviz_plugin_occupancy_tree_display_launch.pyROS2
ros2 launch erl_geometry_rviz_plugin test_rviz_plugin_grid_map_display_launch.py- Plugins not loaded: Verify workspace is sourced:
source <devel|install>/setup.bash - Large point clouds: Increase normal stride to reduce rendering load
- Deep trees: Limit tree depth visualization to improve performance
- Memory usage: Use float precision instead of double when possible



