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 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
00031 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
00032
00033 #include <ros/ros.h>
00034
00035 #include <geometry_msgs/PolygonStamped.h>
00036 #include <nav_msgs/OccupancyGrid.h>
00037
00038 #include <costmap_cspace_msgs/CSpace3D.h>
00039 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
00040
00041 #include <algorithm>
00042 #include <map>
00043 #include <string>
00044
00045 namespace costmap_cspace
00046 {
00047 class CSpace3DMsg : public costmap_cspace_msgs::CSpace3D
00048 {
00049 public:
00050 using Ptr = std::shared_ptr<CSpace3DMsg>;
00051 using ConstPtr = std::shared_ptr<const CSpace3DMsg>;
00052 size_t address(const int& x, const int& y, const int& yaw) const
00053 {
00054 return (yaw * info.height + y) * info.width + x;
00055 }
00056 const int8_t& getCost(const int& x, const int& y, const int& yaw) const
00057 {
00058 ROS_ASSERT(static_cast<size_t>(yaw) < info.angle);
00059 ROS_ASSERT(static_cast<size_t>(x) < info.width);
00060 ROS_ASSERT(static_cast<size_t>(y) < info.height);
00061
00062 const size_t addr = address(x, y, yaw);
00063 ROS_ASSERT(addr < data.size());
00064
00065 return data[addr];
00066 }
00067 int8_t& getCost(const int& x, const int& y, const int& yaw)
00068 {
00069 ROS_ASSERT(static_cast<size_t>(yaw) < info.angle);
00070 ROS_ASSERT(static_cast<size_t>(x) < info.width);
00071 ROS_ASSERT(static_cast<size_t>(y) < info.height);
00072
00073 const size_t addr = address(x, y, yaw);
00074 ROS_ASSERT(addr < data.size());
00075
00076 return data[addr];
00077 }
00078 };
00079
00080 enum MapOverlayMode
00081 {
00082 OVERWRITE,
00083 MAX
00084 };
00085
00086 class UpdatedRegion
00087 {
00088 public:
00089 int x_, y_, yaw_;
00090 int width_, height_, angle_;
00091 ros::Time stamp_;
00092
00093 UpdatedRegion()
00094 : x_(0)
00095 , y_(0)
00096 , yaw_(0)
00097 , width_(0)
00098 , height_(0)
00099 , angle_(0)
00100 , stamp_(0)
00101 {
00102 }
00103 UpdatedRegion(
00104 const int& x, const int& y, const int& yaw,
00105 const int& width, const int& height, const int& angle,
00106 const ros::Time& stamp = ros::Time())
00107 : x_(x)
00108 , y_(y)
00109 , yaw_(yaw)
00110 , width_(width)
00111 , height_(height)
00112 , angle_(angle)
00113 , stamp_(stamp)
00114 {
00115 }
00116 void merge(const UpdatedRegion& region)
00117 {
00118 if (region.width_ == 0 || region.height_ == 0 || region.angle_ == 0)
00119 return;
00120 if (region.stamp_ > stamp_)
00121 stamp_ = region.stamp_;
00122
00123 if (width_ == 0 || height_ == 0 || angle_ == 0)
00124 {
00125 *this = region;
00126 return;
00127 }
00128 int x2 = x_ + width_;
00129 int y2 = y_ + height_;
00130 int yaw2 = yaw_ + angle_;
00131
00132 const int mx2 = region.x_ + region.width_;
00133 const int my2 = region.y_ + region.height_;
00134 const int myaw2 = region.yaw_ + region.angle_;
00135
00136 if (region.x_ < x_)
00137 x_ = region.x_;
00138 if (region.y_ < y_)
00139 y_ = region.y_;
00140 if (region.yaw_ < yaw_)
00141 yaw_ = region.yaw_;
00142
00143 if (x2 < mx2)
00144 x2 = mx2;
00145 if (y2 < my2)
00146 y2 = my2;
00147 if (yaw2 < myaw2)
00148 yaw2 = myaw2;
00149
00150 width_ = x2 - x_;
00151 height_ = y2 - y_;
00152 angle_ = yaw2 - yaw_;
00153 }
00154 void expand(const int& ex)
00155 {
00156 ROS_ASSERT(ex >= 0);
00157 x_ -= ex;
00158 y_ -= ex;
00159 width_ += 2 * ex;
00160 height_ += 2 * ex;
00161 }
00162 void normalize()
00163 {
00164 const int x2 = x_ + width_;
00165 const int y2 = y_ + height_;
00166 if (x_ < 0)
00167 x_ = 0;
00168 if (y_ < 0)
00169 y_ = 0;
00170
00171 width_ = x2 - x_;
00172 height_ = y2 - y_;
00173 }
00174 void bitblt(const CSpace3DMsg::Ptr& dest, const CSpace3DMsg::ConstPtr& src)
00175 {
00176 ROS_ASSERT(dest->info.angle == src->info.angle);
00177 ROS_ASSERT(dest->info.width == src->info.width);
00178 ROS_ASSERT(dest->info.height == src->info.height);
00179
00180 normalize();
00181 const size_t copy_length =
00182 std::min<size_t>(width_, src->info.width - x_) *
00183 sizeof(src->data[0]);
00184 for (
00185 size_t a = yaw_;
00186 static_cast<int>(a) < yaw_ + angle_ && a < src->info.angle;
00187 ++a)
00188 {
00189 auto dest_pos = &dest->data[dest->address(x_, y_, a)];
00190 auto src_pos = &src->data[src->address(x_, y_, a)];
00191 const auto dest_stride = dest->info.width * sizeof(dest->data[0]);
00192 const auto src_stride = src->info.width * sizeof(src->data[0]);
00193 for (
00194 size_t y = y_;
00195 static_cast<int>(y) < y_ + height_ && y < src->info.height;
00196 ++y)
00197 {
00198 memcpy(
00199 dest_pos, src_pos, copy_length);
00200 src_pos += src_stride;
00201 dest_pos += dest_stride;
00202 }
00203 }
00204 }
00205 };
00206
00207 class Costmap3dLayerBase
00208 {
00209 public:
00210 using Ptr = std::shared_ptr<Costmap3dLayerBase>;
00211
00212 protected:
00213 int ang_grid_;
00214 MapOverlayMode overlay_mode_;
00215 bool root_;
00216
00217 CSpace3DMsg::Ptr map_;
00218 CSpace3DMsg::Ptr map_overlay_;
00219
00220 Costmap3dLayerBase::Ptr child_;
00221 UpdatedRegion region_;
00222 UpdatedRegion region_prev_;
00223 nav_msgs::OccupancyGrid::ConstPtr map_updated_;
00224
00225 public:
00226 Costmap3dLayerBase()
00227 : ang_grid_(-1)
00228 , overlay_mode_(MapOverlayMode::MAX)
00229 , root_(true)
00230 , map_(new CSpace3DMsg)
00231 , map_overlay_(new CSpace3DMsg)
00232 {
00233 }
00234
00235 virtual void loadConfig(XmlRpc::XmlRpcValue config) = 0;
00236 virtual void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info) = 0;
00237
00238 void setAngleResolution(
00239 const int ang_resolution)
00240 {
00241 ang_grid_ = ang_resolution;
00242 }
00243 void setOverlayMode(
00244 const MapOverlayMode overlay_mode)
00245 {
00246 overlay_mode_ = overlay_mode;
00247 }
00248 void setChild(Costmap3dLayerBase::Ptr child)
00249 {
00250 child_ = child;
00251 child_->setMap(getMapOverlay());
00252 child_->root_ = false;
00253 }
00254 void setBaseMap(const nav_msgs::OccupancyGrid::ConstPtr& base_map)
00255 {
00256 ROS_ASSERT(root_);
00257 ROS_ASSERT(ang_grid_ > 0);
00258 ROS_ASSERT(base_map->data.size() >= base_map->info.width * base_map->info.height);
00259
00260 const size_t xy_size = base_map->info.width * base_map->info.height;
00261 map_->header = base_map->header;
00262 map_->info.width = base_map->info.width;
00263 map_->info.height = base_map->info.height;
00264 map_->info.angle = ang_grid_;
00265 map_->info.linear_resolution = base_map->info.resolution;
00266 map_->info.angular_resolution = 2.0 * M_PI / ang_grid_;
00267 map_->info.origin = base_map->info.origin;
00268 map_->data.resize(xy_size * map_->info.angle);
00269
00270 setMapMetaData(map_->info);
00271
00272 for (size_t yaw = 0; yaw < map_->info.angle; yaw++)
00273 {
00274 for (unsigned int i = 0; i < xy_size; i++)
00275 {
00276 map_->data[i + yaw * xy_size] = 0;
00277 }
00278 }
00279 updateCSpace(
00280 base_map,
00281 UpdatedRegion(
00282 0, 0, 0,
00283 map_->info.width, map_->info.height, map_->info.angle,
00284 map_->header.stamp));
00285 for (size_t yaw = 0; yaw < map_->info.angle; yaw++)
00286 {
00287 for (unsigned int i = 0; i < xy_size; i++)
00288 {
00289 if (base_map->data[i] < 0)
00290 {
00291 map_->data[i + yaw * xy_size] = -1;
00292 }
00293 }
00294 }
00295 *map_overlay_ = *map_;
00296 if (child_)
00297 child_->setBaseMapChain();
00298
00299 updateChainEntry(
00300 UpdatedRegion(
00301 0, 0, 0, map_->info.width, map_->info.height, map_->info.angle,
00302 base_map->header.stamp));
00303 }
00304 void processMapOverlay(const nav_msgs::OccupancyGrid::ConstPtr& msg)
00305 {
00306 ROS_ASSERT(!root_);
00307 ROS_ASSERT(ang_grid_ > 0);
00308 const int ox =
00309 lroundf((msg->info.origin.position.x - map_->info.origin.position.x) /
00310 map_->info.linear_resolution);
00311 const int oy =
00312 lroundf((msg->info.origin.position.y - map_->info.origin.position.y) /
00313 map_->info.linear_resolution);
00314
00315 const int w =
00316 lroundf(msg->info.width * msg->info.resolution / map_->info.linear_resolution);
00317 const int h =
00318 lroundf(msg->info.height * msg->info.resolution / map_->info.linear_resolution);
00319
00320 map_updated_ = msg;
00321
00322 region_ = UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg->header.stamp);
00323 updateChainEntry(UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg->header.stamp));
00324 }
00325 CSpace3DMsg::Ptr getMap()
00326 {
00327 return map_;
00328 }
00329 void setMap(CSpace3DMsg::Ptr map)
00330 {
00331 map_ = map;
00332 }
00333 CSpace3DMsg::Ptr getMapOverlay()
00334 {
00335 return map_overlay_;
00336 }
00337 int getAngularGrid() const
00338 {
00339 return ang_grid_;
00340 }
00341
00342 protected:
00343 virtual bool updateChain(const bool output) = 0;
00344 virtual void updateCSpace(
00345 const nav_msgs::OccupancyGrid::ConstPtr& map,
00346 const UpdatedRegion& region) = 0;
00347 virtual int getRangeMax() const = 0;
00348
00349 bool updateChainEntry(const UpdatedRegion& region, bool output = true)
00350 {
00351 auto region_expand = region;
00352 region_expand.expand(getRangeMax());
00353
00354 region_.merge(region_expand);
00355
00356 auto region_prev_now = region_;
00357 region_prev_now.merge(region_prev_);
00358 region_prev_ = region_;
00359
00360 region_prev_now.bitblt(map_overlay_, map_);
00361 if (map_updated_)
00362 {
00363 if (map_->header.frame_id == map_updated_->header.frame_id)
00364 {
00365 updateCSpace(map_updated_, region_);
00366 }
00367 else
00368 {
00369 ROS_ERROR("map and map_overlay must have same frame_id. skipping");
00370 }
00371 }
00372
00373 if (updateChain(output))
00374 output = false;
00375
00376 if (child_)
00377 {
00378 return child_->updateChainEntry(region_, output);
00379 }
00380 return false;
00381 }
00382 void setBaseMapChain()
00383 {
00384 setMapMetaData(map_->info);
00385 *map_overlay_ = *map_;
00386 if (child_)
00387 child_->setBaseMapChain();
00388 }
00389 };
00390 }
00391
00392 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H