|
Nav2 Navigation Stack - kilted
kilted
ROS 2 Navigation Stack
|
Using a costmap via a ros topic, this object is used to find if robot poses are in collision with the costmap environment. More...
#include <nav2_costmap_2d/include/nav2_costmap_2d/costmap_topic_collision_checker.hpp>

Public Member Functions | |
| CostmapTopicCollisionChecker (CostmapSubscriber &costmap_sub, FootprintSubscriber &footprint_sub, std::string name="collision_checker") | |
| A constructor. | |
| CostmapTopicCollisionChecker (CostmapSubscriber &costmap_sub, std::string footprint_string, std::string name="collision_checker") | |
| Alternative constructor with a footprint string instead of a subscriber. It needs to be defined relative to the robot frame. | |
| ~CostmapTopicCollisionChecker ()=default | |
| A destructor. | |
| double | scorePose (const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true) |
| Returns the obstacle footprint score for a particular pose. More... | |
| bool | isCollisionFree (const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true) |
| Returns if a pose is collision free. More... | |
Protected Member Functions | |
| Footprint | getFootprint (const geometry_msgs::msg::Pose2D &pose, bool fetch_latest_footprint=true) |
| Get a footprint at a set pose. More... | |
Protected Attributes | |
| std::string | name_ |
| CostmapSubscriber & | costmap_sub_ |
| FootprintSubscriber * | footprint_sub_ = nullptr |
| FootprintCollisionChecker< std::shared_ptr< Costmap2D > > | collision_checker_ |
| rclcpp::Clock::SharedPtr | clock_ |
| Footprint | footprint_ |
| std::string | footprint_string_ |
Using a costmap via a ros topic, this object is used to find if robot poses are in collision with the costmap environment.
Definition at line 40 of file costmap_topic_collision_checker.hpp.
|
protected |
Get a footprint at a set pose.
| pose | Pose to get footprint at |
| fetch_latest_footprint | Defaults to true. When checking with multiple poses at once, footprint should be fetched in the first check but fetching can be skipped in consequent checks for speedup |
Definition at line 100 of file costmap_topic_collision_checker.cpp.
References nav2_costmap_2d::FootprintSubscriber::getFootprintInRobotFrame(), and nav2_costmap_2d::transformFootprint().
Referenced by scorePose().


| bool nav2_costmap_2d::CostmapTopicCollisionChecker::isCollisionFree | ( | const geometry_msgs::msg::Pose2D & | pose, |
| bool | fetch_costmap_and_footprint = true |
||
| ) |
Returns if a pose is collision free.
| pose | Pose to check collision at |
| fetch_costmap_and_footprint | Defaults to true. When checking with multiple poses at once, data should be fetched in the first check but fetching can be skipped in consequent checks for speedup |
Definition at line 58 of file costmap_topic_collision_checker.cpp.
References scorePose().

| double nav2_costmap_2d::CostmapTopicCollisionChecker::scorePose | ( | const geometry_msgs::msg::Pose2D & | pose, |
| bool | fetch_costmap_and_footprint = true |
||
| ) |
Returns the obstacle footprint score for a particular pose.
| pose | Pose to get score at |
| fetch_costmap_and_footprint | Defaults to true. When checking with multiple poses at once, data should be fetched in the first check but fetching can be skipped in consequent checks for speedup |
Definition at line 79 of file costmap_topic_collision_checker.cpp.
References nav2_costmap_2d::CostmapSubscriber::getCostmap(), and getFootprint().
Referenced by isCollisionFree().

