Nav2 Navigation Stack - rolling  main
ROS 2 Navigation Stack
costmap_topic_collision_checker.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 // Modified by: Shivang Patel (shivaan14@gmail.com)
16 
17 #include <memory>
18 #include <string>
19 #include <vector>
20 #include <algorithm>
21 #include <iostream>
22 
23 #include "tf2/utils.hpp"
24 
25 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
26 
27 #include "nav2_costmap_2d/cost_values.hpp"
28 #include "nav2_costmap_2d/exceptions.hpp"
29 #include "nav2_costmap_2d/footprint.hpp"
30 #include "nav2_util/line_iterator.hpp"
31 
32 using namespace std::chrono_literals;
33 
34 namespace nav2_costmap_2d
35 {
36 
37 CostmapTopicCollisionChecker::CostmapTopicCollisionChecker(
38  CostmapSubscriber & costmap_sub,
39  FootprintSubscriber & footprint_sub,
40  std::string name)
41 : name_(name),
42  costmap_sub_(costmap_sub),
43  footprint_sub_(&footprint_sub),
44  collision_checker_(nullptr)
45 {}
46 
48  CostmapSubscriber & costmap_sub,
49  std::string footprint_string,
50  std::string name)
51 : name_(name),
52  costmap_sub_(costmap_sub),
53  collision_checker_(nullptr)
54 {
55  if (!makeFootprintFromString(footprint_string, footprint_)) {
56  throw CollisionCheckerException("Failed to create footprint from string");
57  }
58 }
59 
61  const geometry_msgs::msg::Pose & pose,
62  bool fetch_costmap_and_footprint)
63 {
64  try {
65  if (scorePose(pose, fetch_costmap_and_footprint) >= LETHAL_OBSTACLE) {
66  return false;
67  }
68  return true;
69  } catch (const IllegalPoseException & e) {
70  RCLCPP_ERROR(rclcpp::get_logger(name_), "%s", e.what());
71  return false;
72  } catch (const CollisionCheckerException & e) {
73  RCLCPP_ERROR(rclcpp::get_logger(name_), "%s", e.what());
74  return false;
75  } catch (...) {
76  RCLCPP_ERROR(rclcpp::get_logger(name_), "Failed to check pose score!");
77  return false;
78  }
79 }
80 
82  const geometry_msgs::msg::Pose & pose,
83  bool fetch_costmap_and_footprint)
84 {
85  if (fetch_costmap_and_footprint) {
86  try {
87  collision_checker_.setCostmap(costmap_sub_.getCostmap());
88  } catch (const std::runtime_error & e) {
89  throw CollisionCheckerException(e.what());
90  }
91  }
92 
93  unsigned int cell_x, cell_y;
94  if (!collision_checker_.worldToMap(pose.position.x, pose.position.y, cell_x, cell_y)) {
95  RCLCPP_DEBUG(rclcpp::get_logger(name_), "Map Cell: [%d, %d]", cell_x, cell_y);
96  throw IllegalPoseException(name_, "Pose Goes Off Grid.");
97  }
98 
99  return collision_checker_.footprintCost(getFootprint(pose, fetch_costmap_and_footprint));
100 }
101 
103  const geometry_msgs::msg::Pose & pose,
104  bool fetch_latest_footprint)
105 {
106  if (fetch_latest_footprint) {
107  std_msgs::msg::Header header;
108 
109  // if footprint_sub_ was not initialized (alternative constructor), we are using the
110  // footprint built from the footprint_string alternative constructor argument.
111  if (footprint_sub_ && !footprint_sub_->getFootprintInRobotFrame(footprint_, header)) {
112  throw CollisionCheckerException("Current footprint not available.");
113  }
114  }
115 
116  Footprint footprint;
117  double x = pose.position.x;
118  double y = pose.position.y;
119  double theta = tf2::getYaw(pose.orientation);
120  transformFootprint(x, y, theta, footprint_, footprint);
121 
122  return footprint;
123 }
124 
125 } // namespace nav2_costmap_2d
Exceptions thrown if collision checker determines a pose is in collision with the environment costmap...
Definition: exceptions.hpp:49
Subscribes to the costmap via a ros topic.
std::shared_ptr< Costmap2D > getCostmap()
Get current costmap.
double scorePose(const geometry_msgs::msg::Pose &pose, bool fetch_costmap_and_footprint=true)
Returns the obstacle footprint score for a particular pose.
Footprint getFootprint(const geometry_msgs::msg::Pose &pose, bool fetch_latest_footprint=true)
Get a footprint at a set pose.
bool isCollisionFree(const geometry_msgs::msg::Pose &pose, bool fetch_costmap_and_footprint=true)
Returns if a pose is collision free.
CostmapTopicCollisionChecker(CostmapSubscriber &costmap_sub, FootprintSubscriber &footprint_sub, std::string name="collision_checker")
A constructor.
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).
Thrown when CollisionChecker encounters a fatal error.
Definition: exceptions.hpp:60
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
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:177