19#ifndef EASYNAV_OCTOMAP_MAPS_MANAGER__OCTOMAP_MAPS_MANAGER_HPP_
20#define EASYNAV_OCTOMAP_MAPS_MANAGER__OCTOMAP_MAPS_MANAGER_HPP_
24#include "nav_msgs/msg/occupancy_grid.hpp"
25#include "octomap_msgs/msg/octomap.hpp"
26#include "std_srvs/srv/trigger.hpp"
27#include "sensor_msgs/msg/point_cloud2.hpp"
29#include "easynav_core/MapsManagerBase.hpp"
30#include "octomap/octomap.h"
33#include "pluginlib/class_loader.hpp"
78 virtual void update(::easynav::NavState & nav_state)
override;
90 std::shared_ptr<::octomap::OcTree> octomap_;
95 rclcpp::Publisher<octomap_msgs::msg::Octomap>::SharedPtr octomap_pub_;
100 rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr incoming_occ_map_sub_;
105 rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr incoming_pc2_map_sub_;
110 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr savemap_srv_;
115 octomap_msgs::msg::Octomap octomap_msg_;
117 std::unique_ptr<pluginlib::ClassLoader<OctomapFilter>> octomap_filters_loader_;
119 std::vector<std::shared_ptr<OctomapFilter>> octomap_filters_;
121 double resolution_ {1.0};
~OctomapMapsManager()
Destructor.
Definition OctomapMapsManager.cpp:56
std::string map_path_
Full path to the map file.
Definition OctomapMapsManager.hpp:84
virtual void on_initialize() override
Initializes the maps manager.
Definition OctomapMapsManager.cpp:59
OctomapMapsManager()
Default constructor.
Definition OctomapMapsManager.cpp:42
virtual void update(::easynav::NavState &nav_state) override
Updates the internal maps using the current navigation state.
Definition OctomapMapsManager.cpp:249
Definition InflationFilter.hpp:32
Provides a mapping for often used cost values.
Definition cost_values.hpp:41