Class GridCollisionChecker

Inheritance Relationships

Base Type

  • public nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * >

Class Documentation

class GridCollisionChecker : public nav2_costmap_2d::FootprintCollisionChecker<nav2_costmap_2d::Costmap2D*>

A costmap grid collision checker.

Public Functions

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 appropriate.

Parameters:
  • costmap – The costmap to collision check against

  • num_quantizations – The number of quantizations to precompute footprint

  • node – Node to extract clock and logger from orientations for to speed up collision checking

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 appropriate.

Set the footprint to use with collision checker

Parameters:
  • costmap – The costmap to collision check against

  • angles – The vector of possible angle bins to precompute for orientations for to speed up collision checking, in radians

  • footprint – The footprint to collision check against

  • radius – Whether or not the footprint is a circle and use radius collision checking

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.

Parameters:
  • x – X coordinate of pose to check against

  • y – Y coordinate of pose to check against

  • theta – Angle bin number of pose to check against (NOT radians)

  • traverse_unknown – Whether or not to traverse in unknown space

Returns:

boolean if in collision or not.

bool inCollision(const unsigned int &i, const bool &traverse_unknown)

Check if in collision with costmap and footprint at pose.

Parameters:
  • i – Index to search collision status of

  • traverse_unknown – Whether or not to traverse in unknown space

Returns:

boolean if in collision or not.

float getCost()

Get cost at footprint pose in costmap.

Returns:

the cost at the pose in costmap

inline std::vector<float> &getPrecomputedAngles()

Get the angles of the precomputed footprint orientations.

Returns:

the ordered vector of angles corresponding to footprints

inline std::shared_ptr<nav2_costmap_2d::Costmap2DROS> getCostmapROS()

Get costmap ros object for inflation layer params.

Returns:

Costmap ros

Protected Attributes

std::shared_ptr<nav2_costmap_2d::Costmap2DROS> costmap_ros_
std::vector<nav2_costmap_2d::Footprint> oriented_footprints_
nav2_costmap_2d::Footprint unoriented_footprint_
float footprint_cost_
bool footprint_is_radius_
std::vector<float> angles_
float possible_collision_cost_ = {-1}
rclcpp::Logger logger_ = {rclcpp::get_logger("SmacPlannerCollisionChecker")}
rclcpp::Clock::SharedPtr clock_