38 #include "dwb_critics/base_obstacle.hpp"
39 #include "dwb_core/exceptions.hpp"
40 #include "pluginlib/class_list_macros.hpp"
41 #include "nav2_costmap_2d/cost_values.hpp"
42 #include "nav2_util/node_utils.hpp"
49 void BaseObstacleCritic::onInit()
51 costmap_ = costmap_ros_->getCostmap();
53 auto node = node_.lock();
55 throw std::runtime_error{
"Failed to lock node"};
58 nav2_util::declare_parameter_if_not_declared(
60 dwb_plugin_name_ +
"." + name_ +
".sum_scores", rclcpp::ParameterValue(
false));
61 node->get_parameter(dwb_plugin_name_ +
"." + name_ +
".sum_scores", sum_scores_);
67 for (
unsigned int i = 0; i < traj.poses.size(); ++i) {
68 double pose_score =
scorePose(traj.poses[i]);
71 score =
static_cast<double>(sum_scores_) * score + pose_score;
78 unsigned int cell_x, cell_y;
79 if (!costmap_->
worldToMap(pose.x, pose.y, cell_x, cell_y)) {
81 IllegalTrajectoryException(name_,
"Trajectory Goes Off Grid.");
83 unsigned char cost = costmap_->
getCost(cell_x, cell_y);
86 IllegalTrajectoryException(name_,
"Trajectory Hits Obstacle.");
93 return cost != nav2_costmap_2d::LETHAL_OBSTACLE &&
94 cost != nav2_costmap_2d::INSCRIBED_INFLATED_OBSTACLE &&
95 cost != nav2_costmap_2d::NO_INFORMATION;
99 std::vector<std::pair<std::string, std::vector<float>>> & cost_channels)
101 std::pair<std::string, std::vector<float>> grid_scores;
102 grid_scores.first = name_;
106 grid_scores.second.resize(size_x * size_y);
108 for (
unsigned int cy = 0; cy < size_y; cy++) {
109 for (
unsigned int cx = 0; cx < size_x; cx++) {
110 grid_scores.second[i] = costmap_->
getCost(cx, cy);
114 cost_channels.push_back(grid_scores);
Evaluates a Trajectory2D to produce a score.
Uses costmap 2d to assign negative costs if a circular robot would collide at any point of the trajec...
double scoreTrajectory(const dwb_msgs::msg::Trajectory2D &traj) override
Return a raw score for the given trajectory.
virtual double scorePose(const geometry_msgs::msg::Pose2D &pose)
Return the obstacle score for a particular pose.
void addCriticVisualization(std::vector< std::pair< std::string, std::vector< float >>> &cost_channels) override
Add information to the given pointcloud for debugging costmap-grid based scores.
virtual bool isValidCost(const unsigned char cost)
Check to see whether a given cell cost is valid for driving through.
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.
unsigned int getSizeInCellsX() const
Accessor for the x size of the costmap in cells.
unsigned int getSizeInCellsY() const
Accessor for the y size of the costmap in cells.