Homepage Demos Overview Downloads Tutorials Reference
Credits

ParticleShapes.h

Go to the documentation of this file.
00001 //-*-c++-*-
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 "Measures.h"     // coordinate_t
00011 #include "ShapeRoot.h"
00012 
00013 namespace DualCoding {
00014 
00015 //! Root class for the particle filter landmark classes.
00016 class PfRoot {
00017  public:
00018   int type;
00019   int id;
00020   rgb color;
00021   coordinate_t x, y;
00022   const ShapeRoot* link;
00023 
00024   PfRoot(int _type, int _id, rgb _color, coordinate_t _x, coordinate_t _y) :
00025     type(_type), id(_id), color(_color), x(_x), y(_y), link(0) {}
00026     
00027   virtual ~PfRoot() {} //!< destructor, doesn't delete #link
00028 
00029   virtual void print(ostream &os) const = 0;
00030 
00031   void printRootInfo(ostream &os) const;
00032 
00033   static vector<PfRoot*>* loadLms(const vector<ShapeRoot> &lms, bool isWorld);
00034 
00035   static void deleteLms(vector<PfRoot*> *vec);
00036 
00037   static void findBounds(const vector<PfRoot*> &map, 
00038        coordinate_t &xmin, coordinate_t &ymin,
00039        coordinate_t &xmax, coordinate_t &ymax);
00040   
00041   static void printLms(const vector<PfRoot*> &lmvec);
00042 
00043 private:
00044   PfRoot(const PfRoot&); //!< don't call this
00045   PfRoot& operator=(const PfRoot&); //!< don't call this
00046 };
00047 
00048 //! A line landmark; world lines will have two of these, with the endpoints switched
00049 class PfLine : public PfRoot {
00050 public:
00051   coordinate_t x2, y2;
00052   bool valid1, valid2;
00053   AngPi orientation;
00054   float length;
00055 
00056   PfLine(int _id, rgb _color, coordinate_t _x, coordinate_t _y, 
00057    coordinate_t _x2, coordinate_t _y2, bool _v1, bool _v2) :
00058     PfRoot(lineDataType, _id, _color, _x, _y),
00059     x2(_x2), y2(_y2), valid1(_v1), valid2(_v2), orientation(0), length(0) {}
00060 
00061   virtual void print(ostream &os) const;
00062 };
00063 
00064 //! An ellipse landmark
00065 class PfEllipse : public PfRoot {
00066 public:
00067   PfEllipse(int _id, rgb _color, coordinate_t _x, coordinate_t _y) :
00068     PfRoot(ellipseDataType, _id, _color, _x, _y) {}
00069 
00070   virtual void print(ostream &os) const;
00071 };
00072 
00073 //! A point landmark
00074 class PfPoint : public PfRoot {
00075 public:
00076   PfPoint(int _id, rgb _color, coordinate_t _x, coordinate_t _y) :
00077     PfRoot(pointDataType, _id, _color, _x, _y) {}
00078 
00079   virtual void print(ostream &os) const;
00080 };
00081 
00082 //! A blob landmark
00083 class PfBlob : public PfRoot {
00084 public:
00085   PfBlob(int _id, rgb _color, coordinate_t _x, coordinate_t _y) :
00086     PfRoot(blobDataType, _id, _color, _x, _y) {}
00087 
00088   virtual void print(ostream &os) const;
00089 };
00090 
00091 ostream& operator<<(ostream &os, const PfRoot &x);
00092 
00093 } // namespace
00094 
00095 #endif

DualCoding 3.0beta
Generated Wed Oct 4 00:01:54 2006 by Doxygen 1.4.7