15 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
16 #include "nav2_smac_planner/constants.hpp"
17 #include "rclcpp_lifecycle/lifecycle_node.hpp"
19 #ifndef NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
20 #define NAV2_SMAC_PLANNER__COLLISION_CHECKER_HPP_
22 namespace nav2_smac_planner
43 unsigned int num_quantizations,
44 rclcpp_lifecycle::LifecycleNode::SharedPtr node);
63 const nav2_costmap_2d::Footprint & footprint,
65 const double & possible_inscribed_cost);
79 const bool & traverse_unknown);
88 const unsigned int & i,
89 const bool & traverse_unknown);
114 bool outsideRange(
const unsigned int & max,
const float & value);
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_;
A 2D costmap provides a mapping between points in the world and their associated "costs".
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.