NavMap
Loading...
Searching...
No Matches
conversions.hpp File Reference

Conversions between the core NavMap representation and ROS messages. More...

#include <string>
#include <memory>
#include <vector>
#include <Eigen/Core>
#include <pcl/point_cloud.h>
#include <pcl/point_types.h>
#include "sensor_msgs/msg/point_cloud2.hpp"
#include "navmap_ros_interfaces/msg/nav_map.hpp"
#include "navmap_ros_interfaces/msg/nav_map_layer.hpp"
#include "nav_msgs/msg/occupancy_grid.hpp"
#include "navmap_core/NavMap.hpp"
Include dependency graph for conversions.hpp:
This graph shows which files directly or indirectly include this file:

Go to the source code of this file.

Classes

struct  BuildParams
 Parameters controlling NavMap construction from unorganized points. More...
 

Namespaces

namespace  navmap_ros
 Conversions between core NavMap and ROS-level structures.
 

Functions

navmap::NavMap from_msg (const navmap_ros_interfaces::msg::NavMap &msg)
 Reconstruct a core navmap::NavMap from the ROS transport message.
 
void from_msg (const navmap_ros_interfaces::msg::NavMapLayer &msg, navmap::NavMap &nm)
 Import a single NavMapLayer message into a NavMap.
 
navmap::NavMap from_occupancy_grid (const nav_msgs::msg::OccupancyGrid &grid)
 Build a navmap::NavMap from a nav_msgs::msg::OccupancyGrid using a regular triangular surface with shared vertices.
 
navmap::NavMap from_pointcloud2 (const sensor_msgs::msg::PointCloud2 &pc2, navmap_ros_interfaces::msg::NavMap &out_msg, BuildParams params)
 Build a NavMap surface from a ROS sensor_msgs::msg::PointCloud2.
 
navmap::NavMap from_points (const pcl::PointCloud< pcl::PointXYZ > &input_points, navmap_ros_interfaces::msg::NavMap &out_msg, BuildParams params)
 Build a NavMap surface from a PCL point cloud.
 
navmap_ros_interfaces::msg::NavMap to_msg (const navmap::NavMap &nm)
 Convert a core navmap::NavMap into its compact ROS transport message.
 
navmap_ros_interfaces::msg::NavMapLayer to_msg (const navmap::NavMap &nm, const std::string &layer)
 Convert a single layer from a NavMap into a ROS message.
 
nav_msgs::msg::OccupancyGrid to_occupancy_grid (const navmap::NavMap &nm)
 Convert a navmap::NavMap back to nav_msgs::msg::OccupancyGrid.
 

Detailed Description

Conversions between the core NavMap representation and ROS messages.

This header provides:

  • Lossless conversion between the core type navmap::NavMap and the compact transport message navmap_ros_interfaces::msg::NavMap.
  • Bidirectional conversion between nav_msgs::msg::OccupancyGrid and navmap::NavMap using a regular triangular mesh (shared vertices, two triangles per grid cell).

Occupancy mapping

When building a NavMap from an OccupancyGrid, a per-NavCel (triangle) layer named "occupancy" (uint8) is added with the following value mapping:

  • -1 (unknown) → 255
  • 0..100 (percent) → 0..254 (linear scaling)

The reverse conversion reuses that layer when present.