23#ifndef EASYNAV_GRIDMAP_MAPS_MANAGER__GRIDMAPMAPSBUILDERNODE_HPP_
24#define EASYNAV_GRIDMAP_MAPS_MANAGER__GRIDMAPMAPSBUILDERNODE_HPP_
26#include "rclcpp/rclcpp.hpp"
27#include "rclcpp/macros.hpp"
28#include "rclcpp_lifecycle/lifecycle_node.hpp"
30#include "sensor_msgs/msg/point_cloud2.hpp"
31#include "grid_map_msgs/msg/grid_map.hpp"
32#include "std_srvs/srv/trigger.hpp"
34#include "grid_map_ros/grid_map_ros.hpp"
36#include "easynav_common/types/Perceptions.hpp"
54 using
CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
109 const grid_map::GridMap &
get_map()
const {
return map_;}
110 void set_map(
const grid_map::GridMap & map) {map_ = map;}
114 std::string sensor_topic_;
117 std::map<std::string, std::vector<PerceptionPtr>> perceptions_;
120 rclcpp::CallbackGroup::SharedPtr cbg_;
123 double downsample_resolution_;
126 std::string perception_default_frame_;
129 rclcpp_lifecycle::LifecyclePublisher<grid_map_msgs::msg::GridMap>::SharedPtr pub_;
132 std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_;
134 grid_map::GridMap map_;
GridmapMapsBuilderNode(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor.
Definition GridmapMapsBuilderNode.cpp:42
void cycle()
Perform a processing cycle on the perception data and update the grid map.
Definition GridmapMapsBuilderNode.cpp:150
CallbackReturnT on_activate(const rclcpp_lifecycle::State &state) override
Lifecycle activate callback.
Definition GridmapMapsBuilderNode.cpp:124
CallbackReturnT on_cleanup(const rclcpp_lifecycle::State &state) override
Lifecycle cleanup callback.
Definition GridmapMapsBuilderNode.cpp:141
const grid_map::GridMap & get_map() const
Definition GridmapMapsBuilderNode.hpp:109
void register_handler(std::shared_ptr< PerceptionHandler > handler)
Registers a perception handler.
Definition GridmapMapsBuilderNode.cpp:214
rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn CallbackReturnT
Definition GridmapMapsBuilderNode.hpp:54
CallbackReturnT on_configure(const rclcpp_lifecycle::State &state) override
Lifecycle configure callback.
Definition GridmapMapsBuilderNode.cpp:75
void set_map(const grid_map::GridMap &map)
Definition GridmapMapsBuilderNode.hpp:110
CallbackReturnT on_deactivate(const rclcpp_lifecycle::State &state) override
Lifecycle deactivate callback.
Definition GridmapMapsBuilderNode.cpp:132
Definition GridMapAStarPlanner.hpp:41