Nav2 Navigation Stack - rolling  main
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_ros_common/lifecycle_node.hpp"
24 #include "nav2_util/robot_utils.hpp"
25 
26 namespace nav2_costmap_2d
27 {
34 {
35 public:
39  template<typename NodeT>
41  const NodeT & parent,
42  const std::string & topic_name,
43  tf2_ros::Buffer & tf,
44  std::string robot_base_frame = "base_link",
45  double transform_tolerance = 0.1)
46  : tf_(tf),
47  robot_base_frame_(robot_base_frame),
48  transform_tolerance_(transform_tolerance)
49  {
50  // Could be using a user rclcpp::Node, so need to use the Nav2 factory to create the
51  // subscription to convert nav2::LifecycleNode, rclcpp::Node or rclcpp_lifecycle::LifecycleNode
52  footprint_sub_ = nav2::interfaces::create_subscription<geometry_msgs::msg::PolygonStamped>(
53  parent, topic_name,
54  std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1));
55  }
56 
61 
69  bool getFootprintRaw(
70  std::vector<geometry_msgs::msg::Point> & footprint,
71  std_msgs::msg::Header & footprint_header);
72 
81  std::vector<geometry_msgs::msg::Point> & footprint,
82  std_msgs::msg::Header & footprint_header);
83 
84 protected:
88  void footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg);
89 
90  tf2_ros::Buffer & tf_;
91  std::string robot_base_frame_;
92  double transform_tolerance_;
93  bool footprint_received_{false};
94  geometry_msgs::msg::PolygonStamped::SharedPtr footprint_;
95  nav2::Subscription<geometry_msgs::msg::PolygonStamped>::SharedPtr footprint_sub_;
96 };
97 
98 } // namespace nav2_costmap_2d
99 
100 #endif // NAV2_COSTMAP_2D__FOOTPRINT_SUBSCRIBER_HPP_
Subscriber to the footprint topic to get current robot footprint (if changing) for use in collision a...
FootprintSubscriber(const NodeT &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 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.
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).