30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H 40 #include <costmap_cspace_msgs/CSpace3D.h> 41 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 42 #include <geometry_msgs/PolygonStamped.h> 43 #include <nav_msgs/OccupancyGrid.h> 56 using Ptr = std::shared_ptr<Costmap3dLayerFootprint>;
74 , keep_unknown_(false)
81 static_cast<double>(config[
"linear_expand"]),
82 static_cast<double>(config[
"linear_spread"]));
89 keep_unknown_ = keep_unknown;
92 const float linear_expand,
93 const float linear_spread)
95 linear_expand_ = linear_expand;
96 linear_spread_ = linear_spread;
105 footprint_p_ = footprint;
106 footprint_radius_ = footprint.
radius();
107 footprint_ = footprint.
toMsg();
134 std::ceil((footprint_radius_ + linear_expand_ + linear_spread_) / info.linear_resolution);
135 cs_template_.
reset(range_max_, range_max_, info.angle);
138 for (
size_t yaw = 0; yaw < info.angle; yaw++)
145 f.move(
x * info.linear_resolution,
146 y * info.linear_resolution,
147 yaw * info.angular_resolution);
153 cs_template_.
e(
x,
y, yaw) = 100;
157 const float d =
f.dist(p);
158 if (d < linear_expand_)
160 cs_template_.
e(
x,
y, yaw) = 100;
162 else if (d < linear_expand_ + linear_spread_)
168 cs_template_.
e(
x,
y, yaw) = 0;
173 if (footprint_radius_ == 0)
174 cs_template_.
e(0, 0, yaw) = 100;
184 const nav_msgs::OccupancyGrid::ConstPtr& map,
194 const nav_msgs::OccupancyGrid::ConstPtr& msg,
199 for (
size_t yaw = 0; yaw < map->info.angle; yaw++)
208 const nav_msgs::OccupancyGrid::ConstPtr& msg)
215 std::lround((msg->info.origin.position.x - map->info.origin.position.x) /
216 map->info.linear_resolution);
218 std::lround((msg->info.origin.position.y - map->info.origin.position.y) /
219 map->info.linear_resolution);
220 const double resolution_scale = msg->info.resolution / map->info.linear_resolution;
222 for (
size_t yaw = 0; yaw < map->info.angle; yaw++)
224 for (
size_t i = 0; i < msg->data.size(); i++)
226 const auto& val = msg->data[i];
230 const int x = std::lround((i % msg->info.width) * resolution_scale);
231 if (x < range_max_ || static_cast<int>(msg->info.width) - range_max_ <= x)
233 const int y = std::lround((i / msg->info.width) * resolution_scale);
234 if (y < range_max_ || static_cast<int>(msg->info.height) - range_max_ <= y)
237 const int res_up = std::ceil(resolution_scale);
238 for (
int yp = 0; yp < res_up; yp++)
240 const int y2 = y + oy + yp;
241 if (static_cast<size_t>(y2) >= map->info.height)
243 for (
int xp = 0; xp < res_up; xp++)
245 const int x2 = x + ox + xp;
246 if (static_cast<size_t>(x2) >= map->info.width)
249 map->getCost(x2, y2, yaw) = -1;
257 const nav_msgs::OccupancyGrid::ConstPtr& msg,
261 std::lround((msg->info.origin.position.x - map->info.origin.position.x) /
262 map->info.linear_resolution);
264 std::lround((msg->info.origin.position.y - map->info.origin.position.y) /
265 map->info.linear_resolution);
266 const double resolution_scale = msg->info.resolution / map->info.linear_resolution;
269 unknown_buf_.resize(msg->data.size());
270 for (
size_t i = 0; i < msg->data.size(); i++)
272 const int gx = std::lround((i % msg->info.width) * resolution_scale) + ox;
273 const int gy = std::lround((i / msg->info.width) * resolution_scale) + oy;
274 if (static_cast<size_t>(gx) >= map->info.width ||
275 static_cast<size_t>(gy) >= map->info.height)
281 unknown_buf_[i] = msg->data[i] < 0 && map->getCost(gx, gy, yaw) < 0;
284 for (
size_t i = 0; i < msg->data.size(); i++)
286 const int8_t val = msg->data[i];
291 const int gx = std::lround((i % msg->info.width) * resolution_scale) + ox;
292 const int gy = std::lround((i / msg->info.width) * resolution_scale) + oy;
293 if (static_cast<size_t>(gx) >= map->info.width ||
294 static_cast<size_t>(gy) >= map->info.height)
298 int8_t& m = map->getCost(gx, gy, yaw);
304 const int map_x_min = std::max(gx - range_max_, 0);
305 const int map_x_max = std::min(gx + range_max_, static_cast<int>(map->info.width) - 1);
306 const int map_y_min = std::max(gy - range_max_, 0);
307 const int map_y_max = std::min(gy + range_max_, static_cast<int>(map->info.height) - 1);
308 for (
int map_y = map_y_min; map_y <= map_y_max; ++map_y)
311 int8_t* cost_addr = &(map->getCost(map_x_min, map_y, yaw));
312 const char* cs_addr = &(cs_template_.
e(map_x_min - gx, map_y - gy, yaw));
313 for (
int n = 0; n <= map_x_max - map_x_min; ++n, ++cost_addr, ++cs_addr)
315 const int8_t c = *cs_addr * val / 100;
316 if (c > 0 && *cost_addr < c)
323 for (
size_t i = 0; i < unknown_buf_.size(); i++)
325 if (!unknown_buf_[i])
327 const int gx = std::lround((i % msg->info.width) * resolution_scale) + ox;
328 const int gy = std::lround((i / msg->info.width) * resolution_scale) + oy;
329 if (static_cast<size_t>(gx) >= map->info.width ||
330 static_cast<size_t>(gy) >= map->info.height)
332 map->getCost(gx, gy, yaw) = -1;
339 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H
MapOverlayMode overlay_mode_
CSpace3DMsg::Ptr map_overlay_
geometry_msgs::PolygonStamped toMsg() const
TFSIMD_FORCE_INLINE const tfScalar & y() const
TFSIMD_FORCE_INLINE const tfScalar & x() const
bool hasMember(const std::string &name) const
std::shared_ptr< CSpace3DMsg > Ptr
void reset(const int &x, const int &y, const int &yaw)
std::shared_ptr< Costmap3dLayerBase > Ptr
char & e(const int &x, const int &y, const int &yaw)