EasyNav Gridmap Stack
Loading...
Searching...
No Matches
GridmapMapsBuilderNode.hpp
Go to the documentation of this file.
1// Copyright 2025 Intelligent Robotics Lab
2//
3// This file is part of the project Easy Navigation (EasyNav in sh0rt)
4// licensed under the GNU General Public License v3.0.
5// See <http://www.gnu.org/licenses/> for details.
6//
7// Easy Navigation program is free software: you can redistribute it and/or modify
8// it under the terms of the GNU General Public License as published by
9// the Free Software Foundation, either version 3 of the License, or
10// (at your option) any later version.
11//
12// This program is distributed in the hope that it will be useful,
13// but WITHOUT ANY WARRANTY; without even the implied warranty of
14// MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
15// GNU General Public License for more details.
16//
17// You should have received a copy of the GNU General Public License
18// along with this program. If not, see <http://www.gnu.org/licenses/>.
19
22
23#ifndef EASYNAV_GRIDMAP_MAPS_MANAGER__GRIDMAPMAPSBUILDERNODE_HPP_
24#define EASYNAV_GRIDMAP_MAPS_MANAGER__GRIDMAPMAPSBUILDERNODE_HPP_
25
26#include "rclcpp/rclcpp.hpp"
27#include "rclcpp/macros.hpp"
28#include "rclcpp_lifecycle/lifecycle_node.hpp"
29
30#include "sensor_msgs/msg/point_cloud2.hpp"
31#include "grid_map_msgs/msg/grid_map.hpp"
32#include "std_srvs/srv/trigger.hpp"
33
34#include "grid_map_ros/grid_map_ros.hpp"
35
36#include "easynav_common/types/Perceptions.hpp"
37
38namespace easynav
39{
40
49class GridmapMapsBuilderNode : public rclcpp_lifecycle::LifecycleNode
50{
51public:
52 RCLCPP_SMART_PTR_DEFINITIONS(GridmapMapsBuilderNode)
53
54 using CallbackReturnT = rclcpp_lifecycle::node_interfaces::LifecycleNodeInterface::CallbackReturn;
55
60 explicit GridmapMapsBuilderNode(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
61
66
72 CallbackReturnT on_configure(const rclcpp_lifecycle::State & state) override;
73
79 CallbackReturnT on_activate(const rclcpp_lifecycle::State & state) override;
80
86 CallbackReturnT on_deactivate(const rclcpp_lifecycle::State & state) override;
87
93 CallbackReturnT on_cleanup(const rclcpp_lifecycle::State & state) override;
94
101 void cycle();
102
107 void register_handler(std::shared_ptr<PerceptionHandler> handler);
108
109 const grid_map::GridMap & get_map() const {return map_;}
110 void set_map(const grid_map::GridMap & map) {map_ = map;}
111
112private:
114 std::string sensor_topic_;
115
117 std::map<std::string, std::vector<PerceptionPtr>> perceptions_;
118
120 rclcpp::CallbackGroup::SharedPtr cbg_;
121
123 double downsample_resolution_;
124
126 std::string perception_default_frame_;
127
129 rclcpp_lifecycle::LifecyclePublisher<grid_map_msgs::msg::GridMap>::SharedPtr pub_;
130
132 std::map<std::string, std::shared_ptr<PerceptionHandler>> handlers_;
133
134 grid_map::GridMap map_;
135};
136
137} // namespace easynav
138
139#endif // EASYNAV_GRIDMAP_MAPS_MANAGER__GRIDMAPMAPSBUILDERNODE_HPP_
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