Nav2 Navigation Stack - kilted  kilted
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 "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
24 
25 #include "nav2_costmap_2d/cost_values.hpp"
26 #include "nav2_costmap_2d/exceptions.hpp"
27 #include "nav2_costmap_2d/footprint.hpp"
28 #include "nav2_util/line_iterator.hpp"
29 
30 using namespace std::chrono_literals;
31 
32 namespace nav2_costmap_2d
33 {
34 
35 CostmapTopicCollisionChecker::CostmapTopicCollisionChecker(
36  CostmapSubscriber & costmap_sub,
37  FootprintSubscriber & footprint_sub,
38  std::string name)
39 : name_(name),
40  costmap_sub_(costmap_sub),
41  footprint_sub_(&footprint_sub),
42  collision_checker_(nullptr)
43 {}
44 
46  CostmapSubscriber & costmap_sub,
47  std::string footprint_string,
48  std::string name)
49 : name_(name),
50  costmap_sub_(costmap_sub),
51  collision_checker_(nullptr)
52 {
53  if (!makeFootprintFromString(footprint_string, footprint_)) {
54  throw CollisionCheckerException("Failed to create footprint from string");
55  }
56 }
57 
59  const geometry_msgs::msg::Pose2D & pose,
60  bool fetch_costmap_and_footprint)
61 {
62  try {
63  if (scorePose(pose, fetch_costmap_and_footprint) >= LETHAL_OBSTACLE) {
64  return false;
65  }
66  return true;
67  } catch (const IllegalPoseException & e) {
68  RCLCPP_ERROR(rclcpp::get_logger(name_), "%s", e.what());
69  return false;
70  } catch (const CollisionCheckerException & e) {
71  RCLCPP_ERROR(rclcpp::get_logger(name_), "%s", e.what());
72  return false;
73  } catch (...) {
74  RCLCPP_ERROR(rclcpp::get_logger(name_), "Failed to check pose score!");
75  return false;
76  }
77 }
78 
80  const geometry_msgs::msg::Pose2D & pose,
81  bool fetch_costmap_and_footprint)
82 {
83  if (fetch_costmap_and_footprint) {
84  try {
85  collision_checker_.setCostmap(costmap_sub_.getCostmap());
86  } catch (const std::runtime_error & e) {
87  throw CollisionCheckerException(e.what());
88  }
89  }
90 
91  unsigned int cell_x, cell_y;
92  if (!collision_checker_.worldToMap(pose.x, pose.y, cell_x, cell_y)) {
93  RCLCPP_DEBUG(rclcpp::get_logger(name_), "Map Cell: [%d, %d]", cell_x, cell_y);
94  throw IllegalPoseException(name_, "Pose Goes Off Grid.");
95  }
96 
97  return collision_checker_.footprintCost(getFootprint(pose, fetch_costmap_and_footprint));
98 }
99 
101  const geometry_msgs::msg::Pose2D & pose,
102  bool fetch_latest_footprint)
103 {
104  if (fetch_latest_footprint) {
105  std_msgs::msg::Header header;
106 
107  // if footprint_sub_ was not initialized (alternative constructor), we are using the
108  // footprint built from the footprint_string alternative constructor argument.
109  if (footprint_sub_ && !footprint_sub_->getFootprintInRobotFrame(footprint_, header)) {
110  throw CollisionCheckerException("Current footprint not available.");
111  }
112  }
113  Footprint footprint;
114  transformFootprint(pose.x, pose.y, pose.theta, footprint_, footprint);
115 
116  return footprint;
117 }
118 
119 } // 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.
Footprint getFootprint(const geometry_msgs::msg::Pose2D &pose, bool fetch_latest_footprint=true)
Get a footprint at a set pose.
double scorePose(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns the obstacle footprint score for a particular pose.
CostmapTopicCollisionChecker(CostmapSubscriber &costmap_sub, FootprintSubscriber &footprint_sub, std::string name="collision_checker")
A constructor.
bool isCollisionFree(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns if a pose is collision free.
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:110
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.
Definition: footprint.cpp:175