00001
00002
00003 #include <iostream>
00004 #include <vector>
00005 #include <fstream>
00006
00007 #include "DualCoding/ShapeRoot.h"
00008 #include "DualCoding/ShapeLine.h"
00009 #include "DualCoding/ShapeEllipse.h"
00010 #include "DualCoding/ShapeBlob.h"
00011 #include "DualCoding/ShapePoint.h"
00012
00013 #include "ShapeLandmarks.h"
00014
00015 using namespace std;
00016
00017 void PfRoot::loadLms(const std::vector<ShapeRoot> &lms, bool isWorld, std::vector<PfRoot*>& landmarks){
00018 int id;
00019 int type;
00020 rgb color;
00021 bool mobile;
00022 deleteLms(landmarks);
00023 landmarks.reserve(lms.size());
00024 for (unsigned int i = 0; i<lms.size(); i++){
00025 type = lms[i]->getType();
00026 color = lms[i]->getColor();
00027 mobile = lms[i]->getMobile();
00028 switch ( type ) {
00029 case lineDataType: {
00030 const Shape<LineData> &line = ShapeRootTypeConst(lms[i],LineData);
00031 id = line->getId();
00032 const EndPoint &pt1 = line->end1Pt();
00033 const EndPoint &pt2 = line->end2Pt();
00034 PfLine *land = new PfLine(id, color, mobile, pt1.coordX(), pt1.coordY(),
00035 pt2.coordX(), pt2.coordY(), pt1.isValid(), pt2.isValid());
00036 land->link = &lms[i];
00037 land->orientation = atan2(pt2.coordY()-pt1.coordY(), pt2.coordX()-pt1.coordX());
00038 land->length = sqrt((pt2.coordX()-pt1.coordX())*(pt2.coordX()-pt1.coordX()) +
00039 (pt2.coordY()-pt1.coordY())*(pt2.coordY()-pt1.coordY()));
00040 landmarks.push_back(land);
00041 if ( isWorld ) {
00042 PfLine *land2 = new PfLine(id, color, mobile, pt2.coordX(), pt2.coordY(),
00043 pt1.coordX(), pt1.coordY(), pt2.isValid(), pt1.isValid());
00044 land2->link = &lms[i];
00045 land2->orientation = land->orientation;
00046 land2->length = land->length;
00047 landmarks.push_back(land2);
00048 }
00049 }
00050 break;
00051 case ellipseDataType: {
00052 const Shape<EllipseData> &ellipse = ShapeRootTypeConst(lms[i],EllipseData);
00053 id = ellipse->getId();
00054 const Point &pt = ellipse->getCentroid();
00055 PfEllipse* land = new PfEllipse(id, color, mobile, pt.coordX(), pt.coordY());
00056 land->link = &lms[i];
00057 landmarks.push_back(land);
00058 }
00059 break;
00060 case pointDataType: {
00061 const Shape<PointData> &point = ShapeRootTypeConst(lms[i],PointData);
00062 id = point->getId();
00063 const Point &pt = point->getCentroid();
00064 PfPoint* land = new PfPoint(id, color, mobile, pt.coordX(), pt.coordY());
00065 land->link = &lms[i];
00066 landmarks.push_back(land);
00067 }
00068 break;
00069 case blobDataType: {
00070 const Shape<BlobData> &blob = ShapeRootTypeConst(lms[i],BlobData);
00071 id = blob->getId();
00072 Point pt = blob->getCentroid();
00073 PfBlob* land = new PfBlob(id, color, mobile, pt.coordX(), pt.coordY());
00074 land->link = &lms[i];
00075 landmarks.push_back(land);
00076 }
00077 break;
00078 case markerDataType: {
00079 const Shape<MarkerData> &marker = ShapeRootTypeConst(lms[i],MarkerData);
00080 id = marker->getId();
00081 Point pt = marker->getCentroid();
00082 PfMarker* land = new PfMarker(id, color, mobile, pt.coordX(), pt.coordY(), marker);
00083 land->link = &lms[i];
00084 landmarks.push_back(land);
00085 }
00086 break;
00087 case aprilTagDataType: {
00088 const Shape<AprilTagData> &tag = ShapeRootTypeConst(lms[i],AprilTagData);
00089 id = tag->getId();
00090 Point pt = tag->getCentroid();
00091 PfAprilTag* land = new PfAprilTag(id, color, mobile, pt.coordX(), pt.coordY(), tag);
00092 land->link = &lms[i];
00093 landmarks.push_back(land);
00094 }
00095 default:
00096 break;
00097 }
00098 }
00099 }
00100
00101 void PfRoot::deleteLms(std::vector<PfRoot*>& vec) {
00102 for ( unsigned int i = 0; i < vec.size(); i++ )
00103 delete vec[i];
00104 vec.clear();
00105 }
00106
00107 void PfRoot::findBounds(const std::vector<PfRoot*> &landmarks,
00108 coordinate_t &xmin, coordinate_t &ymin,
00109 coordinate_t &xmax, coordinate_t &ymax) {
00110 if ( landmarks.size() == 0 ) {
00111 cout << "Error in PFRoot::findBounds -- empty landmark vector" << endl;
00112 return;
00113 }
00114 xmin = xmax = landmarks[0]->x;
00115 ymin = ymax = landmarks[0]->y;
00116 for ( size_t i = 1; i<landmarks.size(); i++ ) {
00117 if ( (*landmarks[i]).x < xmin )
00118 xmin = landmarks[i]->x;
00119 else if ( landmarks[i]->x > xmax )
00120 xmax = landmarks[i]->x;
00121 if ( landmarks[i]->y < ymin )
00122 ymin = landmarks[i]->y;
00123 else if ( landmarks[i]->y > ymax )
00124 ymax = landmarks[i]->y;
00125 }
00126 }
00127
00128 void PfRoot::printLms(const std::vector<PfRoot*> &landmarks) {
00129 for (unsigned int i = 0; i<landmarks.size(); i++)
00130 cout << *landmarks[i] << endl;
00131 }
00132
00133 void PfRoot::printRootInfo(std::ostream &os) const {
00134 os << "id=" << id
00135 << ", x=" << x
00136 << ", y=" << y
00137 << ", mobile=" << mobile;
00138 }
00139
00140 ostream& operator<<(std::ostream &os, const PfRoot &obj) {
00141 obj.print(os);
00142 return os;
00143 }
00144
00145 void PfLine::print(std::ostream &os) const {
00146 os << "PfLine(";
00147 printRootInfo(os);
00148 os << ", x2=" << x2
00149 << ", y2=" << y2
00150 << ", length=" << length
00151 << ")";
00152 }
00153
00154 void PfEllipse::print(std::ostream &os) const {
00155 os << "PfEllipse(";
00156 printRootInfo(os);
00157 os << ")";
00158 }
00159
00160 void PfPoint::print(std::ostream &os) const {
00161 os << "PfPoint(";
00162 printRootInfo(os);
00163 os << ")";
00164 }
00165
00166 void PfBlob::print(std::ostream &os) const {
00167 os << "PfBlob(";
00168 printRootInfo(os);
00169 os << ")";
00170 }
00171
00172 void PfMarker::print(std::ostream &os) const {
00173 os << "PfMarker(";
00174 printRootInfo(os);
00175 os << ")";
00176 }
00177
00178 void PfAprilTag::print(std::ostream &os) const {
00179 os << "PfAprilTag(";
00180 printRootInfo(os);
00181 os << ")";
00182 }