Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
costmap_subscriber.hpp
1 // Copyright (c) 2019 Intel Corporation
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_COSTMAP_2D__COSTMAP_SUBSCRIBER_HPP_
16 #define NAV2_COSTMAP_2D__COSTMAP_SUBSCRIBER_HPP_
17 
18 #include <string>
19 #include <memory>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_costmap_2d/costmap_2d.hpp"
23 #include "nav2_msgs/msg/costmap.hpp"
24 #include "nav2_util/lifecycle_node.hpp"
25 
26 namespace nav2_costmap_2d
27 {
33 {
34 public:
39  const nav2_util::LifecycleNode::WeakPtr & parent,
40  const std::string & topic_name);
41 
46  const rclcpp::Node::WeakPtr & parent,
47  const std::string & topic_name);
48 
53 
57  std::shared_ptr<Costmap2D> getCostmap();
58 
62  void toCostmap2D();
66  void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg);
67 
68 protected:
69  std::shared_ptr<Costmap2D> costmap_;
70  nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
71  std::string topic_name_;
72  bool costmap_received_{false};
73  rclcpp::Subscription<nav2_msgs::msg::Costmap>::SharedPtr costmap_sub_;
74 };
75 
76 } // namespace nav2_costmap_2d
77 
78 #endif // NAV2_COSTMAP_2D__COSTMAP_SUBSCRIBER_HPP_
Subscribes to the costmap via a ros topic.
CostmapSubscriber(const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name)
A constructor.
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
Callback for the costmap topic.
void toCostmap2D()
Convert an occ grid message into a costmap object.
std::shared_ptr< Costmap2D > getCostmap()
A Get the costmap from topic.