00001
00002 #include "Events/EventRouter.h"
00003 #include "Events/TextMsgEvent.h"
00004 #include "Events/LookoutEvents.h"
00005 #include "Motion/HeadPointerMC.h"
00006 #include "Motion/Kinematics.h"
00007 #include "Shared/mathutils.h"
00008 #include "Shared/Measures.h"
00009 #include "Shared/Config.h"
00010 #include "Shared/MarkScope.h"
00011
00012 #include "DualCoding/EllipseData.h"
00013 #include "DualCoding/SphereData.h"
00014 #include "DualCoding/BlobData.h"
00015 #include "DualCoding/PolygonData.h"
00016 #include "DualCoding/SphereData.h"
00017 #include "DualCoding/TargetData.h"
00018 #include "DualCoding/ShapeRoot.h"
00019 #include "DualCoding/ShapeLine.h"
00020 #include "DualCoding/ShapeEllipse.h"
00021 #include "DualCoding/ShapeBlob.h"
00022 #include "DualCoding/ShapePolygon.h"
00023 #include "DualCoding/ShapeSphere.h"
00024 #include "DualCoding/ShapeTarget.h"
00025 #include "DualCoding/ShapeMarker.h"
00026 #include "DualCoding/ShapeSift.h"
00027 #include "DualCoding/ShapeAprilTag.h"
00028 #include "DualCoding/Sketch.h"
00029 #include "DualCoding/visops.h"
00030 #include "DualCoding/VRmixin.h"
00031
00032 #include "Crew/LookoutRequests.h"
00033 #include "Crew/Lookout.h"
00034 #include "Crew/MapBuilder.h"
00035
00036 #include "Vision/SIFT/API/SiftTekkotsu.h"
00037 #include "Vision/AprilTags/TagDetector.h"
00038 #include "Vision/AprilTags/TagDetection.h"
00039
00040 using namespace std;
00041
00042 namespace DualCoding {
00043
00044 inline float distSq(const fmat::Column<4>& vec) {
00045 return vec[0]*vec[0] + vec[1]*vec[1] + vec[2]*vec[2];
00046 }
00047
00048 MapBuilder::MapBuilder() :
00049 BehaviorBase("MapBuilder"),
00050 camSkS(VRmixin::getCamSkS()), camShS(camSkS.getDualSpace()),
00051 groundShS(VRmixin::getGroundShS()),
00052 localSkS(VRmixin::getLocalSkS()), localShS(localSkS.getDualSpace()),
00053 worldSkS(VRmixin::getWorldSkS()), worldShS(worldSkS.getDualSpace()),
00054 xres(camSkS.getWidth()), yres(camSkS.getHeight()),
00055 ground_plane(),
00056 theAgent(VRmixin::theAgent),
00057 localToWorldMatrix(fmat::Transform::identity()),
00058 worldToLocalTranslateMatrix(fmat::Transform::identity()),
00059 worldToLocalRotateMatrix(fmat::Transform::identity()),
00060 badGazePoints(),
00061 requests(), curReq(NULL), idCounter(0), maxDistSq(0), siftMatchers(),
00062 pointAtID(Lookout::invalid_LO_ID), scanID(Lookout::invalid_LO_ID),
00063 nextGazePoint() {}
00064
00065 void MapBuilder::preStart() {
00066 BehaviorBase::preStart();
00067 if ( verbosity & MBVstart )
00068 cout << "MapBuilder::start()\n";
00069
00070 camSkS.clear(); camShS.clear();
00071 groundShS.clear();
00072 localSkS.clear(); localShS.clear();
00073 worldSkS.clear(); worldShS.clear();
00074 badGazePoints.clear();
00075
00076 erouter->addListener(this,EventBase::textmsgEGID);
00077 erouter->addListener(this,EventBase::lookoutEGID);
00078 }
00079
00080 bool MapBuilder::retain = true;
00081
00082 MapBuilder::MapBuilderVerbosity_t MapBuilder::verbosity = (-1U & ~(MBVevents | MBVcomplete | MBVgroundPlane));
00083
00084
00085
00086
00087
00088
00089
00090
00091 void MapBuilder::stop() {
00092 cout << "MapBuilder::stop()\n";
00093 while(!requests.empty()) {
00094 delete requests.front();
00095 requests.pop();
00096 }
00097 curReq = NULL;
00098 BehaviorBase::stop();
00099 }
00100
00101 void MapBuilder::executeRequest(BehaviorBase *requestingBehavior, const MapBuilderRequest &req) {
00102 MapBuilderRequest newreq(req);
00103 newreq.requestingBehavior = requestingBehavior;
00104 executeRequest(newreq);
00105 }
00106
00107 unsigned int MapBuilder::executeRequest(const MapBuilderRequest& req, unsigned int *req_id) {
00108 MapBuilderRequest *newreq = new MapBuilderRequest(req);
00109 if ( !newreq->validateRequest() ) {
00110 cout << "*** Request rejected by MapBuilder" << endl;
00111 return 0;
00112 }
00113 const unsigned int this_request = ++idCounter;
00114 newreq->requestID = this_request;
00115 if ( req_id != NULL ) *req_id = this_request;
00116 requests.push(newreq);
00117 executeRequest();
00118 return this_request;
00119 }
00120
00121 void MapBuilder::executeRequest() {
00122 if ( curReq != NULL || requests.empty() ) return;
00123 curReq = requests.front();
00124 curReq->verbosity = (verbosity & ~curReq->clearVerbosity) | curReq->setVerbosity;
00125 if ( curReq->verbosity & MBVexecute )
00126 cout << "MapBuilder::executeRequest: execute " << curReq->requestID << endl;
00127 erouter->postEvent(EventBase::mapbuilderEGID, curReq->requestID, EventBase::activateETID,0);
00128
00129 calculateGroundPlane();
00130 maxDistSq = curReq->maxDist*curReq->maxDist;
00131
00132 if ( curReq->clearCamera ) {
00133 camShS.clear();
00134 camSkS.clear();
00135 curReq->gazePts.clear();
00136 curReq->baseToCamMats.clear();
00137 }
00138 if ( curReq->clearLocal ) {
00139 localShS.clear();
00140 localSkS.clear();
00141 }
00142 if ( curReq->clearWorld ) {
00143 worldShS.clear();
00144 worldSkS.clear();
00145 }
00146
00147 if ( curReq->immediateRequest )
00148 grabCameraImageAndGo();
00149 else if ( !curReq->searchArea.isValid() && curReq->worldTargets.size() == 0 )
00150 storeImage(false);
00151 else {
00152 defineGazePts();
00153 if ( curReq->doScan == true )
00154 return;
00155 else if ( curReq->worldTargets.size() > 0 )
00156 doNextSearch();
00157 else if ( determineNextGazePoint() )
00158 moveToNextGazePoint();
00159 else
00160 requestComplete();
00161 }
00162 }
00163
00164
00165
00166
00167
00168
00169
00170
00171
00172
00173
00174
00175
00176
00177
00178
00179
00180 void MapBuilder::doEvent() {
00181 if ( curReq == NULL) return;
00182 if ( curReq->verbosity & MBVevents )
00183 cout << "MapBuilder got event " << event->getName() << endl;
00184
00185 switch ( event->getGeneratorID() ) {
00186 case EventBase::textmsgEGID:
00187 if ( strcmp(dynamic_cast<const TextMsgEvent&>(*event).getText().c_str(),"MoveHead") == 0 )
00188 moveToNextGazePoint(true);
00189 break;
00190
00191 case EventBase::lookoutEGID:
00192 if ( event->getSourceID() == pointAtID )
00193 processImage(dynamic_cast<const LookoutSketchEvent&>(*event));
00194 else if ( event->getSourceID() == scanID ) {
00195 const vector<Point>& pts = dynamic_cast<const LookoutScanEvent*>(event)->getTasks().front()->data;
00196 cout << " doScan found " << pts.size() << " interest points." << endl;
00197 curReq->gazePts.insert(curReq->gazePts.end(),pts.begin(), pts.end());
00198 }
00199 else {
00200 cout << "MapBuilder: unexpected Lookout event " << event->getDescription()
00201 << ", current pointAtID=" << pointAtID << ", scanID=" << scanID << endl;
00202 return;
00203 }
00204
00205 if ( requestExitTest() )
00206 requestComplete();
00207 else if ( curReq->worldTargets.size() > 0 )
00208 doNextSearch();
00209 else if ( determineNextGazePoint() )
00210 moveToNextGazePoint();
00211 else
00212 requestComplete();
00213 break;
00214
00215 default:
00216 cout << "MapBuilder received unexpected event: " << event->getDescription() << endl;
00217 }
00218 }
00219
00220 void MapBuilder::processImage(const LookoutSketchEvent &e) {
00221 if ( curReq->clearCamera ) {
00222 camSkS.clear(false);
00223 camShS.clear();
00224 }
00225 if ( curReq->rawY ) {
00226 NEW_SKETCH(rawY, uchar, VRmixin::sketchFromRawY());
00227 }
00228 NEW_SKETCH(camFrame, uchar, e.getSketch());
00229 if (curReq->userImageProcessing != NULL) (*curReq->userImageProcessing)();
00230 const fmat::Transform& camToBase = curReq->baseTransform * e.toBaseMatrix;
00231 const fmat::Transform baseToCam = camToBase.rigidInverse();
00232 getCameraShapes(camFrame);
00233 if (curReq->userCamProcessing != NULL) (*curReq->userCamProcessing)();
00234 if (curReq->getRequestType() > MapBuilderRequest::cameraMap) {
00235 projectToGround(camToBase);
00236 if (curReq->userGroundProcessing != NULL) (*curReq->userGroundProcessing)();
00237 filterGroundShapes(baseToCam);
00238 }
00239 switch ( curReq->getRequestType() ) {
00240 case MapBuilderRequest::cameraMap:
00241 case MapBuilderRequest::groundMap:
00242 break;
00243 case MapBuilderRequest::localMap:
00244 extendLocal(baseToCam);
00245 if (curReq->userLocalProcessing != NULL) (*curReq->userLocalProcessing)();
00246 break;
00247 case MapBuilderRequest::worldMap:
00248 extendLocal(baseToCam);
00249 if (curReq->userLocalProcessing != NULL) (*curReq->userLocalProcessing)();
00250 extendWorld(baseToCam);
00251 if (curReq->userWorldProcessing != NULL) (*curReq->userWorldProcessing)();
00252 }
00253 }
00254
00255 bool MapBuilder::determineNextGazePoint() {
00256 if (curReq->getRequestType() == MapBuilderRequest::worldMap) {
00257 worldShS.applyTransform(worldToLocalTranslateMatrix,egocentric);
00258 worldShS.applyTransform(worldToLocalRotateMatrix,egocentric);
00259 bool b = determineNextGazePoint(worldShS.allShapes()) || determineNextGazePoint(curReq->gazePts);
00260 worldShS.applyTransform(localToWorldMatrix,allocentric);
00261 return b;
00262 }
00263 else
00264 return determineNextGazePoint(localShS.allShapes()) || determineNextGazePoint(curReq->gazePts);
00265 }
00266
00267
00268 bool MapBuilder::determineNextGazePoint(const vector<ShapeRoot>& shapes) {
00269 if ( ! curReq->pursueShapes ) return false;
00270 HeadPointerMC headpointer_mc;
00271 for (vector<ShapeRoot>::const_iterator it = shapes.begin();
00272 it != shapes.end(); it++) {
00273
00274 if ((*it)->isType(lineDataType) || (*it)->isType(polygonDataType)) {
00275 const Shape<LineData>& ld = ShapeRootTypeConst(*it,LineData);
00276 const Shape<PolygonData>& pd = ShapeRootTypeConst(*it,PolygonData);
00277 bool isLine = (*it)->isType(lineDataType);
00278 EndPoint p[2] = { isLine ? ld->end1Pt(): pd->end1Pt(), isLine ? ld->end2Pt() : pd->end2Pt()};
00279 for (int i = 0; i < 2; i++) {
00280 if ( !p[i].isValid() && !isBadGazePoint(p[i] )
00281 && badGazePoints.end() == find(badGazePoints.begin(), badGazePoints.end(), (Point) p[i])) {
00282 cout << "Take image at endpoint" << (i+1) << " of shape id "
00283 << (*it)->getId() << " at " << p[i] << endl;
00284 if ( !headpointer_mc.lookAtPoint(p[i].coordX(),p[i].coordY(),p[i].coordZ()) ) {
00285 if ( curReq->verbosity & MBVbadGazePoint )
00286 cout << "MapBuilder noting unreachable gaze point " << (Point)p[i] << endl;
00287 badGazePoints.push_back((Point)p[i]);
00288 }
00289 nextGazePoint = p[i];
00290 return true;
00291 }
00292 }
00293 }
00294
00295 if ((!(*it)->isType(agentDataType)) &&
00296 (*it)->getLastMatchId() != 0 &&
00297 (*it)->getConfidence() <= 1 &&
00298 ! isBadGazePoint((*it)->getCentroid()) &&
00299 badGazePoints.end() == find(badGazePoints.begin(), badGazePoints.end(), (*it)->getCentroid())) {
00300 const Point pt = (*it)->getCentroid();
00301 cout << "take image at shape " << (*it)
00302 << " (confidence level: " << (*it)->getConfidence() << ")" << endl;
00303 cout << " at " << pt << endl;
00304 if (! headpointer_mc.lookAtPoint(pt.coordX(),pt.coordY(),pt.coordZ()))
00305 badGazePoints.push_back(pt);
00306 nextGazePoint = pt;
00307 return true;
00308 }
00309
00310
00311 }
00312 return false;
00313 }
00314
00315
00316 bool MapBuilder::determineNextGazePoint(vector<Point>& gazePts) {
00317 for ( vector<Point>::iterator it = gazePts.begin();
00318 it != gazePts.end(); it = gazePts.erase(it) )
00319 if ( ! isBadGazePoint(*it) ) {
00320 nextGazePoint = *it;
00321 return true;
00322 }
00323 return false;
00324 }
00325
00326 void MapBuilder::moveToNextGazePoint(const bool manualOverride) {
00327 if ( curReq == NULL ) {
00328 cout << "curReq == NULL in moveToNextGazePoint!" << endl;
00329 return;
00330 }
00331 if ( (curReq->verbosity & MBVnextGazePoint) || (curReq->manualHeadMotion && manualOverride==false) )
00332 cout << "moveToNextGazePoint " << nextGazePoint << endl;
00333 if ( curReq->manualHeadMotion && manualOverride==false ) {
00334 cout << "To proceed to this gaze point: !msg MoveHead" << endl;
00335 return;
00336 }
00337 else
00338 storeImage(true);
00339 }
00340
00341
00342 void MapBuilder::doNextSearch() {
00343 LookoutSearchRequest *curLSR = curReq->worldTargets.front();
00344 curReq->worldTargets.pop();
00345 pointAtID = VRmixin::lookout->executeRequest(*curLSR);
00346 }
00347
00348 bool MapBuilder::isBadGazePoint(const Point& Pt) const {
00349 const coordinate_t x = Pt.coordX();
00350 const coordinate_t y = Pt.coordY();
00351 return ( x*x + y*y > maxDistSq || x < -30.0);
00352 }
00353
00354 void MapBuilder::storeImage(bool useNextGazePoint) {
00355 LookoutPointRequest lreq;
00356 lreq.motionSettleTime = curReq->motionSettleTime;
00357 lreq.numSamples = curReq->numSamples;
00358 lreq.sampleInterval = curReq->sampleInterval;
00359 if ( useNextGazePoint )
00360 lreq.setTarget(nextGazePoint);
00361 else
00362 lreq.setHeadMotionType(LookoutRequest::noMotion);
00363 pointAtID = VRmixin::lookout->executeRequest(lreq);
00364 }
00365
00366 void MapBuilder::grabCameraImageAndGo() {
00367
00368
00369
00370
00371 pointAtID = 0;
00372 Sketch<uchar> camFrame(VRmixin::sketchFromSeg());
00373 #ifdef TGT_HAS_CAMERA
00374 const fmat::Transform camToBase = kine->linkToBase(CameraFrameOffset);
00375 #else
00376 const fmat::Transform &camToBase = fmat::Transform::identity();
00377 #endif
00378 LookoutSketchEvent dummy(true, camFrame, camToBase,
00379 EventBase::lookoutEGID, pointAtID, EventBase::deactivateETID);
00380 processImage(dummy);
00381 requestComplete();
00382 }
00383
00384 void MapBuilder::scanForGazePts() {
00385 LookoutScanRequest lreq;
00386 lreq.searchArea = curReq->searchArea;
00387 lreq.motionSettleTime = curReq->motionSettleTime;
00388 set<color_index> colors;
00389 for (map<ShapeType_t,set<color_index> >::const_iterator it1 = curReq->objectColors.begin();
00390 it1 != curReq->objectColors.end(); it1++)
00391 for (set<color_index>::const_iterator it2 = it1->second.begin();
00392 it2 != it1->second.end(); it2++)
00393 colors.insert(*it2);
00394 lreq.addTask(LookoutScanRequest::VisionRegionTask(colors,curReq->dTheta));
00395 scanID = VRmixin::lookout->executeRequest(lreq);
00396 }
00397
00398 void MapBuilder::extendLocal(const fmat::Transform& baseToCam) {
00399 vector<ShapeRoot> all = localShS.allShapes();
00400 removeNoise(localShS, baseToCam);
00401 matchSrcToDst(groundShS,localShS,curReq->objectColors[polygonDataType]);
00402
00403
00404
00405
00406 if ( curReq->gazePts.size() > 0 )
00407 curReq->gazePts.erase(curReq->gazePts.begin());
00408 curReq->baseToCamMats.push_back(baseToCam);
00409 }
00410
00411 void MapBuilder::extendWorld(const fmat::Transform& baseToCam) {
00412 worldShS.applyTransform(worldToLocalTranslateMatrix,egocentric);
00413 worldShS.applyTransform(worldToLocalRotateMatrix,egocentric);
00414 removeNoise(worldShS, baseToCam);
00415 matchSrcToDst(localShS,worldShS,curReq->objectColors[polygonDataType]);
00416 worldShS.applyTransform(localToWorldMatrix,allocentric);
00417 removeGazePts(curReq->gazePts,baseToCam);
00418 curReq->baseToCamMats.push_back(baseToCam);
00419 }
00420
00421 bool MapBuilder::requestExitTest() {
00422 if ( curReq->exitTest == NULL )
00423 return false;
00424 else
00425 return (*curReq->exitTest)();
00426 }
00427
00428 void MapBuilder::requestComplete() {
00429 const size_t reqID = curReq->requestID;
00430 if ( curReq->verbosity & MBVcomplete )
00431 cout << "MapBuilderRequest " << reqID << " complete\n";
00432 BehaviorBase* reqbeh = curReq->requestingBehavior;
00433 delete curReq;
00434 curReq = NULL;
00435 requests.pop();
00436 if ( reqbeh )
00437 erouter->postEvent(EventBase::mapbuilderEGID, (size_t)reqbeh, EventBase::statusETID,0);
00438 else {
00439 erouter->postEvent(EventBase::mapbuilderEGID, reqID, EventBase::statusETID,0);
00440 erouter->postEvent(EventBase::mapbuilderEGID, reqID, EventBase::deactivateETID,0);
00441 }
00442 if ( requests.empty() )
00443 VRmixin::lookout->relax();
00444 else
00445 executeRequest();
00446 }
00447
00448 void MapBuilder::setAgent(const Point &worldLocation, const AngTwoPi worldHeading, bool quiet) {
00449 if ( !quiet && ((curReq==NULL ? verbosity : curReq->verbosity) & MBVsetAgent) )
00450 cout << "Agent now at " << worldLocation << " hdg " << worldHeading
00451 << " (= " << float(worldHeading)*180/M_PI << " deg.)" << endl;
00452 theAgent->setCentroidPt(worldLocation);
00453 theAgent->setOrientation(worldHeading);
00454 const coordinate_t dx = worldLocation.coordX();
00455 const coordinate_t dy = worldLocation.coordY();
00456 const coordinate_t dz = worldLocation.coordZ();
00457 float const c = cos(worldHeading);
00458 float const s = sin(worldHeading);
00459 float localToWorld[] = {c, -s, 0, dx,
00460 s, c, 0, dy,
00461 0, 0, 1, dz};
00462 float worldToLocalTrans[] = {1, 0, 0, -dx,
00463 0, 1, 0, -dy,
00464 0, 0, 1, -dz};
00465 float worldToLocalRotate[] = { c, s, 0, 0,
00466 -s, c, 0, 0,
00467 0, 0, 1, 0};
00468 localToWorldMatrix = fmat::Matrix<4,3>(localToWorld).transpose();;
00469 worldToLocalTranslateMatrix = fmat::Matrix<4,3>(worldToLocalTrans).transpose();
00470 worldToLocalRotateMatrix = fmat::Matrix<4,3>(worldToLocalRotate).transpose();
00471 }
00472
00473 void MapBuilder::moveAgent(coordinate_t const local_dx, coordinate_t const local_dy, coordinate_t const local_dz, AngSignPi dtheta) {
00474 Point const agentLoc = theAgent->getCentroid();
00475 AngTwoPi const heading = theAgent->getOrientation();
00476 float const c = cos(heading);
00477 float const s = sin(heading);
00478 float const dx = local_dx*c + local_dy*-s;
00479 float const dy = local_dx*s + local_dy*c;
00480 setAgent(agentLoc + Point(dx,dy,local_dz,allocentric), heading+dtheta);
00481 }
00482
00483 void MapBuilder::importLocalToWorld() {
00484 worldShS.applyTransform(worldToLocalTranslateMatrix,egocentric);
00485 worldShS.applyTransform(worldToLocalRotateMatrix,egocentric);
00486 matchSrcToDst(localShS,worldShS);
00487 worldShS.applyTransform(localToWorldMatrix,allocentric);
00488 }
00489
00490 ShapeRoot MapBuilder::importLocalShapeToWorld(const ShapeRoot &localShape) {
00491 ShapeRoot worldShape(worldShS.importShape(localShape));
00492 worldShape->applyTransform(localToWorldMatrix, allocentric);
00493 return worldShape;
00494 }
00495
00496 ShapeRoot MapBuilder::importWorldToLocal(const ShapeRoot &worldShape) {
00497 ShapeRoot localShape(localShS.importShape(worldShape));
00498 localShape->applyTransform(worldToLocalTranslateMatrix,egocentric);
00499 localShape->applyTransform(worldToLocalRotateMatrix,egocentric);
00500 return localShape;
00501 }
00502
00503 bool MapBuilder::isPointVisible(const Point &pt, const fmat::Transform& baseToCam, float maxDistanceSq) {
00504 fmat::Column<3> camCoords = baseToCam*fmat::pack(pt.coordX(),pt.coordY(),pt.coordZ());
00505
00506 if ( fmat::SubVector<2>(camCoords).sumSq() >= maxDistanceSq )
00507 return false;
00508 float normX,normY;
00509 config->vision.computePixel(camCoords[0],camCoords[1],camCoords[2],normX,normY);
00510 return (fabs(normX) < 0.9f && fabs(normY) < config->vision.aspectRatio*.9f);
00511 }
00512
00513 bool MapBuilder::isLineVisible(const LineData& ln, const fmat::Transform& baseToCam) {
00514 float normX1,normX2,normY1,normY2;
00515 fmat::Column<3> camCoords;
00516 Point pt = ln.end1Pt();
00517 camCoords = baseToCam*fmat::pack(pt.coordX(),pt.coordY(),pt.coordZ());
00518 config->vision.computePixel(camCoords[0],camCoords[1],camCoords[2],normX1,normY1);
00519 pt = ln.end2Pt();
00520 camCoords = baseToCam*fmat::pack(pt.coordX(),pt.coordY(),pt.coordZ());
00521 config->vision.computePixel(camCoords[0],camCoords[1],camCoords[2],normX2,normY2);
00522 const float xRange = 0.9f;
00523 const float yRange = config->vision.aspectRatio*.9f;
00524 const bool end1Pt_visible = fabs(normX1) < xRange && fabs(normY1) < yRange;
00525 const bool end2Pt_visible = fabs(normX2) < xRange && fabs(normY2) < yRange;
00526 if (end1Pt_visible && end2Pt_visible)
00527 return true;
00528 LineData lnCam(VRmixin::groundShS, Point(normX1,normY1), Point(normX2,normY2));
00529
00530 LineData camBounds[] = {LineData(VRmixin::groundShS, Point( xRange, yRange), Point( xRange,-yRange)),
00531 LineData(VRmixin::groundShS, Point( xRange,-yRange), Point(-xRange,-yRange)),
00532 LineData(VRmixin::groundShS, Point(-xRange,-yRange), Point(-xRange, yRange)),
00533 LineData(VRmixin::groundShS, Point(-xRange, yRange), Point( xRange, yRange))};
00534 unsigned int ptCount = 0;
00535 Point p[2];
00536
00537 if (end1Pt_visible) p[ptCount++].setCoords(normX1,normY1,0);
00538 else if (end2Pt_visible) p[ptCount++].setCoords(normX2,normY2,0);
00539 for (int i = 0; i < 4; i++)
00540 if (camBounds[i].intersectsLine(lnCam)) {
00541 p[ptCount++].setCoords(lnCam.intersectionWithLine(camBounds[i]));
00542
00543 if (ptCount > 1)
00544 return p[0].distanceFrom(p[1]) > 0.1;
00545 }
00546 return false;
00547 }
00548
00549 bool MapBuilder::isShapeVisible(const ShapeRoot &ground_shape, const fmat::Transform& baseToCam,
00550 float maxDistanceSq) {
00551 if (ground_shape->isType(lineDataType))
00552 return isLineVisible(ShapeRootTypeConst(ground_shape,LineData).getData(), baseToCam);
00553 else if (ground_shape->isType(polygonDataType)) {
00554 const Shape<PolygonData>& polygon = ShapeRootTypeConst(ground_shape,PolygonData);
00555 for (vector<LineData>::const_iterator edge_it = polygon->getEdges().begin();
00556 edge_it != polygon->getEdges().end(); edge_it++)
00557 if (isLineVisible(*edge_it,baseToCam))
00558 return true;
00559 return false;
00560 }
00561 else
00562 return isPointVisible(ground_shape->getCentroid(), baseToCam, maxDistanceSq);
00563 }
00564
00565
00566
00567
00568
00569 void MapBuilder::filterGroundShapes(const fmat::Transform& baseToCam) {
00570
00571 vector<ShapeRoot> ground_shapes = groundShS.allShapes();
00572
00573 for (vector<ShapeRoot>::iterator ground_it = ground_shapes.begin();
00574 ground_it != ground_shapes.end(); ground_it++ ) {
00575 const coordinate_t cenX = (*ground_it)->getCentroid().coordX();
00576 const coordinate_t cenY = (*ground_it)->getCentroid().coordY();
00577 if (cenX*cenX + cenY*cenY > maxDistSq) {
00578 if ( curReq->verbosity & MBVnotAdmissible )
00579 cout << "ground shape " << (*ground_it)->getId() << " (lastMatch "
00580 << (*ground_it)->getLastMatchId() << ") too far, delete\n";
00581 ground_it->deleteShape();
00582 }
00583 fmat::Column<3> coords = Kinematics::pack(cenX,cenY,(*ground_it)->getCentroid().coordZ());
00584 coords = baseToCam*coords;
00585 if (coords[2] < 0) {
00586 if ( curReq->verbosity & MBVprojectionFailed )
00587 cout << "Projection failed for ground shape " << (*ground_it)->getId()
00588 << ": " << coords
00589 << " (lastMatch " << (*ground_it)->getLastMatchId() << "): deleting\n";
00590 ground_it->deleteShape();
00591 }
00592
00593 else if ((*ground_it)->isType(lineDataType)) {
00594 Shape<LineData>& line = ShapeRootType(*ground_it,LineData);
00595 const coordinate_t e1x = line->end1Pt().coordX();
00596 const coordinate_t e1y = line->end1Pt().coordY();
00597 const coordinate_t e2x = line->end2Pt().coordX();
00598 const coordinate_t e2y = line->end2Pt().coordY();
00599 if (e1x*e1x + e1y*e1y > maxDistSq && e2x*e2x + e2y*e2y > maxDistSq)
00600 ground_it->deleteShape();
00601 else if (e1x*e1x + e1y*e1y > maxDistSq || e2x*e2x + e2y*e2y > maxDistSq) {
00602
00603
00604 vector<float> line_abc = line->lineEquation_abc();
00605 Point pt;
00606 const EndPoint* far_ept = (e1x*e1x + e1y*e1y > maxDistSq) ? &line->end1Pt() : &line->end2Pt();
00607 if (line_abc[1] == 0.0) {
00608 const coordinate_t y_abs = sqrt(maxDistSq - line_abc[2]*line_abc[2]);
00609 if (fabs(far_ept->coordY()-y_abs) < fabs(far_ept->coordY()+y_abs))
00610 pt.setCoords(e1x, y_abs, far_ept->coordZ());
00611 else
00612 pt.setCoords(e1x, -y_abs, far_ept->coordZ());
00613 }
00614 else {
00615 const float a = - line_abc[0]/line_abc[1];
00616 const float b = line_abc[2]/line_abc[1];
00617 const coordinate_t x1 = (std::sqrt((a*a+1)*maxDistSq-b*b)-a*b)/(a*a+1);
00618 const coordinate_t x2 = (-std::sqrt((a*a+1)*maxDistSq-b*b)-a*b)/(a*a+1);
00619 if (std::abs(far_ept->coordX()-x1) < std::abs(far_ept->coordX()-x2))
00620 pt.setCoords(x1, a*x1+b, far_ept->coordZ());
00621 else
00622 pt.setCoords(x2, a*x2+b, far_ept->coordZ());
00623 }
00624 EndPoint temp_endPt(pt);
00625 temp_endPt.setValid(false);
00626
00627
00628 if (e1x*e1x + e1y*e1y > maxDistSq)
00629 line->setEndPts(temp_endPt, line->end2Pt());
00630 else
00631 line->setEndPts(line->end1Pt(), temp_endPt);
00632 badGazePoints.push_back(pt);
00633 }
00634 }
00635 }
00636 }
00637
00638 void MapBuilder::calculateGroundPlane() {
00639 switch(curReq->groundPlaneAssumption) {
00640 case MapBuilderRequest::onLegs:
00641 ground_plane = kine->calculateGroundPlane();
00642 if ( curReq->verbosity & MBVgroundPlane )
00643 cout << "Calculated ground plane: " << ground_plane << endl;
00644 break;
00645 case MapBuilderRequest::onStand:
00646 #if defined(TGT_ERS210) || defined(TGT_ERS220) || defined(TGT_ERS2xx)
00647 ground_plane = PlaneEquation(0,0,-1,200);
00648 #else
00649 ground_plane = PlaneEquation(0,0,-1,170);
00650 #endif
00651
00652 break;
00653 case MapBuilderRequest::onWheel:
00654 #ifdef TGT_REGIS1
00655 std::cout << "Target Regis 1 Mapping";
00656 ground_plane = fmat::pack<float>(0,0,(-1/85.0),1);
00657 #endif
00658 break;
00659 case MapBuilderRequest::custom:
00660 ground_plane = curReq->customGroundPlane;
00661 }
00662 }
00663
00664 void MapBuilder::projectToGround(const fmat::Transform& camToBase) {
00665 VRmixin::projectToGround(camToBase, ground_plane);
00666 }
00667
00668 ShapeRoot MapBuilder::projectToLocal(ShapeRoot &shape) {
00669 #ifdef TGT_HAS_CAMERA
00670 fmat::Transform camToBase = kine->linkToBase(CameraFrameOffset);
00671 #else
00672 fmat::Transform camToBase = fmat::Transform::identity();
00673 #endif
00674 ground_plane = kine->calculateGroundPlane();
00675
00676 groundShS.importShape(shape);
00677 ShapeRoot &newShape = groundShS.allShapes().back();
00678 newShape->projectToGround(camToBase, ground_plane);
00679 localShS.importShape(newShape);
00680 return localShS.allShapes().back();
00681 }
00682
00683 void MapBuilder::matchSrcToDst(ShapeSpace &srcShS, ShapeSpace &dstShS,
00684 set<color_index> polCols, bool mergeSrc, bool mergeDst) {
00685 vector<ShapeRoot> src_shapes = srcShS.allShapes();
00686 vector<ShapeRoot> dst_shapes = dstShS.allShapes();
00687 vector<LineData> polygon_edges;
00688
00689
00690 std::set<int> markedForDeletion;
00691 vector<ShapeRoot> cleaned_src;
00692 for (vector<ShapeRoot>::iterator src_it = src_shapes.begin();
00693 src_it != src_shapes.end(); src_it++ ) {
00694 if (!(*src_it)->isAdmissible()) {
00695 if (curReq && curReq->verbosity & MBVnotAdmissible )
00696 cout << "shape " << (*src_it)->getId() << " (lastMatch "
00697 << (*src_it)->getLastMatchId() << ") is not admissible." << endl;
00698
00699 markedForDeletion.insert((*src_it)->getId());
00700 }
00701 else if ((*src_it)->isType(polygonDataType)) {
00702 const vector<LineData>& lines = ShapeRootTypeConst(*src_it, PolygonData)->getEdges();
00703 polygon_edges.insert(polygon_edges.end(), lines.begin(), lines.end());
00704 markedForDeletion.insert((*src_it)->getId());
00705 }
00706 else if ((*src_it)->isType(lineDataType)) {
00707 const color_index colorIndex = ProjectInterface::getColorIndex((*src_it)->getColor());
00708 if ( polCols.end() != find(polCols.begin(), polCols.end(), colorIndex)) {
00709 polygon_edges.push_back(ShapeRootTypeConst(*src_it, LineData).getData());
00710 markedForDeletion.insert((*src_it)->getId());
00711 }
00712 }
00713 }
00714
00715 for ( vector<ShapeRoot>::iterator it = src_shapes.begin();
00716 it != src_shapes.end(); it++ )
00717 if ( markedForDeletion.find((*it)->getId()) == markedForDeletion.end() )
00718 cleaned_src.push_back(*it);
00719 src_shapes = cleaned_src;
00720
00721
00722 if (mergeSrc) {
00723 markedForDeletion.clear();
00724 cleaned_src.clear();
00725 for ( vector<ShapeRoot>::iterator it = src_shapes.begin();
00726 it != src_shapes.end(); it++ )
00727 for ( vector<ShapeRoot>::iterator it2 = it+1;
00728 it2 != src_shapes.end(); it2++)
00729 if ((*it2)->isMatchFor(*it) && (*it)->updateParams(*it2)) {
00730 if (curReq && curReq->verbosity & MBVshapesMerge )
00731 cout << "merging shape " << (*it)->getId() << " (from " << (*it)->getLastMatchId()
00732 << ") and shape " << (*it2)->getId() << " (from " << (*it2)->getLastMatchId() << ")" << endl;
00733 markedForDeletion.insert((*it2)->getId());
00734 }
00735
00736 for ( vector<ShapeRoot>::iterator it = src_shapes.begin();
00737 it != src_shapes.end(); it++ )
00738 if ( markedForDeletion.find((*it)->getId()) == markedForDeletion.end() )
00739 cleaned_src.push_back(*it);
00740 src_shapes = cleaned_src;
00741 }
00742
00743
00744 markedForDeletion.clear();
00745 cleaned_src.clear();
00746 vector<Shape<PolygonData> > existingPolygons;
00747 for (vector<ShapeRoot>::iterator dst_it = dst_shapes.begin();
00748 dst_it != dst_shapes.end(); dst_it++ ) {
00749 if ((*dst_it)->isType(polygonDataType)) {
00750 existingPolygons.push_back(ShapeRootType(*dst_it,PolygonData));
00751 continue;
00752 }
00753 if ( (*dst_it)->isType(localizationParticleDataType) )
00754 continue;
00755 for (vector<ShapeRoot>::iterator src_it = src_shapes.begin();
00756 src_it != src_shapes.end(); src_it++)
00757 if ((*dst_it)->isMatchFor(*src_it) && (*dst_it)->updateParams((*src_it))) {
00758 (*dst_it)->increaseConfidence(*src_it);
00759 if (curReq && curReq->verbosity & MBVshapeMatch )
00760 cout << "Matched src shape " << (*src_it)->getId() << " (lastMatch " << (*src_it)->getLastMatchId()
00761 << ") to dst shape " << (*dst_it)->getId() << endl;
00762 markedForDeletion.insert((*src_it)->getId());
00763 }
00764 }
00765
00766
00767 for ( vector<ShapeRoot>::iterator it = src_shapes.begin();
00768 it != src_shapes.end(); it++ )
00769 if ( markedForDeletion.find((*it)->getId()) == markedForDeletion.end() )
00770 cleaned_src.push_back(*it);
00771 src_shapes = cleaned_src;
00772
00773
00774 vector<ShapeRoot> deletedPolygons;
00775
00776 vector<ShapeRoot> newPolygons = PolygonData::formPolygons(polygon_edges,existingPolygons,deletedPolygons);
00777
00778 for (vector<ShapeRoot>::iterator delete_it = deletedPolygons.begin();
00779 delete_it != deletedPolygons.end(); delete_it++)
00780 delete_it->deleteShape();
00781 dstShS.importShapes(newPolygons);
00782 dstShS.importShapes(src_shapes);
00783 if (curReq && curReq->verbosity & MBVimportShapes )
00784 cout << "Imported " << (src_shapes.size()+newPolygons.size()) << " new shape(s) from "
00785 << srcShS.name << "ShS to " << dstShS.name << "ShS\n";
00786
00787
00788
00789 if (mergeDst) {
00790 dst_shapes = dstShS.allShapes();
00791 for ( vector<ShapeRoot>::iterator it = dst_shapes.begin();
00792 it != dst_shapes.end(); it++ )
00793 if ( ! (*it)->isType(localizationParticleDataType) )
00794 for ( vector<ShapeRoot>::iterator it2 = it+1;
00795 it2 < dst_shapes.end(); it2++)
00796 if ((*it2)->isMatchFor(*it) && (*it)->updateParams(*it2,true)) {
00797 cout << "Matched src shape " << (*it)->getId() << " (lastMatch "
00798 << (*it)->getLastMatchId()<< ") is a match for "
00799 << (*it2)->getId() << " (lastMatch "
00800 << (*it2)->getLastMatchId() << "), delete\n";
00801 it2->deleteShape();
00802 }
00803 }
00804 }
00805
00806
00807
00808 void MapBuilder::removeNoise(ShapeSpace& ShS, const fmat::Transform& baseToCam) {
00809
00810 vector<ShapeRoot> shapes = ShS.allShapes();
00811 for (vector<ShapeRoot>::iterator it = shapes.begin();
00812 it != shapes.end(); it++ ) {
00813
00814
00815 if (curReq->objectColors[(*it)->getType()].find(ProjectInterface::getColorIndex((*it)->getColor())) ==
00816 curReq->objectColors[(*it)->getType()].end())
00817 continue;
00818 if ((*it)->isType(polygonDataType)) {
00819 Shape<PolygonData>& polygon = ShapeRootType(*it,PolygonData);
00820 vector<LineData>& edges = polygon->getEdgesRW();
00821 unsigned int edge_index = 0;
00822 for (vector<LineData>::iterator edge_it = edges.begin();
00823 edge_it != edges.end(); edge_it++, edge_index++) {
00824 if (isLineVisible(*edge_it, baseToCam)) {
00825 if ( curReq->verbosity & MBVshouldSee )
00826 cout << "edge " << edge_index << " of polygon " << (*it)->getId() << "(confidence: "
00827 << edge_it->getConfidence() << ") should be visible in this frame" << endl;
00828 edge_it->decreaseConfidence();
00829 }
00830 }
00831 vector<ShapeRoot> brokenPolygons = polygon->updateState();
00832 ShS.importShapes(brokenPolygons);
00833 if (!polygon->isAdmissible()) {
00834 if ( curReq->verbosity & MBVdeleteShape )
00835 cout << "delete polygon " << (*it)->getId() << " from map" << endl;
00836 it->deleteShape();
00837 }
00838 }
00839 else if ((!(*it)->isType(agentDataType)) && isShapeVisible(*it, baseToCam, maxDistSq)){
00840 (*it)->decreaseConfidence();
00841 if ((*it)->getConfidence() < 0 ) {
00842 if ( curReq->verbosity & MBVshouldSee )
00843 cout << "shape " << (*it)->getId() << "(confidence: " << (*it)->getConfidence()
00844 << ") should be visible in this frame; deleted" << endl;
00845 it->deleteShape();
00846 }
00847 }
00848 }
00849 }
00850
00851
00852
00853 void MapBuilder::defineGazePts() {
00854 const ShapeRoot &sArea = curReq->searchArea;
00855 if ( !sArea.isValid() )
00856 return;
00857 else if ( curReq->doScan == true )
00858 scanForGazePts();
00859 else
00860 switch ( sArea->getType() ) {
00861
00862 case pointDataType:
00863 curReq->gazePts.push_back(sArea->getCentroid());
00864 break;
00865
00866 case lineDataType: {
00867 static const float meshSize=50;
00868 const Shape<LineData>& line = ShapeRootTypeConst(sArea,LineData);
00869 if ( curReq->doScan == true )
00870 scanForGazePts();
00871 else {
00872 int numIntervals = (int) (line->getLength()/meshSize);
00873 const EndPoint& ep1 = line->end1Pt();
00874 const EndPoint& ep2 = line->end2Pt();
00875 curReq->gazePts.push_back(ep1);
00876 for (int i = 1; i < numIntervals; i++)
00877 curReq->gazePts.push_back((ep1*i + ep2*(numIntervals-i))/numIntervals);
00878 curReq->gazePts.push_back(ep2);
00879 }
00880 }
00881 break;
00882
00883 case polygonDataType:
00884 if ( curReq->doScan == true )
00885 scanForGazePts();
00886 else {
00887 const Shape<PolygonData> &poly = ShapeRootTypeConst(sArea,PolygonData);
00888 const vector<Point> &verts = poly->getVertices();
00889 curReq->gazePts.insert(curReq->gazePts.end(),verts.begin(),verts.end());
00890 }
00891 break;
00892
00893 default:
00894 cerr << "ERROR MapBuilder::defineGazePts: Supported searchArea shapes are Point, Line, and Polygon\n";
00895 requestComplete();
00896 break;
00897 }
00898 }
00899
00900 void MapBuilder::removeGazePts(vector<Point> &gazePts, const fmat::Transform& baseToCam) {
00901 if (curReq->removePts) {
00902 int num_points_seen = 0;
00903 for ( vector<Point>::iterator it = gazePts.begin();
00904 it != gazePts.end(); it++ ) {
00905 if ( isPointVisible(*it,baseToCam,maxDistSq) ) {
00906 cout << "Removing already-visible gaze point " << *it << endl;
00907 num_points_seen++;
00908 gazePts.erase(it--);
00909 }
00910 }
00911
00912
00913 }
00914 }
00915
00916
00917
00918
00919
00920 void MapBuilder::printShS(ShapeSpace &ShS) const {
00921 cout << "MapBuilder::printShS()" << endl;
00922 unsigned int line_count = 0;
00923 vector<ShapeRoot> shapes = ShS.allShapes();
00924 for (vector<ShapeRoot>::const_iterator it = shapes.begin();
00925 it != shapes.end(); it++) {
00926 if ((*it)->isType(lineDataType)) {
00927 const Shape<LineData>& ld = ShapeRootTypeConst(*it,LineData);
00928 cout << (*it)->getId() << " " << lineDataType << " "
00929 << ProjectInterface::getColorIndex((*it)->getColor())
00930 << " " << ld->end1Pt().coordX() << " " << ld->end1Pt().coordY()
00931 << " " << ++line_count << " " << ld->getLength() << " " << ld->end1Pt().isValid() << endl;
00932 cout << (*it)->getId() << " " << lineDataType << " "
00933 << ProjectInterface::getColorIndex((*it)->getColor())
00934 << " " << ld->end2Pt().coordX() << " " << ld->end2Pt().coordY()
00935 << " " << line_count << " " << ld->getLength() << " " << ld->end2Pt().isValid() << endl;
00936 }
00937 else {
00938 cout << (*it)->getId() << " " << (*it)->getType() << " "
00939 << ProjectInterface::getColorIndex((*it)->getColor())
00940 << " " << (*it)->getCentroid().coordX() << " " << (*it)->getCentroid().coordY() << endl;
00941 }
00942 }
00943 }
00944
00945
00946
00947
00948 void MapBuilder::getCameraShapes(const Sketch<uchar>& camFrame) {
00949 getCamLines(camFrame, curReq->objectColors[lineDataType], curReq->occluderColors[lineDataType]);
00950 getCamEllipses(camFrame, curReq->objectColors[ellipseDataType], curReq->occluderColors[ellipseDataType]);
00951 getCamPolygons(camFrame, curReq->objectColors[polygonDataType], curReq->occluderColors[polygonDataType]);
00952 getCamSpheres(camFrame, curReq->objectColors[sphereDataType], curReq->occluderColors[sphereDataType]);
00953 getCamWalls(camFrame, curReq->floorColor);
00954 if ( curReq->numSamples == 1 && !curReq->searchArea.isValid() &&
00955 !curReq->objectColors[blobDataType].empty() && curReq->userImageProcessing == NULL )
00956 getCamBlobs(curReq->objectColors[blobDataType]);
00957 else
00958 getCamBlobs(camFrame, curReq->objectColors[blobDataType], curReq->minBlobAreas, curReq->blobOrientations, curReq->assumedBlobHeights);
00959 getCamTargets(camFrame, curReq->objectColors[targetDataType], curReq->occluderColors[targetDataType]);
00960 getCamMarkers(camFrame, curReq->objectColors[markerDataType], curReq->occluderColors[markerDataType],
00961 curReq->markerTypes);
00962
00963 NEW_SKETCH_N(rawY, uchar, VRmixin::sketchFromRawY());
00964 getCamSiftObjects(rawY, curReq->siftDatabasePath, curReq->siftObjectNames);
00965 getCamAprilTags(rawY);
00966 }
00967
00968 vector<Shape<LineData> > MapBuilder::getCamLines(const Sketch<uchar> &camFrame, const set<color_index>& objectColors,
00969 const set<color_index>& occluderColors) const {
00970 vector<Shape<LineData> > linesReturned;
00971 if ( objectColors.empty() )
00972 return linesReturned;
00973 if ( curReq->verbosity & MBVshapeSearch )
00974 cout << "*** Find the lines ***" << endl;
00975 NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
00976 for ( set<color_index>::const_iterator it = occluderColors.begin();
00977 it != occluderColors.end(); it++ )
00978 occluders |= visops::minArea(visops::colormask(camFrame,*it));
00979
00980 for (set<color_index>::const_iterator it = objectColors.begin();
00981 it != objectColors.end(); it++) {
00982 NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it));
00983 NEW_SKETCH_N(cleancolor,bool,visops::minArea(colormask));
00984 NEW_SKETCH_N(fatmask,bool,visops::fillin(cleancolor,1,2,8));
00985 NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
00986 vector<Shape<LineData> > line_shapes(LineData::extractLines(skel,cleancolor|occluders));
00987 linesReturned.insert(linesReturned.end(), line_shapes.begin(), line_shapes.end());
00988 if ( curReq->verbosity & MBVshapesFound )
00989 cout << "Found " << line_shapes.size() << " "
00990 << ProjectInterface::getColorName(*it) << " lines." << endl;
00991 }
00992 return linesReturned;
00993 }
00994
00995 vector<Shape<EllipseData> >
00996 MapBuilder::getCamEllipses(const Sketch<uchar> &camFrame,
00997 const set<color_index>& objectColors, const set<color_index>& ) const {
00998 vector<Shape<EllipseData> > ellipses;
00999 if (objectColors.empty())
01000 return ellipses;
01001 if ( curReq->verbosity & MBVshapeSearch )
01002 cout << "*** Find the ellipses ***" << endl;
01003 for (set<color_index>::const_iterator it = objectColors.begin();
01004 it !=objectColors.end(); it++) {
01005 NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it));
01006 vector<Shape<EllipseData> > ellipse_shapes = EllipseData::extractEllipses(colormask);
01007 ellipses.insert(ellipses.end(), ellipse_shapes.begin(),ellipse_shapes.begin());
01008 if ( curReq->verbosity & MBVshapesFound )
01009 cout << "Found " << ellipse_shapes.size() << " "
01010 << ProjectInterface::getColorName(*it) << " ellipses." << endl;
01011 }
01012 return ellipses;
01013 }
01014
01015 void MapBuilder::getCamPolygons(const Sketch<uchar> &camFrame,
01016 const set<color_index>& objectColors, const set<color_index>& occluderColors) const {
01017 vector<Shape<PolygonData> > polygons;
01018 if ( objectColors.empty() )
01019 return;
01020 if ( curReq->verbosity & MBVshapeSearch )
01021 cout << "*** Find the polygons ***" << endl;
01022 NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
01023 for ( set<color_index>::const_iterator it = occluderColors.begin();
01024 it !=occluderColors.end(); it++ )
01025 occluders |= visops::colormask(camFrame,*it);
01026
01027 for (set<color_index>::const_iterator it = objectColors.begin();
01028 it !=objectColors.end(); it++) {
01029 NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it));
01030 NEW_SKETCH_N(fatmask,bool,visops::fillin(colormask,1,2,8));
01031 NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
01032 NEW_SKETCH_N(fatskel,bool,visops::fillin(skel,1,2,8));
01033
01034 vector<Shape<LineData> > polygon_lines = PolygonData::extractPolygonEdges(fatskel,fatmask|occluders);
01035 polygons.insert(polygons.end(), polygon_lines.begin(), polygon_lines.end());
01036 if ( curReq->verbosity & MBVshapesFound )
01037 cout << "Found " << polygon_lines.size() << " lines." << endl;
01038 }
01039 }
01040
01041 void MapBuilder::getCamSpheres(const Sketch<uchar> &camFrame,
01042 const set<color_index>& objectColors, const set<color_index>& ) const {
01043 vector<Shape<SphereData> > spheres;
01044 if ( objectColors.empty() )
01045 return;
01046 if ( curReq->verbosity & MBVshapeSearch )
01047 cout << "*** Find the spheres ***" << endl;
01048 for (set<color_index>::const_iterator it = objectColors.begin();
01049 it !=objectColors.end(); it++) {
01050 NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it));
01051 vector<Shape<SphereData> > sphere_shapes = SphereData::extractSpheres(colormask);
01052 spheres.insert(spheres.end(), spheres.begin(), spheres.end());
01053 if ( curReq->verbosity & MBVshapesFound )
01054 cout << "Found " << sphere_shapes.size() << " spheres." << endl;
01055 }
01056 }
01057
01058 vector<Shape<LineData> >
01059 MapBuilder::getCamWalls(const Sketch<uchar> &camFrame, unsigned int floorColor) const {
01060 if (floorColor == 0)
01061 return vector<Shape<LineData> >();
01062 if ( curReq->verbosity & MBVshapeSearch )
01063 cout << "*** Find the walls ***" << endl;
01064 const int camFrame_offset = 8;
01065
01066 NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,floorColor));
01067 NEW_SKETCH_N(fillinmask ,bool,visops::fillin(colormask, 1, 6, 8));
01068 NEW_SKETCH_N(fillinmask2 ,bool,visops::fillin(fillinmask, 2, 3, 8));
01069 NEW_SKETCH_N(edgemask ,bool,visops::fillin(fillinmask2, 1, 5, 7));
01070 NEW_SKETCH_N(edgemask2 ,bool,visops::non_bounds(edgemask, camFrame_offset));
01071
01072 NEW_SKETCH_N(occluders_floor, bool, (camFrame != uchar(0)) & (camFrame != uchar(floorColor)));
01073 NEW_SKETCH_N(occ_mask ,bool,visops::fillin(occluders_floor, 1, 8, 8));
01074 usint const clear_dist = 15;
01075 Sketch<bool> not_too_close = (visops::mdist(occ_mask) >= clear_dist);
01076 edgemask2 &= not_too_close;
01077
01078 NEW_SKETCH_N(fatmask ,bool,visops::fillin(edgemask2,2,2,8));
01079 NEW_SKETCH_N(skel,bool,visops::skel(fatmask));
01080 NEW_SKETCH_N(fatskel,bool,visops::fillin(skel,1,2,8));
01081
01082 vector<Shape<LineData> > wall_bounds = PolygonData::extractPolygonEdges(fatskel,fatmask|occluders_floor);
01083
01084
01085
01086 for (vector<Shape<LineData> >::iterator it = wall_bounds.begin();
01087 it != wall_bounds.end(); it++) {
01088 if (((*it)->end1Pt().coordX() < camFrame_offset*2.0 || (*it)->end1Pt().coordX() > xres - camFrame_offset*2.0
01089 || (*it)->end1Pt().coordY() < camFrame_offset*2.0 || (*it)->end1Pt().coordY() > yres - camFrame_offset*2.0)
01090 && (*it)->end1Pt().isValid())
01091 (*it)->end1Pt().setValid(false);
01092 if (((*it)->end2Pt().coordX() < camFrame_offset*2.0 || (*it)->end2Pt().coordX() > xres - camFrame_offset*2.0
01093 || (*it)->end2Pt().coordY() < camFrame_offset*2.0 || (*it)->end2Pt().coordY() > yres - camFrame_offset*2.0)
01094 && (*it)->end2Pt().isValid())
01095 (*it)->end2Pt().setValid(false);
01096 }
01097
01098 if ( curReq->verbosity & MBVshapesFound )
01099 cout << "Found " << wall_bounds.size() << " wall boundary lines" << endl;
01100 return wall_bounds;
01101 }
01102
01103 void MapBuilder::getCamBlobs(const Sketch<uchar>& camFrame,
01104 const set<color_index>& colors,
01105 const map<color_index,int>& minBlobAreas,
01106 const map<color_index, BlobData::BlobOrientation_t>& blobOrientations,
01107 const map<color_index,coordinate_t>& assumedBlobHeights) {
01108 if ( colors.empty() )
01109 return;
01110 int const maxblobs = 50;
01111 vector<Shape<BlobData> > result(BlobData::extractBlobs(camFrame, colors, minBlobAreas, blobOrientations, assumedBlobHeights, maxblobs));
01112 if ( curReq->verbosity & MBVshapesFound )
01113 if ( !result.empty() )
01114 cout << "Found " << result.size() << " blobs." << endl;
01115 }
01116
01117
01118
01119 void MapBuilder::getCamBlobs(const set<color_index>& colors, int defMinBlobArea) {
01120
01121 if ( curReq->verbosity & MBVshapeSearch )
01122 cout << "*** Find the blobs ***" << endl;
01123 for (set<color_index>::const_iterator it = colors.begin();
01124 it != colors.end(); it++) {
01125 int const minarea = (curReq->minBlobAreas.find(*it)==curReq->minBlobAreas.end()) ?
01126 defMinBlobArea : curReq->minBlobAreas[*it];
01127 BlobData::BlobOrientation_t const orient = (curReq->blobOrientations.find(*it)==curReq->blobOrientations.end()) ?
01128 BlobData::groundplane : curReq->blobOrientations[*it];
01129 coordinate_t const height = (curReq->assumedBlobHeights.find(*it)==curReq->assumedBlobHeights.end()) ?
01130 0 : curReq->assumedBlobHeights[*it];
01131 vector<Shape<BlobData> > blob_shapes(VRmixin::getBlobsFromRegionGenerator(*it,minarea,orient,height));
01132 if ( curReq->verbosity & MBVshapesFound )
01133 if ( !blob_shapes.empty() )
01134 cout << "Found " << blob_shapes.size() << " "
01135 << ProjectInterface::getColorName(*it) << " region generator blobs." << endl;
01136 }
01137 }
01138
01139 void MapBuilder::getCamTargets(const Sketch<uchar> &camFrame, const set<color_index>& objectColors, const set<color_index>& occluderColors) const {
01140 vector<Shape<TargetData> > targets;
01141 if (objectColors.empty())
01142 return;
01143 if ( curReq->verbosity & MBVshapeSearch )
01144 cout << "*** Find the targets ***" << endl;
01145
01146 NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
01147 for (set<color_index>::const_iterator it = occluderColors.begin();
01148 it != occluderColors.end(); it++)
01149 occluders |= visops::minArea(visops::colormask(camFrame,*it));
01150
01151
01152 for (set<color_index>::const_iterator it = objectColors.begin();
01153 it != objectColors.end(); it++) {
01154 NEW_SKETCH_N(front_colormask, bool, visops::colormask(camFrame,*it));
01155 it++;
01156 if (it == objectColors.end()) {
01157 it--;
01158 }
01159 NEW_SKETCH_N(back_colormask, bool, visops::colormask(camFrame,*it));
01160 it++;
01161 if (it == objectColors.end()) {
01162 it--;
01163 }
01164 NEW_SKETCH_N(right_colormask, bool, visops::colormask(camFrame,*it));
01165 Shape<TargetData> target = TargetData::extractLineTarget(front_colormask, back_colormask, right_colormask, occluders);
01166 if (target.isValid()) {
01167 targets.insert(targets.end(), target);
01168 }
01169 if ( curReq->verbosity & MBVshapesFound )
01170 cout << "Found " << (target.isValid() ? 1 : 0) << " targets." << endl;
01171 }
01172 }
01173
01174 vector<Shape<MarkerData> >
01175 MapBuilder::getCamMarkers(const Sketch<uchar> &camFrame, const set<color_index>& objectColors,
01176 const set<color_index>&, const set<MarkerType_t>& markerTypes) const
01177 {
01178 vector<Shape<MarkerData> > markers;
01179 if (objectColors.empty() || markerTypes.empty())
01180 return markers;
01181
01182 if ( curReq->verbosity & MBVshapeSearch )
01183 cout << "*** Find the markers ***" << endl;
01184
01185
01186
01187
01188
01189
01190
01191
01192
01193
01194 for (set<MarkerType_t>::const_iterator it = markerTypes.begin();
01195 it != markerTypes.end(); it++) {
01196 vector<Shape<MarkerData> > single_type = MarkerData::extractMarkers(camFrame, *it, *curReq);
01197 markers.insert(markers.end(), single_type.begin(), single_type.end());
01198 }
01199
01200 if ( curReq->verbosity & MBVshapesFound )
01201 cout << "Found " << markers.size() << " markers." << endl;
01202
01203 return markers;
01204 }
01205
01206 void MapBuilder::getCamSiftObjects(const Sketch<uchar> &rawY, const std::string &siftDatabasePath,
01207 const std::set<std::string> &siftObjectNames) {
01208 if ( siftDatabasePath.empty() ) return;
01209 SiftTekkotsu *matcher = siftMatchers[siftDatabasePath];
01210 if ( matcher == NULL ) {
01211 matcher = new SiftTekkotsu;
01212 matcher->loadFile(siftDatabasePath);
01213 matcher->setParameter("probOfMatch", 0.8);
01214 siftMatchers[siftDatabasePath] = matcher;
01215 }
01216 ImageBuffer buff = matcher->sketchToBuffer(rawY);
01217 vector<SiftMatch*> results;
01218 if ( siftObjectNames.empty() )
01219 matcher->findAllObjectsInImage(buff, results);
01220 else
01221 for ( std::set<std::string>::const_iterator it = siftObjectNames.begin();
01222 it != siftObjectNames.end(); it++ ) {
01223 int id = matcher->getObjectID(*it);
01224 matcher->findObjectInImage(id, buff, results);
01225 };
01226 if ( curReq->verbosity & MBVshapesFound )
01227 cout << "Found " << results.size() << " sift objects." << endl;
01228 for ( vector<SiftMatch*>::const_iterator it = results.begin();
01229 it != results.end(); it++ ) {
01230 NEW_SHAPE(siftobj, SiftData, new SiftData(VRmixin::camShS, *it));
01231 }
01232 }
01233
01234 void MapBuilder::newSiftMatcher(const std::string &siftDatabasePath) {
01235 if ( siftDatabasePath.empty() ) return;
01236 SiftTekkotsu *matcher = siftMatchers[siftDatabasePath];
01237 if ( matcher == NULL ) {
01238 matcher = new SiftTekkotsu;
01239
01240 matcher->setParameter("probOfMatch", 0.8);
01241 siftMatchers[siftDatabasePath] = matcher;
01242 }
01243 }
01244
01245 void MapBuilder::getCamAprilTags(const Sketch<uchar> &rawY) {
01246 std::map<std::pair<int,int>,AprilTags::TagFamily*>::const_iterator registryEntry =
01247 AprilTags::TagFamily::tagFamilyRegistry.find(curReq->aprilTagFamily);
01248 if ( registryEntry == AprilTags::TagFamily::tagFamilyRegistry.end() )
01249 return;
01250 AprilTags::TagFamily *tagFamily = registryEntry->second;
01251 std::vector<Shape<AprilTagData> > results = AprilTagData::extractAprilTags(rawY, *tagFamily);
01252
01253 coordinate_t markerHeight = MapBuilderRequest::defaultMarkerHeight;
01254 for ( std::vector<Shape<AprilTagData> >::iterator it = results.begin();
01255 it != results.end(); it++ ) {
01256 Point c = (*it)->getCentroid();
01257 MarkerData::calculateCameraDistance(c, markerHeight);
01258 (*it)->setCentroid(c);
01259 }
01260 }
01261
01262 void MapBuilder::saveSiftDatabase(const std::string &siftDatabasePath) {
01263 if ( siftDatabasePath.empty() ) return;
01264 SiftTekkotsu *matcher = siftMatchers[siftDatabasePath];
01265 if ( matcher == NULL )
01266 cout << "Error in saveSiftDatabase: no database named '" << siftDatabasePath << "' has been loaded." << endl;
01267 else {
01268 matcher->saveToFile(siftDatabasePath, false);
01269 cout << "Wrote SIFT database " << siftDatabasePath << endl;
01270 }
01271 }
01272
01273 void MapBuilder::trainSiftObject(const std::string &siftDatabasePath,
01274 const std::string &objectName, const std::string &modelName) {
01275 NEW_SKETCH_N(rawY, uchar, VRmixin::sketchFromRawY());
01276 trainSiftObject(siftDatabasePath, rawY, objectName, modelName);
01277 }
01278
01279 void MapBuilder::trainSiftObject(const std::string &siftDatabasePath, const Sketch<uchar> &sketch,
01280 const std::string &objectName, const std::string &modelName) {
01281 if ( siftDatabasePath.empty() ) return;
01282 SiftTekkotsu *matcher = siftMatchers[siftDatabasePath];
01283 if ( matcher == NULL ) {
01284 cout << "Error in trainSiftObject:: no database named '" << siftDatabasePath << "' has been loaded." << endl;
01285 return;
01286 }
01287 ImageBuffer buffer = SiftTekkotsu::sketchToBuffer(sketch);
01288 int id = matcher->getObjectID(objectName);
01289 if ( id == -1 ) {
01290 int new_id = matcher->train_addNewObject(buffer);
01291 matcher->setObjectName(new_id, objectName);
01292 } else {
01293 matcher->train_addToObject(id, buffer);
01294 }
01295 }
01296
01297 }
01298