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