No version for distro humble showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro jazzy showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro rolling showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro ardent showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro bouncy showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro crystal showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro eloquent showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro dashing showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro galactic showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro foxy showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro iron showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro lunar showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro jade showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro indigo showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro hydro showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro kinetic showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro melodic showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file

No version for distro noetic showing kilted. Known supported distros are highlighted in the buttons above.

Repository Summary

Checkout URI https://github.com/EasyNavigation/NavMap.git
VCS Type git
VCS Version kilted
Last Updated 2025-10-12
Dev Status DEVELOPED
Released RELEASED
Contributing Help Wanted (-)
Good First Issues (-)
Pull Requests to Review (-)

Packages

README

NavMap

Doxygen Deployment rolling kilted

NavMap SLAM

NavMap is an open-source C++ and ROS 2 library for representing navigable surfaces for mobile robot navigation and localization.
Unlike classic grid-based maps, NavMap stores the environment as triangular meshes (NavCels), enabling efficient queries and multi-surface environments (e.g., multi-floor buildings).


✨ Features

  • Triangular cell mesh representation with adjacency relations.
  • Dynamic runtime layers: per-cell or per-vertex attributes (occupancy, elevation, cost, traversability, etc.).
  • Locate API: find the NavCel under/around a 3D position using BVH acceleration and raycasting.
  • Raytracing: Möller–Trumbore intersection with a simple BVH for efficiency.
  • Multi-surface support: naturally supports multiple disconnected surfaces (e.g., separate floors).

📂 Repository structure

This repository is organized into several ROS 2 packages:

  • navmap_core/
    Core C++ library implementing NavMap. Minimal dependencies (Eigen3).

  • navmap_ros/
    ROS 2 conversions and message definitions:
    • navmap::NavMapnavmap_ros_interfaces::msg::NavMap
    • nav_msgs::msg::OccupancyGridnavmap::NavMap
  • navmap_rviz_plugin/
    RViz2 plugin for visualization of NavMap messages:
    • Displays surfaces and layers.
    • Optional per-cell normal rendering.
    • Layer-based coloring.
  • navmap_tools/
    Tools and utilities for building and testing NavMaps (mesh import/export, conversions, etc.)

  • navmap_examples/
    Practical examples demonstrating the usage of NavMap, both core C++ API and ROS 2 integrations.

⚙️ Build instructions

NavMap can be built as a standalone C++ library or within a ROS 2 workspace.

ROS 2 colcon build

# Clone into your ROS 2 workspace
cd ~/ros2_ws/src
git clone https://github.com/<your-org>/NavMap.git

# Build
cd ~/ros2_ws
colcon build --packages-up-to navmap_core navmap_ros navmap_rviz_plugin navmap_tools navmap_examples

# Source workspace
source install/setup.bash

Dependencies

  • C++23 compiler
  • Eigen3
  • ROS 2 (tested with Humble, Iron, Jazzy)
  • RViz2 (for the visualization plugin)
  • PCL (for mesh construction utilities)

🚀 Usage (C++ API)

C++ API

This section shows small, self-contained snippets that demonstrate how to create a NavMap, add geometry, attach layers, query values, and locate the triangle (NavCel) corresponding to a 3D position.

Note: After modifying geometry (vertices, triangles, or surfaces), always call rebuild_geometry_accels() before performing queries such as locate_navcel() or raycast().


1. Create a minimal NavMap (single square floor with two triangles)

```cpp #include <navmap_core/NavMap.hpp> #include <Eigen/Core>

using navmap::NavMap; using navmap::NavCelId;

NavMap nm;

// Create a surface std::size_t surf_idx = nm.create_surface(“map”);

File truncated at 100 lines see the full file