30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H 35 #include <geometry_msgs/PolygonStamped.h> 36 #include <nav_msgs/OccupancyGrid.h> 38 #include <costmap_cspace_msgs/CSpace3D.h> 39 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 50 using Ptr = std::shared_ptr<CSpace3DMsg>;
51 using ConstPtr = std::shared_ptr<const CSpace3DMsg>;
52 size_t address(
const int& x,
const int& y,
const int& yaw)
const 54 return (yaw * info.height + y) * info.width + x;
56 const int8_t&
getCost(
const int& x,
const int& y,
const int& yaw)
const 58 ROS_ASSERT(static_cast<size_t>(yaw) < info.angle);
59 ROS_ASSERT(static_cast<size_t>(x) < info.width);
60 ROS_ASSERT(static_cast<size_t>(y) < info.height);
62 const size_t addr =
address(x, y, yaw);
67 int8_t&
getCost(
const int& x,
const int& y,
const int& yaw)
69 ROS_ASSERT(static_cast<size_t>(yaw) < info.angle);
70 ROS_ASSERT(static_cast<size_t>(x) < info.width);
71 ROS_ASSERT(static_cast<size_t>(y) < info.height);
73 const size_t addr =
address(x, y, yaw);
104 const int& x,
const int& y,
const int& yaw,
105 const int& width,
const int& height,
const int& angle,
120 if (region.
stamp_ > stamp_)
123 if (width_ == 0 || height_ == 0 || angle_ == 0)
128 int x2 = x_ + width_;
129 int y2 = y_ + height_;
130 int yaw2 = yaw_ + angle_;
132 const int mx2 = region.
x_ + region.
width_;
133 const int my2 = region.
y_ + region.
height_;
134 const int myaw2 = region.
yaw_ + region.
angle_;
140 if (region.
yaw_ < yaw_)
152 angle_ = yaw2 - yaw_;
164 const int x2 = x_ + width_;
165 const int y2 = y_ + height_;
176 ROS_ASSERT(dest->info.angle == src->info.angle);
177 ROS_ASSERT(dest->info.width == src->info.width);
178 ROS_ASSERT(dest->info.height == src->info.height);
181 const size_t copy_length =
182 std::min<size_t>(width_, src->info.width - x_) *
183 sizeof(src->data[0]);
186 static_cast<int>(a) < yaw_ + angle_ && a < src->info.angle;
189 auto dest_pos = &dest->data[dest->address(x_, y_, a)];
190 auto src_pos = &src->data[src->address(x_, y_, a)];
191 const auto dest_stride = dest->info.width *
sizeof(dest->data[0]);
192 const auto src_stride = src->info.width *
sizeof(src->data[0]);
195 static_cast<int>(y) < y_ + height_ && y < src->info.height;
199 dest_pos, src_pos, copy_length);
200 src_pos += src_stride;
201 dest_pos += dest_stride;
210 using Ptr = std::shared_ptr<Costmap3dLayerBase>;
236 virtual void setMapMetaData(
const costmap_cspace_msgs::MapMetaData3D& info) = 0;
239 const int ang_resolution)
241 ang_grid_ = ang_resolution;
246 overlay_mode_ = overlay_mode;
251 child_->setMap(getMapOverlay());
252 child_->root_ =
false;
254 void setBaseMap(
const nav_msgs::OccupancyGrid::ConstPtr& base_map)
258 ROS_ASSERT(base_map->data.size() >= base_map->info.width * base_map->info.height);
260 const size_t xy_size = base_map->info.width * base_map->info.height;
261 map_->header = base_map->header;
262 map_->info.width = base_map->info.width;
263 map_->info.height = base_map->info.height;
264 map_->info.angle = ang_grid_;
265 map_->info.linear_resolution = base_map->info.resolution;
266 map_->info.angular_resolution = 2.0 * M_PI / ang_grid_;
267 map_->info.origin = base_map->info.origin;
268 map_->data.resize(xy_size * map_->info.angle);
270 setMapMetaData(map_->info);
272 for (
size_t yaw = 0; yaw < map_->info.angle; yaw++)
274 for (
unsigned int i = 0; i < xy_size; i++)
276 map_->data[i + yaw * xy_size] = 0;
283 map_->info.width, map_->info.height, map_->info.angle,
284 map_->header.stamp));
285 for (
size_t yaw = 0; yaw < map_->info.angle; yaw++)
287 for (
unsigned int i = 0; i < xy_size; i++)
289 if (base_map->data[i] < 0)
291 map_->data[i + yaw * xy_size] = -1;
295 *map_overlay_ = *map_;
297 child_->setBaseMapChain();
301 0, 0, 0, map_->info.width, map_->info.height, map_->info.angle,
302 base_map->header.stamp));
309 lroundf((msg->info.origin.position.x - map_->info.origin.position.x) /
310 map_->info.linear_resolution);
312 lroundf((msg->info.origin.position.y - map_->info.origin.position.y) /
313 map_->info.linear_resolution);
316 lroundf(msg->info.width * msg->info.resolution / map_->info.linear_resolution);
318 lroundf(msg->info.height * msg->info.resolution / map_->info.linear_resolution);
322 region_ =
UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg->header.stamp);
323 updateChainEntry(
UpdatedRegion(ox, oy, 0, w, h, map_->info.angle, msg->header.stamp));
343 virtual bool updateChain(
const bool output) = 0;
344 virtual void updateCSpace(
345 const nav_msgs::OccupancyGrid::ConstPtr& map,
347 virtual int getRangeMax()
const = 0;
351 auto region_expand = region;
352 region_expand.
expand(getRangeMax());
354 region_.
merge(region_expand);
356 auto region_prev_now = region_;
357 region_prev_now.
merge(region_prev_);
358 region_prev_ = region_;
360 region_prev_now.
bitblt(map_overlay_, map_);
363 if (map_->header.frame_id == map_updated_->header.frame_id)
365 updateCSpace(map_updated_, region_);
369 ROS_ERROR(
"map and map_overlay must have same frame_id. skipping");
373 if (updateChain(output))
378 return child_->updateChainEntry(region_, output);
384 setMapMetaData(map_->info);
385 *map_overlay_ = *map_;
387 child_->setBaseMapChain();
392 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
UpdatedRegion(const int &x, const int &y, const int &yaw, const int &width, const int &height, const int &angle, const ros::Time &stamp=ros::Time())
MapOverlayMode overlay_mode_
UpdatedRegion region_prev_
void bitblt(const CSpace3DMsg::Ptr &dest, const CSpace3DMsg::ConstPtr &src)
const int8_t & getCost(const int &x, const int &y, const int &yaw) const
void merge(const UpdatedRegion ®ion)
CSpace3DMsg::Ptr getMap()
void expand(const int &ex)
CSpace3DMsg::Ptr map_overlay_
Costmap3dLayerBase::Ptr child_
void setOverlayMode(const MapOverlayMode overlay_mode)
void setBaseMap(const nav_msgs::OccupancyGrid::ConstPtr &base_map)
int8_t & getCost(const int &x, const int &y, const int &yaw)
nav_msgs::OccupancyGrid::ConstPtr map_updated_
void setAngleResolution(const int ang_resolution)
void processMapOverlay(const nav_msgs::OccupancyGrid::ConstPtr &msg)
TFSIMD_FORCE_INLINE Vector3 & normalize()
bool updateChainEntry(const UpdatedRegion ®ion, bool output=true)
TFSIMD_FORCE_INLINE const tfScalar & w() const
void setChild(Costmap3dLayerBase::Ptr child)
std::shared_ptr< CSpace3DMsg > Ptr
std::shared_ptr< Costmap3dLayerBase > Ptr
size_t address(const int &x, const int &y, const int &yaw) const
std::shared_ptr< const CSpace3DMsg > ConstPtr
int getAngularGrid() const
CSpace3DMsg::Ptr getMapOverlay()
void setMap(CSpace3DMsg::Ptr map)