17 #ifndef NAV2_COSTMAP_2D__COSTMAP_TOPIC_COLLISION_CHECKER_HPP_
18 #define NAV2_COSTMAP_2D__COSTMAP_TOPIC_COLLISION_CHECKER_HPP_
25 #include "rclcpp/rclcpp.hpp"
26 #include "geometry_msgs/msg/pose_stamped.hpp"
27 #include "geometry_msgs/msg/pose2_d.hpp"
28 #include "nav2_costmap_2d/costmap_2d.hpp"
29 #include "nav2_costmap_2d/footprint_collision_checker.hpp"
30 #include "nav2_costmap_2d/costmap_subscriber.hpp"
31 #include "nav2_costmap_2d/footprint_subscriber.hpp"
49 std::string name =
"collision_checker");
57 std::string footprint_string,
58 std::string name =
"collision_checker");
73 const geometry_msgs::msg::Pose2D & pose,
74 bool fetch_costmap_and_footprint =
true);
84 const geometry_msgs::msg::Pose2D & pose,
85 bool fetch_costmap_and_footprint =
true);
96 const geometry_msgs::msg::Pose2D & pose,
97 bool fetch_latest_footprint =
true);
104 rclcpp::Clock::SharedPtr clock_;
105 Footprint footprint_;
106 std::string footprint_string_;
Subscribes to the costmap via a ros topic.
Using a costmap via a ros topic, this object is used to find if robot poses are in collision with the...
Footprint getFootprint(const geometry_msgs::msg::Pose2D &pose, bool fetch_latest_footprint=true)
Get a footprint at a set pose.
double scorePose(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns the obstacle footprint score for a particular pose.
CostmapTopicCollisionChecker(CostmapSubscriber &costmap_sub, FootprintSubscriber &footprint_sub, std::string name="collision_checker")
A constructor.
bool isCollisionFree(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns if a pose is collision free.
~CostmapTopicCollisionChecker()=default
A destructor.