|
NavMap
|
Conversions between the core NavMap representation and ROS messages. More...
#include <string>#include <Eigen/Core>#include <pcl/point_cloud.h>#include <pcl/point_types.h>#include "std_msgs/msg/header.hpp"#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"

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) |
| 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. | |
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 | FREE_SPACE = 0 |
| constexpr uint8_t | INSCRIBED_INFLATED_OBSTACLE = 253 |
| constexpr uint8_t | LETHAL_OBSTACLE = 254 |
| constexpr uint8_t | MAX_NON_OBSTACLE = 252 |
| constexpr uint8_t | NO_INFORMATION = 255 |
Conversions between the core NavMap representation and ROS messages.
This header provides:
navmap::NavMap and the compact transport message navmap_ros_interfaces::msg::NavMap.nav_msgs::msg::OccupancyGrid and navmap::NavMap using a regular triangular mesh (shared vertices, two triangles per grid cell).When building a NavMap from an OccupancyGrid, a per-NavCel (triangle) layer named "occupancy" (uint8) is added with the following value mapping:
-1 (unknown) → 2550..100 (percent) → 0..254 (linear scaling)The reverse conversion reuses that layer when present.