Nav2 Navigation Stack - rolling  main
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.hpp"
23 #pragma GCC diagnostic pop
24 
25 namespace nav2_costmap_2d
26 {
27 
28 bool
30  std::vector<geometry_msgs::msg::Point> & footprint,
31  std_msgs::msg::Header & footprint_header)
32 {
33  if (!footprint_received_) {
34  return false;
35  }
36 
37  auto current_footprint = std::atomic_load(&footprint_);
38  footprint = toPointVector(current_footprint->polygon);
39  footprint_header = current_footprint->header;
40 
41  return true;
42 }
43 
44 bool
46  std::vector<geometry_msgs::msg::Point> & footprint,
47  std_msgs::msg::Header & footprint_header)
48 {
49  if (!getFootprintRaw(footprint, footprint_header)) {
50  return false;
51  }
52 
53  geometry_msgs::msg::PoseStamped current_pose;
54  if (!nav2_util::getCurrentPose(
55  current_pose, tf_, footprint_header.frame_id, robot_base_frame_,
56  transform_tolerance_, footprint_header.stamp))
57  {
58  return false;
59  }
60 
61  double x = current_pose.pose.position.x;
62  double y = current_pose.pose.position.y;
63  double theta = tf2::getYaw(current_pose.pose.orientation);
64 
65  std::vector<geometry_msgs::msg::Point> temp;
66  transformFootprint(-x, -y, 0, footprint, temp);
67  transformFootprint(0, 0, -theta, temp, footprint);
68 
69  footprint_header.frame_id = robot_base_frame_;
70  footprint_header.stamp = current_pose.header.stamp;
71 
72  return true;
73 }
74 
75 void
76 FootprintSubscriber::footprint_callback(const geometry_msgs::msg::PolygonStamped::SharedPtr msg)
77 {
78  std::atomic_store(&footprint_, msg);
79  if (!footprint_received_) {
80  footprint_received_ = true;
81  }
82 }
83 
84 } // 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.
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:112
std::vector< geometry_msgs::msg::Point > toPointVector(const geometry_msgs::msg::Polygon &polygon)
Convert Polygon msg to vector of Points.
Definition: footprint.cpp:102