45 void BaseObstacleCritic::onInit()
47 critic_nh_.param(
"sum_scores", sum_scores_,
false);
50 double BaseObstacleCritic::scoreTrajectory(
const dwb_msgs::Trajectory2D& traj)
54 for (
unsigned int i = 0; i < traj.poses.size(); ++i)
56 double pose_score = scorePose(costmap, traj.poses[i]);
58 score =
static_cast<double>(sum_scores_) * score + pose_score;
63 double BaseObstacleCritic::scorePose(
const nav_core2::Costmap& costmap,
const geometry_msgs::Pose2D& pose)
65 unsigned int cell_x, cell_y;
68 unsigned char cost = costmap(cell_x, cell_y);
69 if (!isValidCost(cost))
74 bool BaseObstacleCritic::isValidCost(
const unsigned char cost)
76 return cost != costmap_->LETHAL_OBSTACLE &&
77 cost != costmap_->INSCRIBED_INFLATED_OBSTACLE &&
78 cost != costmap_->NO_INFORMATION;
81 void BaseObstacleCritic::addCriticVisualization(sensor_msgs::PointCloud& pc)
83 sensor_msgs::ChannelFloat32 grid_scores;
84 grid_scores.name = name_;
87 unsigned int size_x = costmap.getWidth();
88 unsigned int size_y = costmap.getHeight();
89 grid_scores.values.resize(size_x * size_y);
91 for (
unsigned int cy = 0; cy < size_y; cy++)
93 for (
unsigned int cx = 0; cx < size_x; cx++)
95 grid_scores.values[i] = costmap(cx, cy);
99 pc.channels.push_back(grid_scores);
nav_core2::BasicCostmap costmap
Uses costmap to assign negative costs if a circular robot would collide at any point of the trajector...
#define PLUGINLIB_EXPORT_CLASS(class_type, base_class_type)
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)