35 #include "dwb_critics/obstacle_footprint.hpp"
38 #include "dwb_critics/line_iterator.hpp"
39 #include "dwb_core/exceptions.hpp"
40 #include "pluginlib/class_list_macros.hpp"
41 #include "nav2_costmap_2d/cost_values.hpp"
47 Footprint getOrientedFootprint(
48 const geometry_msgs::msg::Pose & pose,
49 const Footprint & footprint_spec)
51 std::vector<geometry_msgs::msg::Point> oriented_footprint;
52 oriented_footprint.resize(footprint_spec.size());
53 double theta = tf2::getYaw(pose.orientation);
54 double cos_th = cos(theta);
55 double sin_th = sin(theta);
56 for (
unsigned int i = 0; i < footprint_spec.size(); ++i) {
57 geometry_msgs::msg::Point & new_pt = oriented_footprint[i];
58 new_pt.x = pose.position.x + footprint_spec[i].x * cos_th - footprint_spec[i].y * sin_th;
59 new_pt.y = pose.position.y + footprint_spec[i].x * sin_th + footprint_spec[i].y * cos_th;
61 return oriented_footprint;
65 const geometry_msgs::msg::Pose &,
const nav_2d_msgs::msg::Twist2D &,
66 const geometry_msgs::msg::Pose &,
const nav_msgs::msg::Path &)
68 footprint_spec_ = costmap_ros_->getRobotFootprint();
69 if (footprint_spec_.size() == 0) {
71 rclcpp::get_logger(
"ObstacleFootprintCritic"),
72 "Footprint spec is empty, maybe missing call to setFootprint?");
80 unsigned int cell_x, cell_y;
81 if (!costmap_->
worldToMap(pose.position.x, pose.position.y, cell_x, cell_y)) {
83 IllegalTrajectoryException(name_,
"Trajectory Goes Off Grid.");
85 return scorePose(pose, getOrientedFootprint(pose, footprint_spec_));
89 const geometry_msgs::msg::Pose &,
90 const Footprint & footprint)
93 unsigned int x0, x1, y0, y1;
94 double line_cost = 0.0;
95 double footprint_cost = 0.0;
98 for (
unsigned int i = 0; i < footprint.size() - 1; ++i) {
100 if (!costmap_->
worldToMap(footprint[i].x, footprint[i].y, x0, y0)) {
102 IllegalTrajectoryException(name_,
"Footprint Goes Off Grid.");
106 if (!costmap_->
worldToMap(footprint[i + 1].x, footprint[i + 1].y, x1, y1)) {
108 IllegalTrajectoryException(name_,
"Footprint Goes Off Grid.");
111 line_cost =
lineCost(x0, x1, y0, y1);
112 footprint_cost = std::max(line_cost, footprint_cost);
117 if (!costmap_->
worldToMap(footprint.back().x, footprint.back().y, x0, y0)) {
119 IllegalTrajectoryException(name_,
"Footprint Goes Off Grid.");
123 if (!costmap_->
worldToMap(footprint.front().x, footprint.front().y, x1, y1)) {
125 IllegalTrajectoryException(name_,
"Footprint Goes Off Grid.");
128 line_cost =
lineCost(x0, x1, y0, y1);
129 footprint_cost = std::max(line_cost, footprint_cost);
132 return footprint_cost;
137 double line_cost = 0.0;
138 double point_cost = -1.0;
140 for (
LineIterator line(x0, y0, x1, y1); line.isValid(); line.advance()) {
141 point_cost =
pointCost(line.getX(), line.getY());
143 if (line_cost < point_cost) {
144 line_cost = point_cost;
153 unsigned char cost = costmap_->
getCost(x, y);
155 if (cost == nav2_costmap_2d::LETHAL_OBSTACLE) {
157 IllegalTrajectoryException(name_,
"Trajectory Hits Obstacle.");
158 }
else if (cost == nav2_costmap_2d::NO_INFORMATION) {
160 IllegalTrajectoryException(name_,
"Trajectory Hits Unknown Region.");
Evaluates a Trajectory2D to produce a score.
unsigned char getCost(unsigned int mx, unsigned int my) const
Get the cost of a cell in the costmap.
bool worldToMap(double wx, double wy, unsigned int &mx, unsigned int &my) const
Convert from world coordinates to map coordinates.