23 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
25 #include "nav2_costmap_2d/cost_values.hpp"
26 #include "nav2_costmap_2d/exceptions.hpp"
27 #include "nav2_costmap_2d/footprint.hpp"
28 #include "nav2_util/line_iterator.hpp"
30 using namespace std::chrono_literals;
35 CostmapTopicCollisionChecker::CostmapTopicCollisionChecker(
40 costmap_sub_(costmap_sub),
41 footprint_sub_(footprint_sub),
42 collision_checker_(nullptr)
46 const geometry_msgs::msg::Pose2D & pose,
47 bool fetch_costmap_and_footprint)
50 if (
scorePose(pose, fetch_costmap_and_footprint) >= LETHAL_OBSTACLE) {
55 RCLCPP_ERROR(rclcpp::get_logger(name_),
"%s", e.what());
58 RCLCPP_ERROR(rclcpp::get_logger(name_),
"%s", e.what());
61 RCLCPP_ERROR(rclcpp::get_logger(name_),
"Failed to check pose score!");
67 const geometry_msgs::msg::Pose2D & pose,
68 bool fetch_costmap_and_footprint)
70 if (fetch_costmap_and_footprint) {
72 collision_checker_.setCostmap(costmap_sub_.
getCostmap());
73 }
catch (
const std::runtime_error & e) {
78 unsigned int cell_x, cell_y;
79 if (!collision_checker_.worldToMap(pose.x, pose.y, cell_x, cell_y)) {
80 RCLCPP_DEBUG(rclcpp::get_logger(name_),
"Map Cell: [%d, %d]", cell_x, cell_y);
84 return collision_checker_.footprintCost(
getFootprint(pose, fetch_costmap_and_footprint));
88 const geometry_msgs::msg::Pose2D & pose,
89 bool fetch_latest_footprint)
91 if (fetch_latest_footprint) {
92 std_msgs::msg::Header header;
Exceptions thrown if collision checker determines a pose is in collision with the environment costmap...
Subscribes to the costmap via a ros topic.
std::shared_ptr< Costmap2D > getCostmap()
A Get the costmap from topic.
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.
bool isCollisionFree(const geometry_msgs::msg::Pose2D &pose, bool fetch_costmap_and_footprint=true)
Returns if a pose is collision free.
Thrown when CollisionChecker encounters a fatal error.
void transformFootprint(double x, double y, double theta, const std::vector< geometry_msgs::msg::Point > &footprint_spec, std::vector< geometry_msgs::msg::Point > &oriented_footprint)
Given a pose and base footprint, build the oriented footprint of the robot (list of Points)