Nav2 Navigation Stack - jazzy  jazzy
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_msgs/msg/costmap_update.hpp"
25 #include "nav2_util/lifecycle_node.hpp"
26 
27 namespace nav2_costmap_2d
28 {
34 {
35 public:
40  const nav2_util::LifecycleNode::WeakPtr & parent,
41  const std::string & topic_name);
42 
47  const rclcpp::Node::WeakPtr & parent,
48  const std::string & topic_name);
49 
54 
58  std::shared_ptr<Costmap2D> getCostmap();
62  void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg);
66  void costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg);
67 
68 protected:
69  bool isCostmapReceived() {return costmap_ != nullptr;}
70  void processCurrentCostmapMsg();
71 
72  bool haveCostmapParametersChanged();
73  bool hasCostmapSizeChanged();
74  bool hasCostmapResolutionChanged();
75  bool hasCostmapOriginPositionChanged();
76 
77  rclcpp::Subscription<nav2_msgs::msg::Costmap>::SharedPtr costmap_sub_;
78  rclcpp::Subscription<nav2_msgs::msg::CostmapUpdate>::SharedPtr costmap_update_sub_;
79 
80  std::shared_ptr<Costmap2D> costmap_;
81  nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
82 
83  std::string topic_name_;
84  std::mutex costmap_msg_mutex_;
85  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
86 };
87 
88 } // namespace nav2_costmap_2d
89 
90 #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 costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
Callback for the costmap's update topic.
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
Callback for the costmap topic.
std::shared_ptr< Costmap2D > getCostmap()
Get current costmap.