Nav2 Navigation Stack - humble  humble
ROS 2 Navigation Stack
Public Member Functions | Protected Attributes | List of all members
nav2_smac_planner::GridCollisionChecker Class Reference

A costmap grid collision checker. More...

#include <nav2_smac_planner/include/nav2_smac_planner/collision_checker.hpp>

Inheritance diagram for nav2_smac_planner::GridCollisionChecker:
Inheritance graph
[legend]
Collaboration diagram for nav2_smac_planner::GridCollisionChecker:
Collaboration graph
[legend]

Public Member Functions

 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 appropriate. More...
 
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 appropriate. More...
 
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. More...
 
bool inCollision (const unsigned int &i, const bool &traverse_unknown)
 Check if in collision with costmap and footprint at pose. More...
 
float getCost ()
 Get cost at footprint pose in costmap. More...
 
std::vector< float > & getPrecomputedAngles ()
 Get the angles of the precomputed footprint orientations. More...
 
- Public Member Functions inherited from nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * >
 FootprintCollisionChecker ()
 A constructor.
 
 FootprintCollisionChecker (nav2_costmap_2d::Costmap2D * costmap)
 A constructor.
 
double footprintCost (const Footprint footprint)
 Find the footprint cost in oriented footprint.
 
double footprintCostAtPose (double x, double y, double theta, const Footprint footprint)
 Find the footprint cost a a post with an unoriented footprint.
 
double lineCost (int x0, int x1, int y0, int y1) const
 Get the cost for a line segment.
 
bool worldToMap (double wx, double wy, unsigned int &mx, unsigned int &my)
 Get the map coordinates from a world point.
 
double pointCost (int x, int y) const
 Get the cost of a point.
 
void setCostmap (nav2_costmap_2d::Costmap2D * costmap)
 Set the current costmap object to use for collision detection.
 
nav2_costmap_2d::Costmap2DgetCostmap ()
 Get the current costmap object.
 

Protected Attributes

std::vector< nav2_costmap_2d::Footprint > oriented_footprints_
 
nav2_costmap_2d::Footprint unoriented_footprint_
 
double footprint_cost_
 
bool footprint_is_radius_
 
std::vector< float > angles_
 
double possible_inscribed_cost_ {-1}
 
rclcpp::Logger logger_ {rclcpp::get_logger("SmacPlannerCollisionChecker")}
 
rclcpp::Clock::SharedPtr clock_
 
- Protected Attributes inherited from nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * >
nav2_costmap_2d::Costmap2Dcostmap_
 

Detailed Description

A costmap grid collision checker.

Definition at line 29 of file collision_checker.hpp.

Constructor & Destructor Documentation

◆ GridCollisionChecker()

nav2_smac_planner::GridCollisionChecker::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 appropriate.

Parameters
costmapThe costmap to collision check against
num_quantizationsThe number of quantizations to precompute footprint
nodeNode to extract clock and logger from orientations for to speed up collision checking

Definition at line 20 of file collision_checker.cpp.

Member Function Documentation

◆ getCost()

float nav2_smac_planner::GridCollisionChecker::getCost ( )

Get cost at footprint pose in costmap.

Returns
the cost at the pose in costmap

Definition at line 185 of file collision_checker.cpp.

Referenced by nav2_smac_planner::Node2D::isNodeValid(), nav2_smac_planner::NodeHybrid::isNodeValid(), and nav2_smac_planner::NodeLattice::isNodeValid().

Here is the caller graph for this function:

◆ getPrecomputedAngles()

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

Get the angles of the precomputed footprint orientations.

Returns
the ordered vector of angles corresponding to footprints

Definition at line 101 of file collision_checker.hpp.

Referenced by nav2_smac_planner::NodeLattice::isNodeValid().

Here is the caller graph for this function:

◆ inCollision() [1/2]

bool nav2_smac_planner::GridCollisionChecker::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
xX coordinate of pose to check against
yY coordinate of pose to check against
thetaAngle bin number of pose to check against (NOT radians)
traverse_unknownWhether or not to traverse in unknown space
Returns
boolean if in collision or not.

Definition at line 90 of file collision_checker.cpp.

References nav2_costmap_2d::FootprintCollisionChecker< nav2_costmap_2d::Costmap2D * >::footprintCost(), nav2_costmap_2d::Costmap2D::getCost(), nav2_costmap_2d::Costmap2D::getSizeInCellsX(), nav2_costmap_2d::Costmap2D::getSizeInCellsY(), and nav2_costmap_2d::Costmap2D::mapToWorld().

Referenced by nav2_smac_planner::Node2D::isNodeValid(), nav2_smac_planner::NodeHybrid::isNodeValid(), and nav2_smac_planner::NodeLattice::isNodeValid().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ inCollision() [2/2]

bool nav2_smac_planner::GridCollisionChecker::inCollision ( const unsigned int &  i,
const bool &  traverse_unknown 
)

Check if in collision with costmap and footprint at pose.

Parameters
iIndex to search collision status of
traverse_unknownWhether or not to traverse in unknown space
Returns
boolean if in collision or not.

Definition at line 172 of file collision_checker.cpp.

References nav2_costmap_2d::Costmap2D::getCost().

Here is the call graph for this function:

◆ setFootprint()

void nav2_smac_planner::GridCollisionChecker::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 appropriate.

Parameters
costmapThe costmap to collision check against
anglesThe vector of possible angle bins to precompute for orientations for to speed up collision checking, in radians

Set the footprint to use with collision checker

Parameters
footprintThe footprint to collision check against
radiusWhether or not the footprint is a circle and use radius collision checking

Definition at line 47 of file collision_checker.cpp.

Referenced by nav2_smac_planner::SmacPlannerHybrid::configure(), nav2_smac_planner::SmacPlannerHybrid::createPlan(), nav2_smac_planner::SmacPlannerLattice::createPlan(), and nav2_smac_planner::SmacPlannerHybrid::dynamicParametersCallback().

Here is the caller graph for this function:

The documentation for this class was generated from the following files: