35 #include "dwb_critics/path_dist.hpp"
37 #include "pluginlib/class_list_macros.hpp"
38 #include "nav_2d_utils/path_ops.hpp"
39 #include "nav2_costmap_2d/cost_values.hpp"
44 const geometry_msgs::msg::Pose2D &,
const nav_2d_msgs::msg::Twist2D &,
45 const geometry_msgs::msg::Pose2D &,
46 const nav_2d_msgs::msg::Path2D & global_plan)
49 bool started_path =
false;
51 nav_2d_msgs::msg::Path2D adjusted_global_plan =
52 nav_2d_utils::adjustPlanResolution(global_plan, costmap_->
getResolution());
54 if (adjusted_global_plan.poses.size() != global_plan.poses.size()) {
57 "PathDistCritic"),
"Adjusted global plan resolution, added %zu points",
58 adjusted_global_plan.poses.size() - global_plan.poses.size());
63 for (i = 0; i < adjusted_global_plan.poses.size(); ++i) {
64 double g_x = adjusted_global_plan.poses[i].x;
65 double g_y = adjusted_global_plan.poses[i].y;
66 unsigned int map_x, map_y;
69 map_y) && costmap_->
getCost(map_x, map_y) != nav2_costmap_2d::NO_INFORMATION)
71 int index = costmap_->
getIndex(map_x, map_y);
72 cell_values_[index] = 0.0;
73 queue_->enqueueCell(map_x, map_y);
75 }
else if (started_path) {
81 rclcpp::get_logger(
"PathDistCritic"),
82 "None of the %d first of %zu (%zu) points of the global plan were in "
83 "the local costmap and free",
84 i, adjusted_global_plan.poses.size(), global_plan.poses.size());
Evaluates a Trajectory2D to produce a score.
void reset() override
Clear the queueDWB_CRITICS_MAP_GRID_He and set cell_values_ to the appropriate number of unreachableC...
void propagateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents.
Scores trajectories based on how far from the global path they end up.
bool prepare(const geometry_msgs::msg::Pose2D &pose, const nav_2d_msgs::msg::Twist2D &vel, const geometry_msgs::msg::Pose2D &goal, const nav_2d_msgs::msg::Path2D &global_plan) override
Prior to evaluating any trajectories, look at contextual information constant across all trajectories...
unsigned int getIndex(unsigned int mx, unsigned int my) const
Given two map coordinates... compute the associated index.
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.
double getResolution() const
Accessor for the resolution of the costmap.