30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H 33 #include <geometry_msgs/PolygonStamped.h> 34 #include <nav_msgs/OccupancyGrid.h> 35 #include <costmap_cspace_msgs/CSpace3D.h> 36 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 45 using Ptr = std::shared_ptr<Costmap3dLayerOutput>;
46 using Callback = boost::function<bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)>;
77 const nav_msgs::OccupancyGrid::ConstPtr& map,
83 costmap_cspace_msgs::CSpace3DUpdate::Ptr update_msg(
new costmap_cspace_msgs::CSpace3DUpdate);
84 update_msg->header =
map_->header;
92 update_width += update_x;
97 update_height += update_y;
100 if (update_x + update_width > static_cast<int>(
map_->info.width))
102 update_width =
map_->info.width - update_x;
104 if (update_y + update_height > static_cast<int>(
map_->info.height))
106 update_height =
map_->info.height - update_y;
116 region_merged.
merge(region_prev_);
117 region_prev_ = region;
120 update_msg->x = region_merged.
x_;
121 update_msg->y = region_merged.
y_;
122 update_msg->width = region_merged.
width_;
123 update_msg->height = region_merged.
height_;
124 update_msg->yaw = region_merged.
yaw_;
125 update_msg->angle = region_merged.
angle_;
126 update_msg->data.resize(update_msg->width * update_msg->height * update_msg->angle);
128 for (
int i = 0; i < static_cast<int>(update_msg->width); i++)
130 for (
int j = 0; j < static_cast<int>(update_msg->height); j++)
132 for (
int k = 0; k < static_cast<int>(update_msg->angle); k++)
134 const int x2 = update_msg->x + i;
135 const int y2 = update_msg->y + j;
136 const int yaw2 = update_msg->yaw + k;
138 const auto& m =
map_->getCost(x2, y2, yaw2);
139 const size_t addr = (k * update_msg->height + j) * update_msg->width + i;
141 auto& up = update_msg->data[addr];
151 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
boost::function< bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)> Callback
UpdatedRegion region_prev_
void merge(const UpdatedRegion ®ion)
costmap_cspace_msgs::CSpace3DUpdate::Ptr generateUpdateMsg()
void loadConfig(XmlRpc::XmlRpcValue config)
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
std::shared_ptr< Costmap3dLayerBase > Ptr
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion)
void setHandler(Callback cb)
bool updateChain(const bool output)