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"
23 #ifndef NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
24 #define NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
26 namespace nav2_smac_planner
46 std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap,
47 unsigned int num_quantizations,
48 rclcpp_lifecycle::LifecycleNode::SharedPtr node);
67 const nav2_costmap_2d::Footprint & footprint,
69 const double & possible_collision_cost);
83 const bool & traverse_unknown);
92 const unsigned int & i,
93 const bool & traverse_unknown);
114 std::shared_ptr<nav2_costmap_2d::Costmap2DROS>
getCostmapROS() {
return costmap_ros_;}
123 bool outsideRange(
const unsigned int & max,
const float & value);
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_;
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_;
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.