67 std::string aggro_str;
69 std::transform(aggro_str.begin(), aggro_str.end(), aggro_str.begin(), ::tolower);
70 if (aggro_str ==
"last")
74 else if (aggro_str ==
"sum")
78 else if (aggro_str ==
"product")
84 ROS_ERROR_NAMED(
"MapGridCritic",
"aggregation_type parameter \"%s\" invalid. Using Last.", aggro_str.c_str());
112 while (!
queue_->isEmpty())
116 std::abs(static_cast<int>(cell.
src_x_) - static_cast<int>(cell.
x_))
117 + std::abs(static_cast<int>(cell.
src_y_) - static_cast<int>(cell.
y_)));
124 unsigned int start_index = 0;
131 start_index = traj.poses.size() - 1;
135 for (
unsigned int i = start_index; i < traj.poses.size(); ++i)
172 unsigned int cell_x, cell_y;
183 sensor_msgs::ChannelFloat32 grid_scores;
184 grid_scores.name =
name_;
187 unsigned int size_x = costmap.getWidth();
188 unsigned int size_y = costmap.getHeight();
189 grid_scores.values.resize(size_x * size_y);
191 for (
unsigned int cy = 0; cy < size_y; cy++)
193 for (
unsigned int cx = 0; cx < size_x; cx++)
195 grid_scores.values[i] =
getScore(cx, cy);
199 pc.channels.push_back(grid_scores);
void reset() override
Clear the queue and set cell_values_ to the appropriate number of unreachableCellScore.
static const unsigned char INSCRIBED_INFLATED_OBSTACLE
bool validCellToQueue(const costmap_queue::CellData &cell) override
nav_core2::BasicCostmap costmap
virtual double scorePose(const geometry_msgs::Pose2D &pose)
Retrieve the score for a single pose.
void propogateManhattanDistances()
Go through the queue and set the cells to the Manhattan distance from their parents.
void setAsObstacle(unsigned int x, unsigned int y)
Sets the score of a particular cell to the obstacle cost.
static const unsigned char NO_INFORMATION
void setDefaultValue(const T new_value)
ScoreAggregationType aggregationType_
void addCriticVisualization(sensor_msgs::PointCloud &pc) override
ros::NodeHandle critic_nh_
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
void setInfo(const NavGridInfo &new_info) override
void setValue(const unsigned int x, const unsigned int y, const T &value) override
double getScore(unsigned int x, unsigned int y)
Retrieve the score for a particular cell of the costmap.
nav_core2::Costmap & costmap_
NavGridInfo getInfo() const
#define ROS_ERROR_NAMED(name,...)
static const unsigned char LETHAL_OBSTACLE
std::shared_ptr< MapGridQueue > queue_
nav_grid::VectorNavGrid< double > cell_values_
double scoreTrajectory(const dwb_msgs::Trajectory2D &traj) override
double unreachable_score_
Special cell_values.
bool worldToGridBounded(const NavGridInfo &info, double wx, double wy, unsigned int &mx, unsigned int &my)