Nav2 Navigation Stack - rolling  main
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_ros_common/lifecycle_node.hpp"
26 
27 namespace nav2_costmap_2d
28 {
34 {
35 public:
40  const nav2::LifecycleNode::WeakPtr & parent,
41  const std::string & topic_name);
42 
43  template<typename NodeT>
45  const NodeT & parent,
46  const std::string & topic_name)
47  : topic_name_(topic_name)
48  {
49  logger_ = parent->get_logger();
50 
51  // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the
52  // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode
53  costmap_sub_ = nav2::interfaces::create_subscription<nav2_msgs::msg::Costmap>(
54  parent, topic_name_,
55  std::bind(&CostmapSubscriber::costmapCallback, this, std::placeholders::_1),
57 
58  costmap_update_sub_ = nav2::interfaces::create_subscription<nav2_msgs::msg::CostmapUpdate>(
59  parent, topic_name_ + "_updates",
60  std::bind(&CostmapSubscriber::costmapUpdateCallback, this, std::placeholders::_1),
62  }
63 
68 
72  std::shared_ptr<Costmap2D> getCostmap();
76  void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg);
80  void costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg);
81 
82  std::string getFrameID() const
83  {
84  return frame_id_;
85  }
86 
87 protected:
88  bool isCostmapReceived() {return costmap_ != nullptr;}
89  void processCurrentCostmapMsg();
90 
91  bool haveCostmapParametersChanged();
92  bool hasCostmapSizeChanged();
93  bool hasCostmapResolutionChanged();
94  bool hasCostmapOriginPositionChanged();
95 
96  nav2::Subscription<nav2_msgs::msg::Costmap>::SharedPtr costmap_sub_;
97  nav2::Subscription<nav2_msgs::msg::CostmapUpdate>::SharedPtr costmap_update_sub_;
98 
99  std::shared_ptr<Costmap2D> costmap_;
100  nav2_msgs::msg::Costmap::SharedPtr costmap_msg_;
101 
102  std::string topic_name_;
103  std::string frame_id_;
104  std::mutex costmap_msg_mutex_;
105  rclcpp::Logger logger_{rclcpp::get_logger("nav2_costmap_2d")};
106 };
107 
108 } // namespace nav2_costmap_2d
109 
110 #endif // NAV2_COSTMAP_2D__COSTMAP_SUBSCRIBER_HPP_
A QoS profile for latched, reliable topics with a history of 10 messages.
Subscribes to the costmap via a ros topic.
void costmapUpdateCallback(const nav2_msgs::msg::CostmapUpdate::SharedPtr update_msg)
Callback for the costmap's update topic.
CostmapSubscriber(const nav2::LifecycleNode::WeakPtr &parent, const std::string &topic_name)
A constructor.
void costmapCallback(const nav2_msgs::msg::Costmap::SharedPtr msg)
Callback for the costmap topic.
std::shared_ptr< Costmap2D > getCostmap()
Get current costmap.