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/layered_costmap.h>
00039 #include <costmap_2d/footprint.h>
00040 #include <cstdio>
00041 #include <string>
00042 #include <algorithm>
00043 #include <vector>
00044
00045 using std::vector;
00046
00047 namespace costmap_2d
00048 {
00049
00050 LayeredCostmap::LayeredCostmap(std::string global_frame, bool rolling_window, bool track_unknown) :
00051 costmap_(), global_frame_(global_frame), rolling_window_(rolling_window), initialized_(false), size_locked_(false)
00052 {
00053 if (track_unknown)
00054 costmap_.setDefaultValue(255);
00055 else
00056 costmap_.setDefaultValue(0);
00057 }
00058
00059 LayeredCostmap::~LayeredCostmap()
00060 {
00061 while (plugins_.size() > 0)
00062 {
00063 plugins_.pop_back();
00064 }
00065 }
00066
00067 void LayeredCostmap::resizeMap(unsigned int size_x, unsigned int size_y, double resolution, double origin_x,
00068 double origin_y, bool size_locked)
00069 {
00070 size_locked_ = size_locked;
00071 costmap_.resizeMap(size_x, size_y, resolution, origin_x, origin_y);
00072 for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
00073 ++plugin)
00074 {
00075 (*plugin)->matchSize();
00076 }
00077 }
00078
00079 void LayeredCostmap::updateMap(double robot_x, double robot_y, double robot_yaw)
00080 {
00081
00082 if (rolling_window_)
00083 {
00084 double new_origin_x = robot_x - costmap_.getSizeInMetersX() / 2;
00085 double new_origin_y = robot_y - costmap_.getSizeInMetersY() / 2;
00086 costmap_.updateOrigin(new_origin_x, new_origin_y);
00087 }
00088
00089 if (plugins_.size() == 0)
00090 return;
00091
00092 minx_ = miny_ = 1e30;
00093 maxx_ = maxy_ = -1e30;
00094
00095 for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
00096 ++plugin)
00097 {
00098 (*plugin)->updateBounds(robot_x, robot_y, robot_yaw, &minx_, &miny_, &maxx_, &maxy_);
00099 }
00100
00101 int x0, xn, y0, yn;
00102 costmap_.worldToMapEnforceBounds(minx_, miny_, x0, y0);
00103 costmap_.worldToMapEnforceBounds(maxx_, maxy_, xn, yn);
00104
00105 x0 = std::max(0, x0);
00106 xn = std::min(int(costmap_.getSizeInCellsX()), xn + 1);
00107 y0 = std::max(0, y0);
00108 yn = std::min(int(costmap_.getSizeInCellsY()), yn + 1);
00109
00110 ROS_DEBUG("Updating area x: [%d, %d] y: [%d, %d]", x0, xn, y0, yn);
00111
00112 if (xn < x0 || yn < y0)
00113 return;
00114
00115 costmap_.resetMap(x0, y0, xn, yn);
00116
00117 {
00118 boost::unique_lock < boost::shared_mutex > lock(*(costmap_.getLock()));
00119 for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
00120 ++plugin)
00121 {
00122 (*plugin)->updateCosts(costmap_, x0, y0, xn, yn);
00123 }
00124 }
00125
00126 bx0_ = x0;
00127 bxn_ = xn;
00128 by0_ = y0;
00129 byn_ = yn;
00130
00131 initialized_ = true;
00132 }
00133
00134 bool LayeredCostmap::isCurrent()
00135 {
00136 current_ = true;
00137 for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
00138 ++plugin)
00139 {
00140 current_ = current_ && (*plugin)->isCurrent();
00141 }
00142 return current_;
00143 }
00144
00145 void LayeredCostmap::setFootprint(const std::vector<geometry_msgs::Point>& footprint_spec)
00146 {
00147 footprint_ = footprint_spec;
00148 costmap_2d::calculateMinAndMaxDistances( footprint_spec, inscribed_radius_, circumscribed_radius_ );
00149
00150 for (vector<boost::shared_ptr<Layer> >::iterator plugin = plugins_.begin(); plugin != plugins_.end();
00151 ++plugin)
00152 {
00153 (*plugin)->onFootprintChanged();
00154 }
00155 }
00156
00157 }