Nav2 Navigation Stack - kilted  kilted
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 
15 #include <memory>
16 #include <vector>
17 
18 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
19 #include "nav2_costmap_2d/costmap_2d_ros.hpp"
20 #include "nav2_smac_planner/constants.hpp"
21 #include "rclcpp_lifecycle/lifecycle_node.hpp"
22 
23 #ifndef NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
24 #define NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
25 
26 namespace nav2_smac_planner
27 {
28 
34  : public nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D *>
35 {
36 public:
46  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap,
47  unsigned int num_quantizations,
48  rclcpp_lifecycle::LifecycleNode::SharedPtr node);
49 
57  // GridCollisionChecker(
58  // nav2_costmap_2d::Costmap2D * costmap,
59  // std::vector<float> & angles);
60 
66  void setFootprint(
67  const nav2_costmap_2d::Footprint & footprint,
68  const bool & radius,
69  const double & possible_collision_cost);
70 
79  bool inCollision(
80  const float & x,
81  const float & y,
82  const float & theta,
83  const bool & traverse_unknown);
84 
91  bool inCollision(
92  const unsigned int & i,
93  const bool & traverse_unknown);
94 
99  float getCost();
100 
105  std::vector<float> & getPrecomputedAngles()
106  {
107  return angles_;
108  }
109 
114  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> getCostmapROS() {return costmap_ros_;}
115 
123  bool outsideRange(const unsigned int & max, const float & value);
124 
125 protected:
126  std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_;
127  std::vector<nav2_costmap_2d::Footprint> oriented_footprints_;
128  nav2_costmap_2d::Footprint unoriented_footprint_;
129  float center_cost_;
130  bool footprint_is_radius_{false};
131  std::vector<float> angles_;
132  float possible_collision_cost_{-1};
133  rclcpp::Logger logger_{rclcpp::get_logger("SmacPlannerCollisionChecker")};
134  rclcpp::Clock::SharedPtr clock_;
135 };
136 
137 } // namespace nav2_smac_planner
138 
139 #endif // NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
Checker for collision with a footprint on a costmap.
A costmap grid collision checker.
void setFootprint(const nav2_costmap_2d::Footprint &footprint, const bool &radius, const double &possible_collision_cost)
A constructor for nav2_smac_planner::GridCollisionChecker for use when irregular bin intervals are ap...
GridCollisionChecker(std::shared_ptr< nav2_costmap_2d::Costmap2DROS > 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...
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.
std::shared_ptr< nav2_costmap_2d::Costmap2DROS > getCostmapROS()
Get costmap ros object for inflation layer params.
bool outsideRange(const unsigned int &max, const float &value)
Check if value outside the range.
std::vector< float > & getPrecomputedAngles()
Get the angles of the precomputed footprint orientations.
float getCost()
Get cost at footprint pose in costmap.