00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 #include <costmap_2d/static_layer.h>
00039 #include <costmap_2d/costmap_math.h>
00040 #include <pluginlib/class_list_macros.h>
00041
00042 PLUGINLIB_EXPORT_CLASS(costmap_2d::StaticLayer, costmap_2d::Layer)
00043
00044 using costmap_2d::NO_INFORMATION;
00045 using costmap_2d::LETHAL_OBSTACLE;
00046 using costmap_2d::FREE_SPACE;
00047
00048 namespace costmap_2d
00049 {
00050
00051 StaticLayer::StaticLayer() : dsrv_(NULL) {}
00052
00053 StaticLayer::~StaticLayer()
00054 {
00055 if(dsrv_)
00056 delete dsrv_;
00057 }
00058
00059 void StaticLayer::onInitialize()
00060 {
00061 ros::NodeHandle nh("~/" + name_), g_nh;
00062 current_ = true;
00063
00064 global_frame_ = layered_costmap_->getGlobalFrameID();
00065
00066 std::string map_topic;
00067 nh.param("map_topic", map_topic, std::string("map"));
00068 nh.param("subscribe_to_updates", subscribe_to_updates_, false);
00069
00070 nh.param("track_unknown_space", track_unknown_space_, true);
00071 nh.param("use_maximum", use_maximum_, false);
00072
00073 int temp_lethal_threshold, temp_unknown_cost_value;
00074 nh.param("lethal_cost_threshold", temp_lethal_threshold, int(100));
00075 nh.param("unknown_cost_value", temp_unknown_cost_value, int(-1));
00076 nh.param("trinary_costmap", trinary_costmap_, true);
00077
00078 lethal_threshold_ = std::max(std::min(temp_lethal_threshold, 100), 0);
00079 unknown_cost_value_ = temp_unknown_cost_value;
00080
00081 ROS_INFO("Requesting the map...");
00082 map_sub_ = g_nh.subscribe(map_topic, 1, &StaticLayer::incomingMap, this);
00083 map_received_ = false;
00084 has_updated_data_ = false;
00085
00086 ros::Rate r(10);
00087 while (!map_received_ && g_nh.ok())
00088 {
00089 ros::spinOnce();
00090 r.sleep();
00091 }
00092
00093 ROS_INFO("Received a %d X %d map at %f m/pix", getSizeInCellsX(), getSizeInCellsY(), getResolution());
00094
00095 if(subscribe_to_updates_)
00096 {
00097 ROS_INFO("Subscribing to updates");
00098 map_update_sub_ = g_nh.subscribe(map_topic + "_updates", 10, &StaticLayer::incomingUpdate, this);
00099 }
00100
00101 if(dsrv_)
00102 {
00103 delete dsrv_;
00104 }
00105
00106 dsrv_ = new dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>(nh);
00107 dynamic_reconfigure::Server<costmap_2d::GenericPluginConfig>::CallbackType cb = boost::bind(
00108 &StaticLayer::reconfigureCB, this, _1, _2);
00109 dsrv_->setCallback(cb);
00110 }
00111
00112 void StaticLayer::reconfigureCB(costmap_2d::GenericPluginConfig &config, uint32_t level)
00113 {
00114 if (config.enabled != enabled_)
00115 {
00116 enabled_ = config.enabled;
00117 has_updated_data_ = true;
00118 x_ = y_ = 0;
00119 width_ = size_x_;
00120 height_ = size_y_;
00121 }
00122 }
00123
00124 void StaticLayer::matchSize()
00125 {
00126 Costmap2D* master = layered_costmap_->getCostmap();
00127 resizeMap(master->getSizeInCellsX(), master->getSizeInCellsY(), master->getResolution(),
00128 master->getOriginX(), master->getOriginY());
00129 }
00130
00131 unsigned char StaticLayer::interpretValue(unsigned char value)
00132 {
00133
00134 if (track_unknown_space_ && value == unknown_cost_value_)
00135 return NO_INFORMATION;
00136 else if (value >= lethal_threshold_)
00137 return LETHAL_OBSTACLE;
00138 else if (trinary_costmap_)
00139 return FREE_SPACE;
00140
00141 double scale = (double) value / lethal_threshold_;
00142 return scale * LETHAL_OBSTACLE;
00143 }
00144
00145 void StaticLayer::incomingMap(const nav_msgs::OccupancyGridConstPtr& new_map)
00146 {
00147 unsigned int size_x = new_map->info.width, size_y = new_map->info.height;
00148
00149 ROS_DEBUG("Received a %d X %d map at %f m/pix", size_x, size_y, new_map->info.resolution);
00150
00151
00152 Costmap2D* master = layered_costmap_->getCostmap();
00153 if (master->getSizeInCellsX() != size_x ||
00154 master->getSizeInCellsY() != size_y ||
00155 master->getResolution() != new_map->info.resolution ||
00156 master->getOriginX() != new_map->info.origin.position.x ||
00157 master->getOriginY() != new_map->info.origin.position.y ||
00158 !layered_costmap_->isSizeLocked())
00159 {
00160 ROS_INFO("Resizing costmap to %d X %d at %f m/pix", size_x, size_y, new_map->info.resolution);
00161 layered_costmap_->resizeMap(size_x, size_y, new_map->info.resolution, new_map->info.origin.position.x,
00162 new_map->info.origin.position.y, true);
00163 }else if(size_x_ != size_x || size_y_ != size_y ||
00164 resolution_ != new_map->info.resolution ||
00165 origin_x_ != new_map->info.origin.position.x ||
00166 origin_y_ != new_map->info.origin.position.y){
00167 matchSize();
00168 }
00169
00170 unsigned int index = 0;
00171
00172
00173 for (unsigned int i = 0; i < size_y; ++i)
00174 {
00175 for (unsigned int j = 0; j < size_x; ++j)
00176 {
00177 unsigned char value = new_map->data[index];
00178 costmap_[index] = interpretValue(value);
00179 ++index;
00180 }
00181 }
00182 x_ = y_ = 0;
00183 width_ = size_x_;
00184 height_ = size_y_;
00185 map_received_ = true;
00186 has_updated_data_ = true;
00187 }
00188
00189 void StaticLayer::incomingUpdate(const map_msgs::OccupancyGridUpdateConstPtr& update)
00190 {
00191 unsigned int di = 0;
00192 for (unsigned int y = 0; y < update->height ; y++)
00193 {
00194 unsigned int index_base = (update->y + y) * update->width;
00195 for (unsigned int x = 0; x < update->width ; x++)
00196 {
00197 unsigned int index = index_base + x + update->x;
00198 costmap_[index] = interpretValue( update->data[di++] );
00199 }
00200 }
00201 x_ = update->x;
00202 y_ = update->y;
00203 width_ = update->width;
00204 height_ = update->height;
00205 has_updated_data_ = true;
00206 }
00207
00208 void StaticLayer::activate()
00209 {
00210 onInitialize();
00211 }
00212
00213 void StaticLayer::deactivate()
00214 {
00215 map_sub_.shutdown();
00216 if (subscribe_to_updates_)
00217 map_update_sub_.shutdown();
00218 }
00219
00220 void StaticLayer::reset()
00221 {
00222 deactivate();
00223 activate();
00224 }
00225
00226 void StaticLayer::updateBounds(double robot_x, double robot_y, double robot_yaw, double* min_x, double* min_y,
00227 double* max_x, double* max_y)
00228 {
00229 if (!map_received_ || !(has_updated_data_ || has_extra_bounds_))
00230 return;
00231
00232 useExtraBounds(min_x, min_y, max_x, max_y);
00233
00234 double mx, my;
00235
00236 mapToWorld(x_, y_, mx, my);
00237 *min_x = std::min(mx, *min_x);
00238 *min_y = std::min(my, *min_y);
00239
00240 mapToWorld(x_ + width_, y_ + height_, mx, my);
00241 *max_x = std::max(mx, *max_x);
00242 *max_y = std::max(my, *max_y);
00243
00244 has_updated_data_ = false;
00245 }
00246
00247 void StaticLayer::updateCosts(costmap_2d::Costmap2D& master_grid, int min_i, int min_j, int max_i, int max_j)
00248 {
00249 if (!map_received_)
00250 return;
00251 if (!use_maximum_)
00252 updateWithTrueOverwrite(master_grid, min_i, min_j, max_i, max_j);
00253 else
00254 updateWithMax(master_grid, min_i, min_j, max_i, max_j);
00255 }
00256
00257 }