Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030 #ifndef COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
00031 #define COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H
00032
00033 #include <geometry_msgs/PolygonStamped.h>
00034 #include <nav_msgs/OccupancyGrid.h>
00035 #include <costmap_cspace_msgs/CSpace3D.h>
00036 #include <costmap_cspace_msgs/CSpace3DUpdate.h>
00037
00038 #include <costmap_cspace/costmap_3d_layer/base.h>
00039
00040 namespace costmap_cspace
00041 {
00042 class Costmap3dLayerUnknownHandle : public Costmap3dLayerBase
00043 {
00044 public:
00045 using Ptr = std::shared_ptr<Costmap3dLayerUnknownHandle>;
00046
00047 protected:
00048 int8_t unknown_cost_;
00049
00050 public:
00051 Costmap3dLayerUnknownHandle()
00052 : unknown_cost_(-1)
00053 {
00054 }
00055 void loadConfig(XmlRpc::XmlRpcValue config)
00056 {
00057 if (config.hasMember("unknown_cost"))
00058 {
00059 unknown_cost_ = static_cast<int>(config["unknown_cost"]);
00060 }
00061 }
00062 void setMapMetaData(const costmap_cspace_msgs::MapMetaData3D& info)
00063 {
00064 }
00065
00066 protected:
00067 int getRangeMax() const
00068 {
00069 return 0;
00070 }
00071 bool updateChain(const bool output)
00072 {
00073 for (
00074 size_t a = region_.yaw_;
00075 static_cast<int>(a) < region_.yaw_ + region_.angle_ && a < map_->info.angle;
00076 ++a)
00077 {
00078 for (
00079 size_t y = region_.y_;
00080 static_cast<int>(y) < region_.y_ + region_.height_ && y < map_->info.height;
00081 ++y)
00082 {
00083 for (
00084 size_t x = region_.x_;
00085 static_cast<int>(x) < region_.x_ + region_.width_ && x < map_->info.width;
00086 ++x)
00087 {
00088 auto& m = map_overlay_->getCost(x, y, a);
00089 if (m < 0)
00090 m = unknown_cost_;
00091 }
00092 }
00093 }
00094 return false;
00095 }
00096 void updateCSpace(
00097 const nav_msgs::OccupancyGrid::ConstPtr& map,
00098 const UpdatedRegion& region)
00099 {
00100 }
00101 };
00102 }
00103
00104 #endif // COSTMAP_CSPACE_COSTMAP_3D_LAYER_UNKNOWN_HANDLE_H