30 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H 31 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_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> 47 using Ptr = std::shared_ptr<Costmap3dLayerUnknownHandle>;
61 unknown_cost_ =
static_cast<int>(config[
"unknown_cost"]);
99 const nav_msgs::OccupancyGrid::ConstPtr& map,
106 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
CSpace3DMsg::Ptr map_overlay_
TFSIMD_FORCE_INLINE const tfScalar & y() const
void loadConfig(XmlRpc::XmlRpcValue config)
void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D &info)
TFSIMD_FORCE_INLINE const tfScalar & x() const
Costmap3dLayerUnknownHandle()
bool hasMember(const std::string &name) const
std::shared_ptr< Costmap3dLayerBase > Ptr
void updateCSpace(const nav_msgs::OccupancyGrid::ConstPtr &map, const UpdatedRegion ®ion)
bool updateChain(const bool output)