00001
00002 #ifndef LOADED_ShapeLandmarks_h
00003 #define LOADED_ShapeLandmarks_h
00004
00005 #include <vector>
00006 #include <string>
00007
00008 #include "Vision/colors.h"
00009
00010 #include "Shared/Measures.h"
00011 #include "DualCoding/ShapeRoot.h"
00012 #include "DualCoding/ShapeMarker.h"
00013 #include "DualCoding/ShapeAprilTag.h"
00014
00015 using namespace DualCoding;
00016
00017
00018 class PfRoot {
00019 public:
00020 int type;
00021 int id;
00022 rgb color;
00023 bool mobile;
00024 coordinate_t x, y;
00025 const ShapeRoot* link;
00026
00027 PfRoot(int _type, int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) :
00028 type(_type), id(_id), color(_color), mobile (_mobile), x(_x), y(_y),link(0) {}
00029
00030 virtual ~PfRoot() {}
00031
00032 virtual void print(std::ostream &os) const = 0;
00033
00034 void printRootInfo(std::ostream &os) const;
00035
00036 static void loadLms(const std::vector<ShapeRoot> &lms, bool isWorld, std::vector<PfRoot*>& landmarks);
00037
00038 static void deleteLms(std::vector<PfRoot*>& vec);
00039
00040 static void findBounds(const std::vector<PfRoot*> &map,
00041 coordinate_t &xmin, coordinate_t &ymin,
00042 coordinate_t &xmax, coordinate_t &ymax);
00043
00044 static void printLms(const std::vector<PfRoot*> &lmvec);
00045
00046 private:
00047 PfRoot(const PfRoot&);
00048 PfRoot& operator=(const PfRoot&);
00049 };
00050
00051
00052 class PfLine : public PfRoot {
00053 public:
00054 coordinate_t x2, y2;
00055 bool valid1, valid2;
00056 AngPi orientation;
00057 float length;
00058
00059 PfLine(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y,
00060 coordinate_t _x2, coordinate_t _y2, bool _v1, bool _v2) :
00061 PfRoot(lineDataType, _id, _color, _mobile, _x, _y),
00062 x2(_x2), y2(_y2), valid1(_v1), valid2(_v2), orientation(0), length(0) {}
00063
00064 virtual void print(std::ostream &os) const;
00065 };
00066
00067
00068 class PfEllipse : public PfRoot {
00069 public:
00070 PfEllipse(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) :
00071 PfRoot(ellipseDataType, _id, _color, _mobile, _x, _y) {}
00072
00073 virtual void print(std::ostream &os) const;
00074 };
00075
00076
00077 class PfPoint : public PfRoot {
00078 public:
00079 PfPoint(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) :
00080 PfRoot(pointDataType, _id, _color, _mobile, _x, _y) {}
00081
00082 virtual void print(std::ostream &os) const;
00083 };
00084
00085
00086 class PfBlob : public PfRoot {
00087 public:
00088 PfBlob(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) :
00089 PfRoot(blobDataType, _id, _color, _mobile, _x, _y) {}
00090
00091 virtual void print(std::ostream &os) const;
00092 };
00093
00094
00095 class PfMarker : public PfRoot {
00096 public:
00097 Shape<MarkerData> data;
00098
00099 PfMarker(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y, const Shape<MarkerData>& _data) :
00100 PfRoot(markerDataType, _id, _color, _mobile, _x, _y), data(_data) {}
00101
00102 virtual void print(std::ostream &os) const;
00103 };
00104
00105
00106 class PfAprilTag : public PfRoot {
00107 public:
00108 Shape<AprilTagData> data;
00109
00110 PfAprilTag(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y, const Shape<AprilTagData>& _data) :
00111 PfRoot(aprilTagDataType, _id, _color, _mobile, _x, _y), data(_data) {}
00112
00113 virtual void print(std::ostream &os) const;
00114 };
00115
00116 std::ostream& operator<<(std::ostream &os, const PfRoot &x);
00117
00118 #endif