30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_FOOTPRINT_H 35 #include <geometry_msgs/PolygonStamped.h> 36 #include <nav_msgs/OccupancyGrid.h> 37 #include <costmap_cspace_msgs/CSpace3D.h> 38 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 51 using Ptr = std::shared_ptr<Costmap3dLayerFootprint>;
73 static_cast<double>(config[
"linear_expand"]),
74 static_cast<double>(config[
"linear_spread"]));
78 const float linear_expand,
79 const float linear_spread)
81 linear_expand_ = linear_expand;
82 linear_spread_ = linear_spread;
91 footprint_p_ = footprint;
92 footprint_radius_ = footprint.
radius();
93 footprint_ = footprint.
toMsg();
120 ceilf((footprint_radius_ + linear_expand_ + linear_spread_) / info.linear_resolution);
121 cs_template_.
reset(range_max_, range_max_, info.angle);
124 for (
size_t yaw = 0; yaw < info.angle; yaw++)
131 f.move(
x * info.linear_resolution,
132 y * info.linear_resolution,
133 yaw * info.angular_resolution);
139 cs_template_.
e(
x,
y, yaw) = 100;
143 const float d =
f.dist(p);
144 if (d < linear_expand_)
146 cs_template_.
e(
x,
y, yaw) = 100;
148 else if (d < linear_expand_ + linear_spread_)
154 cs_template_.
e(
x,
y, yaw) = 0;
159 if (footprint_radius_ == 0)
160 cs_template_.
e(0, 0, yaw) = 100;
170 const nav_msgs::OccupancyGrid::ConstPtr& map,
180 const nav_msgs::OccupancyGrid::ConstPtr& msg,
185 lroundf((msg->info.origin.position.x - map->info.origin.position.x) /
186 map->info.linear_resolution);
188 lroundf((msg->info.origin.position.y - map->info.origin.position.y) /
189 map->info.linear_resolution);
193 for (
size_t yaw = 0; yaw < map->info.angle; yaw++)
195 for (
unsigned int i = 0; i < msg->data.size(); i++)
197 const auto& val = msg->data[i];
202 lroundf((i % msg->info.width) * msg->info.resolution / map->info.linear_resolution);
203 if (x < range_max_ || static_cast<int>(msg->info.width) - range_max_ <= x)
206 lroundf((i / msg->info.width) * msg->info.resolution / map->info.linear_resolution);
207 if (y < range_max_ || static_cast<int>(msg->info.height) - range_max_ <= y)
210 const int res_up = ceilf(msg->info.resolution / map->info.linear_resolution);
211 for (
int yp = 0; yp < res_up; yp++)
213 for (
int xp = 0; xp < res_up; xp++)
215 const int x2 = x + ox + xp;
216 const int y2 = y + oy + yp;
217 if (static_cast<unsigned int>(x2) >= map->info.width ||
218 static_cast<unsigned int>(y2) >= map->info.height)
221 auto& m = map->getCost(x2, y2, yaw);
229 for (
size_t yaw = 0; yaw < map->info.angle; yaw++)
231 for (
unsigned int i = 0; i < msg->data.size(); i++)
233 const int gx = lroundf((i % msg->info.width) * msg->info.resolution / map->info.linear_resolution) + ox;
234 const int gy = lroundf((i / msg->info.width) * msg->info.resolution / map->info.linear_resolution) + oy;
235 if ((
unsigned int)gx >= map->info.width ||
236 (
unsigned int)gy >= map->info.height)
239 auto val = msg->data[i];
247 const int x2 = gx +
x;
248 const int y2 = gy +
y;
249 if (static_cast<unsigned int>(x2) >= map->info.width ||
250 static_cast<unsigned int>(y2) >= map->info.height)
253 auto& m = map->getCost(x2, y2, yaw);
254 const auto c = cs_template_.
e(x, y, yaw) * val / 100;
265 #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
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)