71 std::string map_topic;
72 nh.param(
"map_topic", map_topic, std::string(
"map"));
78 int temp_lethal_threshold, temp_unknown_cost_value;
79 nh.param(
"lethal_cost_threshold", temp_lethal_threshold,
int(100));
80 nh.param(
"unknown_cost_value", temp_unknown_cost_value,
int(-1));
111 dsrv_ =
new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
112 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb = boost::bind(
114 dsrv_->setCallback(cb);
132 resizeMap(master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
133 master->getOriginX(), master->getOriginY());
140 return NO_INFORMATION;
142 return LETHAL_OBSTACLE;
147 return scale * LETHAL_OBSTACLE;
152 unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
154 ROS_DEBUG(
"Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
158 if (master->getSizeInCellsX() != size_x ||
159 master->getSizeInCellsY() != size_y ||
160 master->getResolution() != new_map->info.resolution ||
161 master->getOriginX() != new_map->info.origin.position.x ||
162 master->getOriginY() != new_map->info.origin.position.y ||
165 ROS_INFO(
"Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
167 new_map->info.origin.position.y,
true);
170 origin_x_ != new_map->info.origin.position.x ||
171 origin_y_ != new_map->info.origin.position.y){
175 unsigned int index = 0;
178 for (
unsigned int i = 0; i < size_y; ++i)
180 for (
unsigned int j = 0; j < size_x; ++j)
182 unsigned char value = new_map->data[index];
199 for (
unsigned int y = 0; y <
update->height ; y++)
202 for (
unsigned int x = 0; x <
update->width ; x++)
204 unsigned int index = index_base + x +
update->x;
236 double* max_x,
double* max_y)
246 *min_x = std::min(mx, *min_x);
247 *min_y = std::min(my, *min_y);
250 *max_x = std::max(mx, *max_x);
251 *max_y = std::max(my, *max_y);