NavMap
Loading...
Searching...
No Matches
navmap_ros Namespace Reference

Conversions between core NavMap and ROS-level structures. More...

Namespaces

namespace  io
 IO helpers to persist NavMap objects to/from disk.
 

Classes

struct  BuildParams
 Parameters controlling NavMap construction from unorganized points. More...
 
struct  EdgeHasher
 
struct  EdgeKey
 
struct  TriHasher
 
struct  TriKey
 
struct  Voxel
 
struct  VoxelAccum
 
struct  VoxelHash
 

Typedefs

using Triangle = Eigen::Vector3i
 

Functions

bool build_navmap_from_mesh (const pcl::PointCloud< pcl::PointXYZ > &cloud, const std::vector< Eigen::Vector3i > &triangles, const std::string &frame_id, navmap_ros_interfaces::msg::NavMap &out_msg, navmap::NavMap *out_core_opt)
 
pcl::PointCloud< pcl::PointXYZ > downsample_voxelize_avgXYZ (const pcl::PointCloud< pcl::PointXYZ > &input_points, float resolution)
 
pcl::PointCloud< pcl::PointXYZ > downsample_voxelize_avgZ (const pcl::PointCloud< pcl::PointXYZ > &input_points, float resolution)
 
navmap::NavMap from_msg (const NavMap &msg)
 
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.
 
std::vector< Trianglegrow_surface_from_seed (const pcl::PointCloud< pcl::PointXYZ > &cloud, int seed_idx, const BuildParams &P)
 
void local_tangent_basis (const std::vector< Eigen::Vector3f > &nbrs, Eigen::Vector3f &t1, Eigen::Vector3f &t2)
 
void sort_neighbors_angular (const Eigen::Vector3f &vpos, const std::vector< std::pair< int, Eigen::Vector3f > > &nbrs, std::vector< int > &out_ordered)
 
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.
 
void triangle_angles_deg (const Eigen::Vector3f &A, const Eigen::Vector3f &B, const Eigen::Vector3f &C, float &angA, float &angB, float &angC)
 
bool try_add_triangle (int i, int j, int k, const pcl::PointCloud< pcl::PointXYZ > &cloud, const BuildParams &P, std::unordered_set< TriKey, TriHasher > &tri_set, std::unordered_set< EdgeKey, EdgeHasher > &edge_set, std::vector< Triangle > &tris)
 

Detailed Description

Conversions between core NavMap and ROS-level structures.

Typedef Documentation

◆ Triangle

using Triangle = Eigen::Vector3i

Function Documentation

◆ build_navmap_from_mesh()

bool build_navmap_from_mesh ( const pcl::PointCloud< pcl::PointXYZ > & cloud,
const std::vector< Eigen::Vector3i > & triangles,
const std::string & frame_id,
navmap_ros_interfaces::msg::NavMap & out_msg,
navmap::NavMap * out_core_opt )

◆ downsample_voxelize_avgXYZ()

pcl::PointCloud< pcl::PointXYZ > downsample_voxelize_avgXYZ ( const pcl::PointCloud< pcl::PointXYZ > & input_points,
float resolution )

◆ downsample_voxelize_avgZ()

pcl::PointCloud< pcl::PointXYZ > downsample_voxelize_avgZ ( const pcl::PointCloud< pcl::PointXYZ > & input_points,
float resolution )

◆ from_msg() [1/3]

navmap::NavMap from_msg ( const NavMap & msg)

◆ from_msg() [2/3]

navmap::NavMap from_msg ( const navmap_ros_interfaces::msg::NavMap & msg)

Reconstruct a core navmap::NavMap from the ROS transport message.

Parameters
[in]msgInput navmap_ros_interfaces::msg::NavMap message.
Returns
A core navmap::NavMap equivalent to the content of msg.
  • Intended to be the inverse of navmap_ros::to_msg for a round-trip without loss.
  • Assumes that the message is internally consistent (sizes and indices match).
Exceptions
std::runtime_errorIf the message describes inconsistent geometry or layer sizes.

◆ from_msg() [3/3]

void from_msg ( const navmap_ros_interfaces::msg::NavMapLayer & msg,
navmap::NavMap & nm )

Import a single NavMapLayer message into a NavMap.

If the layer already exists in nm, it is overwritten. Otherwise, it is created. Performs type dispatch based on the message field type.

Parameters
[in]msgInput NavMapLayer message.
[in,out]nmDestination NavMap (must already have navcels sized correctly).
  • The function verifies that the length of the populated data array matches the number of triangles (NavCels) in nm.
  • Exactly one of the arrays data_u8, data_f32, or data_f64 must be set.
Exceptions
std::runtime_errorIf sizes are inconsistent or the message is ill-formed.

◆ from_occupancy_grid()

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.

Parameters
[in]gridInput ROS OccupancyGrid (row-major, width×height, resolution and origin).
Returns
A core navmap::NavMap with:
  • Vertices: (W+1) * (H+1) laid on the grid plane, with Z = grid.info.origin.position.z.
  • Triangles: 2 * W * H (two per cell), using diagonal pattern = 0.
  • One surface whose frame matches grid.header.frame_id, and grid metadata filled.
  • A per-NavCel layer named "occupancy" of type uint8, with values mapped as: -1 → 255 (unknown), 0..100 → 0..254 (linear scaling).
  • Vertex layout follows the grid indexation with shared vertices across adjacent cells.
  • Triangle winding and diagonal split are deterministic (pattern = 0).
  • If width == 0 or height == 0, the returned map contains no triangles.
Note
The grid origin pose may contain a rotation. The vertex Z is taken from the origin Z; handling of non-zero yaw/roll/pitch (if any) is implementation-defined in the builder.

◆ from_pointcloud2()

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.

Parameters
[in]pc2Input PointCloud2 message (expects fields x, y, z).
[out]out_msgOutput transport message mirroring the created NavMap.
[in]paramsMeshing and filtering parameters (see BuildParams).
Returns
The constructed navmap::NavMap.
  • The cloud is decoded to pcl::PointXYZ and processed as in navmap_ros::from_points.
  • Non-Cartesian fields present in pc2 are ignored by this overload.
  • The resulting NavMap is exported to out_msg for downstream publication or storage.
Note
If the message is empty or lacks the required fields, no geometry is produced.
Exceptions
std::runtime_errorIf decoding fails or meshing cannot be completed.

◆ from_points()

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.

Parameters
[in]input_pointsPoint set in world coordinates (pcl::PointXYZ).
[out]out_msgOutput transport message mirroring the created NavMap.
[in]paramsMeshing and filtering parameters (see BuildParams).
Returns
The constructed navmap::NavMap.

Typical steps implemented by this builder include:

  • Optional downsampling according to params.resolution.
  • Local neighborhood discovery using either radius (params.use_radius) or k-NN.
  • Edge and face filtering based on params.max_edge_len, params.min_area and params.min_angle_deg.
  • Optional slope gating using params.max_slope_deg with respect to the vertical axis.
  • Creation of a single surface with shared vertices and triangle indices. The function also fills out_msg with the compact ROS representation of the resulting map.
Note
Input is treated as an unorganized cloud. If normals or intensities are present, they are ignored by this overload.
Exceptions
std::runtime_errorIf meshing fails due to inconsistent parameters or empty input.

◆ grow_surface_from_seed()

std::vector< Triangle > grow_surface_from_seed ( const pcl::PointCloud< pcl::PointXYZ > & cloud,
int seed_idx,
const BuildParams & P )

◆ local_tangent_basis()

void local_tangent_basis ( const std::vector< Eigen::Vector3f > & nbrs,
Eigen::Vector3f & t1,
Eigen::Vector3f & t2 )

◆ sort_neighbors_angular()

void sort_neighbors_angular ( const Eigen::Vector3f & vpos,
const std::vector< std::pair< int, Eigen::Vector3f > > & nbrs,
std::vector< int > & out_ordered )

◆ to_msg() [1/2]

NavMap to_msg ( const navmap::NavMap & nm)

Convert a core navmap::NavMap into its compact ROS transport message.

Parameters
[in]nmCore NavMap to be serialized into a ROS message.
Returns
A navmap_ros_interfaces::msg::NavMap containing geometry (vertices, triangles), surfaces metadata and user-defined layers.
  • Intended to be lossless with respect to the information represented in the message.
  • The ordering of vertices/triangles/layers in nm is preserved in the resulting message.
Note
This function does not perform IO; it only builds the message in-memory.

◆ to_msg() [2/2]

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.

Parameters
[in]nmInput NavMap.
[in]layerName of the layer to export.
Returns
A NavMapLayer message containing the layer values and metadata.
  • The returned message contains the layer name, type tag, and exactly one populated data array whose length equals the number of NavCels in nm.
  • The function performs a type-safe extraction (U8/F32/F64).
Exceptions
std::runtime_errorIf the layer does not exist or has an unsupported type.

◆ to_occupancy_grid()

nav_msgs::msg::OccupancyGrid to_occupancy_grid ( const navmap::NavMap & nm)

Convert a navmap::NavMap back to nav_msgs::msg::OccupancyGrid.

Parameters
[in]nmCore NavMap to be rasterized as an occupancy grid.
Returns
A ROS OccupancyGrid populated from nm.

Two paths are considered:

  • Fast exact path: If the first surface encodes valid grid metadata (GridMeta) and there is a per-NavCel "occupancy" layer of type U8 with size 2 * W * H, the function reconstructs an OccupancyGrid exactly (linear inverse mapping 0..254 → 0..100, 255 → -1).
  • Generic fallback: If the exact path is not applicable, the function samples cell centers via a navcel-locator (e.g., locate_navcel) and reads "occupancy" values to populate the grid.
Note
The fallback path assumes the presence of an "occupancy" layer. The precise sampling strategy (bounds, resolution, and handling of cells without a containing navcel) is implementation-defined.
Warning
If the map does not carry grid metadata or the "occupancy" layer is missing, the result may be incomplete or implementation-defined.

◆ triangle_angles_deg()

void triangle_angles_deg ( const Eigen::Vector3f & A,
const Eigen::Vector3f & B,
const Eigen::Vector3f & C,
float & angA,
float & angB,
float & angC )

◆ try_add_triangle()

bool try_add_triangle ( int i,
int j,
int k,
const pcl::PointCloud< pcl::PointXYZ > & cloud,
const BuildParams & P,
std::unordered_set< TriKey, TriHasher > & tri_set,
std::unordered_set< EdgeKey, EdgeHasher > & edge_set,
std::vector< Triangle > & tris )