Nav2 Navigation Stack - jazzy  jazzy
ROS 2 Navigation Stack
footprint_subscriber.cpp
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 #include <string>
16 #include <vector>
17 #include <memory>
18 
19 #include "nav2_costmap_2d/footprint_subscriber.hpp"
20 #pragma GCC diagnostic push
21 #pragma GCC diagnostic ignored "-Wpedantic"
22 #include "tf2/utils.h"
23 #pragma GCC diagnostic pop
24 
25 namespace nav2_costmap_2d
26 {
27 
29  const nav2_util::LifecycleNode::WeakPtr & parent,
30  const std::string & topic_name,
31  tf2_ros::Buffer & tf,
32  std::string robot_base_frame,
33  double transform_tolerance)
34 : tf_(tf),
35  robot_base_frame_(robot_base_frame),
36  transform_tolerance_(transform_tolerance)
37 {
38  auto node = parent.lock();
39  footprint_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
40  topic_name, rclcpp::SystemDefaultsQoS(),
41  std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1));
42 }
43 
45  const rclcpp::Node::WeakPtr & parent,
46  const std::string & topic_name,
47  tf2_ros::Buffer & tf,
48  std::string robot_base_frame,
49  double transform_tolerance)
50 : tf_(tf),
51  robot_base_frame_(robot_base_frame),
52  transform_tolerance_(transform_tolerance)
53 {
54  auto node = parent.lock();
55  footprint_sub_ = node->create_subscription<geometry_msgs::msg::PolygonStamped>(
56  topic_name, rclcpp::SystemDefaultsQoS(),
57  std::bind(&FootprintSubscriber::footprint_callback, this, std::placeholders::_1));
58 }
59 
60 bool
62  std::vector<geometry_msgs::msg::Point> & footprint,
63  std_msgs::msg::Header & footprint_header)
64 {
65  if (!footprint_received_) {
66  return false;
67  }
68 
69  auto current_footprint = std::atomic_load(&footprint_);
70  footprint = toPointVector(
71  std::make_shared<geometry_msgs::msg::Polygon>(current_footprint->polygon));
72  footprint_header = current_footprint->header;
73 
74  return true;
75 }
76 
77 bool
79  std::vector<geometry_msgs::msg::Point> & footprint,
80  std_msgs::msg::Header & footprint_header)
81 {
82  if (!getFootprintRaw(footprint, footprint_header)) {
83  return false;
84  }
85 
86  geometry_msgs::msg::PoseStamped current_pose;
87  if (!nav2_util::getCurrentPose(
88  current_pose, tf_, footprint_header.frame_id, robot_base_frame_,
89  transform_tolerance_, footprint_header.stamp))
90  {
91  return false;
92  }
93 
94  double x = current_pose.pose.position.x;
95  double y = current_pose.pose.position.y;
96  double theta = tf2::getYaw(current_pose.pose.orientation);
97 
98  std::vector<geometry_msgs::msg::Point> temp;
99  transformFootprint(-x, -y, 0, footprint, temp);
100  transformFootprint(0, 0, -theta, temp, footprint);
101 
102  footprint_header.frame_id = robot_base_frame_;
103  footprint_header.stamp = current_pose.header.stamp;
104 
105  return true;
106 }
107 
108 void
109 FootprintSubscriber::footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg)
110 {
111  std::atomic_store(&footprint_, msg);
112  if (!footprint_received_) {
113  footprint_received_ = true;
114  }
115 }
116 
117 } // namespace nav2_costmap_2d
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).
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)
Definition: footprint.cpp:110
std::vector< geometry_msgs::msg::Point > toPointVector(geometry_msgs::msg::Polygon::SharedPtr polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:101