23 #include "tf2/utils.hpp"
25 #include "nav2_costmap_2d/costmap_topic_collision_checker.hpp"
27 #include "nav2_costmap_2d/cost_values.hpp"
28 #include "nav2_costmap_2d/exceptions.hpp"
29 #include "nav2_costmap_2d/footprint.hpp"
30 #include "nav2_util/line_iterator.hpp"
32 using namespace std::chrono_literals;
37 CostmapTopicCollisionChecker::CostmapTopicCollisionChecker(
42 costmap_sub_(costmap_sub),
43 footprint_sub_(&footprint_sub),
44 collision_checker_(nullptr)
49 std::string footprint_string,
52 costmap_sub_(costmap_sub),
53 collision_checker_(nullptr)
61 const geometry_msgs::msg::Pose & pose,
62 bool fetch_costmap_and_footprint)
65 if (
scorePose(pose, fetch_costmap_and_footprint) >= LETHAL_OBSTACLE) {
70 RCLCPP_ERROR(rclcpp::get_logger(name_),
"%s", e.what());
73 RCLCPP_ERROR(rclcpp::get_logger(name_),
"%s", e.what());
76 RCLCPP_ERROR(rclcpp::get_logger(name_),
"Failed to check pose score!");
82 const geometry_msgs::msg::Pose & pose,
83 bool fetch_costmap_and_footprint)
85 if (fetch_costmap_and_footprint) {
87 collision_checker_.setCostmap(costmap_sub_.
getCostmap());
88 }
catch (
const std::runtime_error & e) {
93 unsigned int cell_x, cell_y;
94 if (!collision_checker_.worldToMap(pose.position.x, pose.position.y, cell_x, cell_y)) {
95 RCLCPP_DEBUG(rclcpp::get_logger(name_),
"Map Cell: [%d, %d]", cell_x, cell_y);
99 return collision_checker_.footprintCost(
getFootprint(pose, fetch_costmap_and_footprint));
103 const geometry_msgs::msg::Pose & pose,
104 bool fetch_latest_footprint)
106 if (fetch_latest_footprint) {
107 std_msgs::msg::Header header;
117 double x = pose.position.x;
118 double y = pose.position.y;
119 double theta = tf2::getYaw(pose.orientation);
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()
Get current costmap.
double scorePose(const geometry_msgs::msg::Pose &pose, bool fetch_costmap_and_footprint=true)
Returns the obstacle footprint score for a particular pose.
Footprint getFootprint(const geometry_msgs::msg::Pose &pose, bool fetch_latest_footprint=true)
Get a footprint at a set pose.
bool isCollisionFree(const geometry_msgs::msg::Pose &pose, bool fetch_costmap_and_footprint=true)
Returns if a pose is collision free.
CostmapTopicCollisionChecker(CostmapSubscriber &costmap_sub, FootprintSubscriber &footprint_sub, std::string name="collision_checker")
A constructor.
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)
bool makeFootprintFromString(const std::string &footprint_string, std::vector< geometry_msgs::msg::Point > &footprint)
Make the footprint from the given string.