Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap_filter_info_server.hpp
1 // Copyright (c) 2020 Samsung Research Russia
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
15 #ifndef NAV2_MAP_SERVER__COSTMAP_FILTER_INFO_SERVER_HPP_
16 #define NAV2_MAP_SERVER__COSTMAP_FILTER_INFO_SERVER_HPP_
17 
18 #include <memory>
19 
20 #include "rclcpp/rclcpp.hpp"
21 #include "nav2_util/lifecycle_node.hpp"
22 #include "nav2_msgs/msg/costmap_filter_info.hpp"
23 
24 namespace nav2_map_server
25 {
26 
28 {
29 public:
34  explicit CostmapFilterInfoServer(const rclcpp::NodeOptions & options = rclcpp::NodeOptions());
35 
40 
41 protected:
47  nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State & state) override;
53  nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State & state) override;
59  nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State & state) override;
65  nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State & state) override;
71  nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State & state) override;
72 
73 private:
74  rclcpp_lifecycle::LifecyclePublisher<nav2_msgs::msg::CostmapFilterInfo>::SharedPtr publisher_;
75 
76  nav2_msgs::msg::CostmapFilterInfo msg_;
77 }; // CostmapFilterInfoServer
78 
79 } // namespace nav2_map_server
80 
81 #endif // NAV2_MAP_SERVER__COSTMAP_FILTER_INFO_SERVER_HPP_
~CostmapFilterInfoServer()
Destructor for the nav2_map_server::CostmapFilterInfoServer.
nav2_util::CallbackReturn on_configure(const rclcpp_lifecycle::State &state) override
Creates CostmapFilterInfo publisher and forms published message from ROS parameters.
nav2_util::CallbackReturn on_cleanup(const rclcpp_lifecycle::State &state) override
Resets publisher.
CostmapFilterInfoServer(const rclcpp::NodeOptions &options=rclcpp::NodeOptions())
Constructor for the nav2_map_server::CostmapFilterInfoServer.
nav2_util::CallbackReturn on_deactivate(const rclcpp_lifecycle::State &state) override
Deactivates publisher.
nav2_util::CallbackReturn on_shutdown(const rclcpp_lifecycle::State &state) override
Called when in Shutdown state.
nav2_util::CallbackReturn on_activate(const rclcpp_lifecycle::State &state) override
Publishes a CostmapFilterInfo message.
A lifecycle node wrapper to enable common Nav2 needs such as manipulating parameters.