19#ifndef EASYNAV_PLANNER__SIMPLEMAPMANAGER_HPP_
20#define EASYNAV_PLANNER__SIMPLEMAPMANAGER_HPP_
24#include "nav_msgs/msg/occupancy_grid.hpp"
25#include "std_srvs/srv/trigger.hpp"
27#include "easynav_core/MapsManagerBase.hpp"
31#include "pluginlib/class_loader.hpp"
74 virtual void update(NavState & nav_state)
override;
98 std::shared_ptr<Costmap2D> dynamic_map_;
103 rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr static_occ_pub_;
108 rclcpp::Publisher<nav_msgs::msg::OccupancyGrid>::SharedPtr dynamic_occ_pub_;
113 rclcpp::Subscription<nav_msgs::msg::OccupancyGrid>::SharedPtr incoming_map_sub_;
118 rclcpp::Service<std_srvs::srv::Trigger>::SharedPtr savemap_srv_;
123 nav_msgs::msg::OccupancyGrid static_grid_msg_;
128 nav_msgs::msg::OccupancyGrid dynamic_grid_msg_;
130 std::unique_ptr<pluginlib::ClassLoader<CostmapFilter>> costmap_filters_loader_;
132 std::vector<std::shared_ptr<CostmapFilter>> costmap_filters_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition costmap_2d.hpp:66
virtual void update(NavState &nav_state) override
Updates the internal maps using the current navigation state.
Definition CostmapMapsManager.cpp:178
CostmapMapsManager()
Default constructor.
Definition CostmapMapsManager.cpp:35
void set_static_map(const Costmap2D &new_map)
Replaces the current static map.
Definition CostmapMapsManager.cpp:171
~CostmapMapsManager()
Destructor.
Definition CostmapMapsManager.cpp:49
std::string map_path_
Full path to the map file.
Definition CostmapMapsManager.hpp:87
virtual void on_initialize() override
Initializes the maps manager.
Definition CostmapMapsManager.cpp:52
Provides a mapping for often used cost values.
Definition cost_values.hpp:41