Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
collision_checker.hpp
1 // Copyright (c) 2020, Samsung Research America
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. Reserved.
14 #include <vector>
15 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
16 #include "nav2_smac_planner/constants.hpp"
17 #include "rclcpp_lifecycle/lifecycle_node.hpp"
18 
19 #ifndef NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
20 #define NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
21 
22 namespace nav2_smac_planner
23 {
24 
30  : public nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>
31 {
32 public:
43  unsigned int num_quantizations,
44  rclcpp_lifecycle::LifecycleNode::SharedPtr node);
45 
53  // GridCollisionChecker(
54  // nav2_costmap_2d::Costmap2D * costmap,
55  // std::vector<float> & angles);
56 
62  void setFootprint(
63  const nav2_costmap_2d::Footprint & footprint,
64  const bool & radius,
65  const double & possible_inscribed_cost);
66 
75  bool inCollision(
76  const float & x,
77  const float & y,
78  const float & theta,
79  const bool & traverse_unknown);
80 
87  bool inCollision(
88  const unsigned int & i,
89  const bool & traverse_unknown);
90 
95  float getCost();
96 
101  std::vector<float> & getPrecomputedAngles()
102  {
103  return angles_;
104  }
105 
106 private:
114  bool outsideRange(const unsigned int & max, const float & value);
115 
116 protected:
117  std::vector<nav2_costmap_2d::Footprint> oriented_footprints_;
118  nav2_costmap_2d::Footprint unoriented_footprint_;
119  double footprint_cost_;
120  bool footprint_is_radius_;
121  std::vector<float> angles_;
122  double possible_inscribed_cost_{-1};
123  rclcpp::Logger logger_{rclcpp::get_logger("SmacPlannerCollisionChecker")};
124  rclcpp::Clock::SharedPtr clock_;
125 };
126 
127 } // namespace nav2_smac_planner
128 
129 #endif // NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
A 2D costmap provides a mapping between points in the world and their associated "costs".
Definition: costmap_2d.hpp:68
Checker for collision with a footprint on a costmap.
A costmap grid collision checker.
bool inCollision(const float &x, const float &y, const float &theta, const bool &traverse_unknown)
Check if in collision with costmap and footprint at pose.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_inscribed_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
std::vector< float > & getPrecomputedAngles()
Get the angles of the precomputed footprint orientations.
GridCollisionChecker(nav2_costmap_2d::Costmap2D *costmap, unsigned int num_quantizations, rclcpp_lifecycle::LifecycleNode::SharedPtr node)
A constructor for nav2_smac_planner::GridCollisionChecker for use when regular bin intervals are appr...
float getCost()
Get cost at footprint pose in costmap.