Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
footprint_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__FOOTPRINT_SUBSCRIBER_HPP_
16 #define NAV2_COSTMAP_2D__FOOTPRINT_SUBSCRIBER_HPP_
17 
18 #include <string>
19 #include <vector>
20 
21 #include "rclcpp/rclcpp.hpp"
22 #include "nav2_costmap_2d/footprint.hpp"
23 #include "nav2_util/lifecycle_node.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 
26 namespace nav2_costmap_2d
27 {
34 {
35 public:
40  const nav2_util::LifecycleNode::WeakPtr & parent,
41  const std::string & topic_name,
42  tf2_ros::Buffer & tf,
43  std::string robot_base_frame = "base_link",
44  double transform_tolerance = 0.1);
45 
50  const rclcpp::Node::WeakPtr & parent,
51  const std::string & topic_name,
52  tf2_ros::Buffer & tf,
53  std::string robot_base_frame = "base_link",
54  double transform_tolerance = 0.1);
55 
60 
68  bool getFootprintRaw(
69  std::vector<geometry_msgs::msg::Point> & footprint,
70  std_msgs::msg::Header & footprint_header);
71 
80  std::vector<geometry_msgs::msg::Point> & footprint,
81  std_msgs::msg::Header & footprint_header);
82 
83 protected:
87  void footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg);
88 
89  tf2_ros::Buffer & tf_;
90  std::string robot_base_frame_;
91  double transform_tolerance_;
92  bool footprint_received_{false};
93  geometry_msgs::msg::PolygonStamped::SharedPtr footprint_;
94  rclcpp::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr footprint_sub_;
95 };
96 
97 } // namespace nav2_costmap_2d
98 
99 #endif // NAV2_COSTMAP_2D__FOOTPRINT_SUBSCRIBER_HPP_
Subscriber to the footprint topic to get current robot footprint (if changing) for use in collision a...
bool getFootprintInRobotFrame(std::vector< geometry_msgs::msg::Point > &footprint, std_msgs::msg::Header &footprint_header)
Returns the latest robot footprint, transformed into robot base frame (unoriented).
void footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg)
Callback to process new footprint updates.
FootprintSubscriber(const nav2_util::LifecycleNode::WeakPtr &parent, const std::string &topic_name, tf2_ros::Buffer &tf, std::string robot_base_frame="base_link", double transform_tolerance=0.1)
A constructor.
bool getFootprintRaw(std::vector< geometry_msgs::msg::Point > &footprint, std_msgs::msg::Header &footprint_header)
Returns the latest robot footprint, in the form as received from topic (oriented).