30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H
41 #include <geometry_msgs/PolygonStamped.h>
42 #include <nav_msgs/OccupancyGrid.h>
44 #include <costmap_cspace_msgs/CSpace3D.h>
45 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
52 using Ptr = std::shared_ptr<CSpace3DMsg>;
53 using ConstPtr = std::shared_ptr<const CSpace3DMsg>;
54 size_t address(
const int& x,
const int& y,
const int& yaw)
const
56 return (yaw * info.height + y) * info.width + x;
58 const int8_t&
getCost(
const int& x,
const int& y,
const int& yaw)
const
60 ROS_ASSERT(
static_cast<size_t>(yaw) < info.angle);
61 ROS_ASSERT(
static_cast<size_t>(x) < info.width);
62 ROS_ASSERT(
static_cast<size_t>(y) < info.height);
64 const size_t addr =
address(x, y, yaw);
69 int8_t&
getCost(
const int& x,
const int& y,
const int& yaw)
71 ROS_ASSERT(
static_cast<size_t>(yaw) < info.angle);
72 ROS_ASSERT(
static_cast<size_t>(x) < info.width);
73 ROS_ASSERT(
static_cast<size_t>(y) < info.height);
75 const size_t addr =
address(x, y, yaw);
81 const CSpace3DMsg& from,
const int& from_x,
const int& from_y,
const int& from_yaw,
82 const int& copy_cell_num)
84 std::memcpy(to.data.data() + to.
address(to_x, to_y, to_yaw),
85 from.data.data() + from.
address(from_x, from_y, from_yaw), copy_cell_num *
sizeof(int8_t));
87 static void copyCells(costmap_cspace_msgs::CSpace3DUpdate& to,
const int& to_x,
const int& to_y,
const int& to_yaw,
88 const CSpace3DMsg& from,
const int& from_x,
const int& from_y,
const int& from_yaw,
89 const int& copy_cell_num)
91 std::memcpy(to.data.data() + (to_yaw * to.height + to_y) * to.width + to_x,
92 from.data.data() + from.
address(from_x, from_y, from_yaw), copy_cell_num *
sizeof(int8_t));
120 const int& x,
const int& y,
const int& yaw,
121 const int& width,
const int& height,
const int& angle,
148 const int mx2 = region.
x_ + region.
width_;
149 const int my2 = region.
y_ + region.
height_;
150 const int myaw2 = region.
yaw_ + region.
angle_;
178 void normalize(
const int full_width,
const int full_height)
182 int update_width =
width_;
186 update_width += update_x;
191 update_height += update_y;
194 if (update_x + update_width > full_width)
196 update_width = full_width - update_x;
198 if (update_y + update_height > full_height)
200 update_height = full_height - update_y;
202 if (update_width < 0)
206 if (update_height < 0)
218 ROS_ASSERT(dest->info.angle == src->info.angle);
219 ROS_ASSERT(dest->info.width == src->info.width);
220 ROS_ASSERT(dest->info.height == src->info.height);
222 normalize(src->info.width, src->info.height);
226 const size_t copy_length =
227 std::min<size_t>(
width_, src->info.width -
x_) *
228 sizeof(src->data[0]);
231 static_cast<int>(a) <
yaw_ +
angle_ && a < src->info.angle;
234 auto dest_pos = &dest->data[dest->address(
x_,
y_, a)];
235 auto src_pos = &src->data[src->address(
x_,
y_, a)];
236 const auto dest_stride = dest->info.width *
sizeof(dest->data[0]);
237 const auto src_stride = src->info.width *
sizeof(src->data[0]);
240 static_cast<int>(y) <
y_ +
height_ && y < src->info.height;
244 dest_pos, src_pos, copy_length);
245 src_pos += src_stride;
246 dest_pos += dest_stride;
255 using Ptr = std::shared_ptr<Costmap3dLayerBase>;
281 virtual void setMapMetaData(
const costmap_cspace_msgs::MapMetaData3D& info) = 0;
284 const int ang_resolution)
299 void setBaseMap(
const nav_msgs::OccupancyGrid::ConstPtr& base_map)
303 ROS_ASSERT(base_map->data.size() >= base_map->info.width * base_map->info.height);
305 const size_t xy_size = base_map->info.width * base_map->info.height;
306 map_->header = base_map->header;
307 map_->info.width = base_map->info.width;
308 map_->info.height = base_map->info.height;
310 map_->info.linear_resolution = base_map->info.resolution;
312 map_->info.origin = base_map->info.origin;
313 map_->data.resize(xy_size *
map_->info.angle);
317 for (
size_t yaw = 0; yaw <
map_->info.angle; yaw++)
319 for (
unsigned int i = 0; i < xy_size; i++)
321 map_->data[i + yaw * xy_size] = -1;
329 map_->header.stamp));
330 for (
size_t yaw = 0; yaw <
map_->info.angle; yaw++)
332 for (
unsigned int i = 0; i < xy_size; i++)
334 if (base_map->data[i] < 0)
336 map_->data[i + yaw * xy_size] = -1;
342 child_->setBaseMapChain();
346 0, 0, 0,
map_->info.width,
map_->info.height,
map_->info.angle,
347 base_map->header.stamp));
349 void processMapOverlay(
const nav_msgs::OccupancyGrid::ConstPtr& msg,
const bool update_chain_entry)
354 std::lround((msg->info.origin.position.x -
map_->info.origin.position.x) /
355 map_->info.linear_resolution);
357 std::lround((msg->info.origin.position.y -
map_->info.origin.position.y) /
358 map_->info.linear_resolution);
361 std::lround(msg->info.width * msg->info.resolution /
map_->info.linear_resolution);
363 std::lround(msg->info.height * msg->info.resolution /
map_->info.linear_resolution);
369 if (update_chain_entry)
375 ROS_DEBUG(
"update_chain_entry execution has been avoided.");
398 const nav_msgs::OccupancyGrid::ConstPtr& map,
407 auto region_prev_now =
region_;
420 ROS_ERROR(
"map and map_overlay must have same frame_id. skipping");
438 child_->setBaseMapChain();
443 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_BASE_H