30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H 35 #include <costmap_cspace_msgs/CSpace3D.h> 36 #include <costmap_cspace_msgs/CSpace3DUpdate.h> 37 #include <geometry_msgs/PolygonStamped.h> 38 #include <nav_msgs/OccupancyGrid.h> 47 using Ptr = std::shared_ptr<Costmap3dLayerOutput>;
48 using Callback = boost::function<bool(const CSpace3DMsg::Ptr, const costmap_cspace_msgs::CSpace3DUpdate::Ptr)>;
79 const nav_msgs::OccupancyGrid::ConstPtr& map,
85 costmap_cspace_msgs::CSpace3DUpdate::Ptr update_msg(
new costmap_cspace_msgs::CSpace3DUpdate);
86 update_msg->header =
map_->header;
93 region_merged.
merge(region_prev_);
94 region_prev_ = region;
102 update_msg->x = region_merged.
x_;
103 update_msg->y = region_merged.
y_;
104 update_msg->width = region_merged.
width_;
105 update_msg->height = region_merged.
height_;
106 update_msg->yaw = region_merged.
yaw_;
107 update_msg->angle = region_merged.
angle_;
108 update_msg->data.resize(update_msg->width * update_msg->height * update_msg->angle);
109 if ((update_msg->x == 0) && (update_msg->y == 0) && (update_msg->yaw == 0) &&
110 (update_msg->width ==
map_->info.width) && (update_msg->height ==
map_->info.height) &&
111 (update_msg->angle ==
map_->info.angle))
116 for (
unsigned int k = 0; k < update_msg->angle; ++k)
118 for (
unsigned int j = 0; j < update_msg->height; ++j)
121 *
map_, update_msg->x, update_msg->y + j, update_msg->yaw + k, update_msg->width);
129 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_OUTPUT_H
void normalize(const int full_width, const int full_height)
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)
static void copyCells(CSpace3DMsg &to, const int &to_x, const int &to_y, const int &to_yaw, const CSpace3DMsg &from, const int &from_x, const int &from_y, const int &from_yaw, const int ©_cell_num)
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)