54 for (
unsigned int i = 0; i < traj.poses.size(); ++i)
58 score =
static_cast<double>(
sum_scores_) * score + pose_score;
65 unsigned int cell_x, cell_y;
68 unsigned char cost =
costmap(cell_x, cell_y);
76 return cost !=
costmap_->LETHAL_OBSTACLE &&
77 cost !=
costmap_->INSCRIBED_INFLATED_OBSTACLE &&
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);