|
NavMap
|
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 | 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_topZ_layered (const pcl::PointCloud< pcl::PointXYZ > &input_points, float resolution, float dz_merge) |
| navmap::NavMap | from_msg (const NavMap &msg) |
| navmap::NavMap | from_msg (const NavMap &msg, std_msgs::msg::Header &header) |
| navmap::NavMap | from_msg (const navmap_ros_interfaces::msg::NavMap &msg) |
| Backward-compatible overload (ignores message header). | |
| navmap::NavMap | from_msg (const navmap_ros_interfaces::msg::NavMap &msg, std_msgs::msg::Header &header) |
Reconstruct a core navmap::NavMap from the ROS transport message. | |
| void | from_msg (const navmap_ros_interfaces::msg::NavMapLayer &msg, navmap::NavMap &nm) |
| Backward-compatible overload (ignores message header). | |
| void | from_msg (const navmap_ros_interfaces::msg::NavMapLayer &msg, navmap::NavMap &nm, std_msgs::msg::Header &header) |
| Import a single NavMapLayer message into a NavMap. | |
| navmap::NavMap | from_occupancy_grid (const nav_msgs::msg::OccupancyGrid &grid) |
| Backward-compatible overload (ignores grid header). | |
| navmap::NavMap | from_occupancy_grid (const nav_msgs::msg::OccupancyGrid &grid, std_msgs::msg::Header &header) |
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) |
| Backward-compatible overload (no header provided). | |
| navmap_ros_interfaces::msg::NavMapLayer | to_msg (const navmap::NavMap &nm, const std::string &layer) |
| Backward-compatible overload (no header provided). | |
| navmap_ros_interfaces::msg::NavMapLayer | to_msg (const navmap::NavMap &nm, const std::string &layer, const std_msgs::msg::Header &header) |
| Convert a single layer from a NavMap into a ROS message. | |
| navmap_ros_interfaces::msg::NavMap | to_msg (const navmap::NavMap &nm, const std_msgs::msg::Header &header) |
Convert a core navmap::NavMap into its compact ROS transport message. | |
| nav_msgs::msg::OccupancyGrid | to_occupancy_grid (const navmap::NavMap &nm) |
| Backward-compatible overload. | |
| nav_msgs::msg::OccupancyGrid | to_occupancy_grid (const navmap::NavMap &nm, const std_msgs::msg::Header &header) |
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) |
Variables | |
Costmap value semantics | |
Standardized occupancy/cost values used when projecting NavMap layers onto a 2D grid (compatible with These constants follow the same meaning as in
| |
| constexpr uint8_t | NO_INFORMATION = 255 |
| constexpr uint8_t | LETHAL_OBSTACLE = 254 |
| constexpr uint8_t | INSCRIBED_INFLATED_OBSTACLE = 253 |
| constexpr uint8_t | MAX_NON_OBSTACLE = 252 |
| constexpr uint8_t | FREE_SPACE = 0 |
Conversions between core NavMap and ROS-level structures.
| using Triangle = Eigen::Vector3i |
| 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_topZ_layered | ( | const pcl::PointCloud< pcl::PointXYZ > & | input_points, |
| float | resolution, | ||
| float | dz_merge ) |
| navmap::NavMap from_msg | ( | const NavMap & | msg | ) |
| navmap::NavMap from_msg | ( | const NavMap & | msg, |
| std_msgs::msg::Header & | header ) |
| navmap::NavMap from_msg | ( | const navmap_ros_interfaces::msg::NavMap & | msg | ) |
Backward-compatible overload (ignores message header).
| navmap::NavMap from_msg | ( | const navmap_ros_interfaces::msg::NavMap & | msg, |
| std_msgs::msg::Header & | header ) |
Reconstruct a core navmap::NavMap from the ROS transport message.
| [in] | msg | Input navmap_ros_interfaces::msg::NavMap message. |
| [out] | header | Header extracted from the message. |
navmap::NavMap equivalent to the content of msg.| std::runtime_error | If the message describes inconsistent geometry or layer sizes. |
| void from_msg | ( | const navmap_ros_interfaces::msg::NavMapLayer & | msg, |
| navmap::NavMap & | nm ) |
Backward-compatible overload (ignores message header).
| void from_msg | ( | const navmap_ros_interfaces::msg::NavMapLayer & | msg, |
| navmap::NavMap & | nm, | ||
| std_msgs::msg::Header & | header ) |
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.
| [in] | msg | Input NavMapLayer message. |
| [in,out] | nm | Destination NavMap (must already have navcels sized correctly). |
| [out] | header | Header extracted from the message. |
nm.data_u8, data_f32, or data_f64 must be set.| std::runtime_error | If sizes are inconsistent or the message is ill-formed. |
| navmap::NavMap from_occupancy_grid | ( | const nav_msgs::msg::OccupancyGrid & | grid | ) |
Backward-compatible overload (ignores grid header).
| navmap::NavMap from_occupancy_grid | ( | const nav_msgs::msg::OccupancyGrid & | grid, |
| std_msgs::msg::Header & | header ) |
Build a navmap::NavMap from a nav_msgs::msg::OccupancyGrid using a regular triangular surface with shared vertices.
| [in] | grid | Input ROS OccupancyGrid (row-major, width×height, resolution and origin). |
| [out] | header | Header to assign to the resulting message. |
navmap::NavMap with:(W+1) * (H+1) laid on the grid plane, with Z = grid.info.origin.position.z.2 * W * H (two per cell), using diagonal pattern = 0.grid.header.frame_id, and grid metadata filled."occupancy" of type uint8, with values mapped as: -1 → 255 (unknown), 0..100 → 0..254 (linear scaling).width == 0 or height == 0, the returned map contains no triangles.| 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.
| [in] | pc2 | Input PointCloud2 message (expects fields x, y, z). |
| [out] | out_msg | Output transport message mirroring the created NavMap. |
| [in] | params | Meshing and filtering parameters (see BuildParams). |
navmap::NavMap.pcl::PointXYZ and processed as in navmap_ros::from_points.pc2 are ignored by this overload.out_msg for downstream publication or storage.| std::runtime_error | If decoding fails or meshing cannot be completed. |
| 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.
| [in] | input_points | Point set in world coordinates (pcl::PointXYZ). |
| [out] | out_msg | Output transport message mirroring the created NavMap. |
| [in] | params | Meshing and filtering parameters (see BuildParams). |
navmap::NavMap.Typical steps implemented by this builder include:
params.resolution.params.use_radius) or k-NN.params.max_edge_len, params.min_area and params.min_angle_deg.params.max_slope_deg with respect to the vertical axis.out_msg with the compact ROS representation of the resulting map.| std::runtime_error | If meshing fails due to inconsistent parameters or empty input. |
| NavMap to_msg | ( | const navmap::NavMap & | nm | ) |
Backward-compatible overload (no header provided).
The returned message header will be default-constructed.
| navmap_ros_interfaces::msg::NavMapLayer to_msg | ( | const navmap::NavMap & | nm, |
| const std::string & | layer ) |
Backward-compatible overload (no header provided).
| navmap_ros_interfaces::msg::NavMapLayer to_msg | ( | const navmap::NavMap & | nm, |
| const std::string & | layer, | ||
| const std_msgs::msg::Header & | header ) |
Convert a single layer from a NavMap into a ROS message.
| [in] | nm | Input NavMap. |
| [in] | layer | Name of the layer to export. |
| [in] | header | Header to assign to the resulting message. |
nm.| std::runtime_error | If the layer does not exist or has an unsupported type. |
| NavMap to_msg | ( | const navmap::NavMap & | nm, |
| const std_msgs::msg::Header & | header ) |
Convert a core navmap::NavMap into its compact ROS transport message.
| [in] | nm | Core NavMap to be serialized into a ROS message. |
| [in] | header | Header to assign to the resulting message. |
navmap_ros_interfaces::msg::NavMap containing geometry (vertices, triangles), surfaces metadata and user-defined layers.nm is preserved in the resulting message.| nav_msgs::msg::OccupancyGrid to_occupancy_grid | ( | const navmap::NavMap & | nm | ) |
Backward-compatible overload.
| nav_msgs::msg::OccupancyGrid to_occupancy_grid | ( | const navmap::NavMap & | nm, |
| const std_msgs::msg::Header & | header ) |
Convert a navmap::NavMap back to nav_msgs::msg::OccupancyGrid.
| [in] | nm | Core NavMap to be rasterized as an occupancy grid. |
OccupancyGrid populated from nm.Two paths are considered:
"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).locate_navcel) and reads "occupancy" values to populate the grid."occupancy" layer. The precise sampling strategy (bounds, resolution, and handling of cells without a containing navcel) is implementation-defined."occupancy" layer is missing, the result may be incomplete or implementation-defined. | 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 ) |
|
constexpr |
|
constexpr |
|
constexpr |
|
constexpr |
|
constexpr |