30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
37 #include <costmap_cspace_msgs/CSpace3D.h>
38 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
39 #include <geometry_msgs/PolygonStamped.h>
40 #include <nav_msgs/OccupancyGrid.h>
46 template <
class CALLBACK>
50 using Ptr = std::shared_ptr<Costmap3dLayerOutput>;
74 const nav_msgs::OccupancyGrid::ConstPtr& map,
81 :
public Costmap3dLayerOutput<boost::function<bool(const typename costmap_cspace::CSpace3DMsg::Ptr&)>>
84 using Ptr = std::shared_ptr<Costmap3dStaticLayerOutput>;
96 :
public Costmap3dLayerOutput<boost::function<bool(const typename costmap_cspace::CSpace3DMsg::Ptr&,
97 const typename costmap_cspace_msgs::CSpace3DUpdate::Ptr&)>>
100 using Ptr = std::shared_ptr<Costmap3dUpdateLayerOutput>;
113 costmap_cspace_msgs::CSpace3DUpdate::Ptr update_msg(
new costmap_cspace_msgs::CSpace3DUpdate);
114 update_msg->header =
map_->header;
127 update_msg->x = region_merged.
x_;
128 update_msg->y = region_merged.
y_;
129 update_msg->width = region_merged.
width_;
130 update_msg->height = region_merged.
height_;
131 update_msg->yaw = region_merged.
yaw_;
132 update_msg->angle = region_merged.
angle_;
135 (update_msg->x + update_msg->width) *
136 (update_msg->y + update_msg->height) <=
137 map_->info.width *
map_->info.height);
141 update_msg->width = update_msg->height = 0;
145 update_msg->data.resize(update_msg->width * update_msg->height * update_msg->angle);
146 if ((update_msg->x == 0) && (update_msg->y == 0) && (update_msg->yaw == 0) &&
147 (update_msg->width ==
map_->info.width) && (update_msg->height ==
map_->info.height) &&
148 (update_msg->angle ==
map_->info.angle))
153 for (
unsigned int k = 0; k < update_msg->angle; ++k)
155 for (
unsigned int j = 0; j < update_msg->height; ++j)
158 *
map_, update_msg->x, update_msg->y + j, update_msg->yaw + k, update_msg->width);
166 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H