Tekkotsu Homepage
Demos
Overview
Downloads
Dev. Resources
Reference
Credits

VRmixin.cc

Go to the documentation of this file.
00001 #include <sstream>
00002 
00003 #include "Vision/RawCameraGenerator.h"
00004 #include "Vision/RLEGenerator.h"
00005 #include "Vision/RegionGenerator.h"
00006 #include "Vision/SegmentedColorGenerator.h"
00007 
00008 #include "DualCoding/SketchData.h"
00009 #include "DualCoding/ShapeBlob.h"
00010 #include "DualCoding/Sketch.h"
00011 
00012 #include "Crew/Lookout.h"
00013 #include "Crew/MapBuilder.h"
00014 #ifdef TGT_HAS_WALK
00015 #  include "Crew/Pilot.h"
00016 #endif
00017 #if (defined(TGT_HAS_ARMS) || !defined(STRICT_TGT_MODEL)) && !defined(TGT_IS_AIBO)
00018 #  include "Crew/Grasper.h"
00019 #endif
00020 #include "Localization/ShapeBasedParticleFilter.h"
00021 
00022 #include "ViewerConnection.h"  // for port numbers and buffer sizes
00023 #include "VRmixin.h"
00024 
00025 using namespace std;
00026 
00027 namespace DualCoding {
00028 
00029 //----------------------------------------------------------------
00030 
00031 VRmixin* VRmixin::theOne=NULL;
00032 
00033 //! static function allows us to specify intialization order because static within a function isn't created until the function is called
00034 template<ReferenceFrameType_t _refFrameType,int const init_id, size_t const _width, size_t const _height>
00035 static SketchSpace& createStaticSkS(const std::string& _name) {
00036   static SketchSpace SkS(_name,_refFrameType,init_id,_width,_height);
00037   //  cout << _name << " space is constructed\n";
00038   return SkS;
00039 }
00040 
00041 SketchSpace& VRmixin::getCamSkS() {
00042   return createStaticSkS<camcentric,10000,CameraResolutionX,CameraResolutionY>("cam");
00043 }
00044 SketchSpace& VRmixin::getLocalSkS() {
00045   return createStaticSkS<egocentric,20000,WORLD_WIDTH,WORLD_HEIGHT>("local"); 
00046 }
00047 SketchSpace& VRmixin::getWorldSkS() {
00048   return createStaticSkS<allocentric,30000,WORLD_WIDTH,WORLD_HEIGHT>("world");
00049 }
00050 ShapeSpace& VRmixin::getGroundShS() {
00051   static ShapeSpace ShS(&VRmixin::getCamSkS(),90000,"ground",egocentric);
00052   return ShS;
00053 }
00054 
00055 SketchSpace& VRmixin::camSkS=VRmixin::getCamSkS();
00056 ShapeSpace& VRmixin::camShS=VRmixin::getCamSkS().getDualSpace();
00057 
00058 ShapeSpace& VRmixin::groundShS=VRmixin::getGroundShS();
00059 
00060 SketchSpace& VRmixin::localSkS=VRmixin::getLocalSkS();
00061 ShapeSpace& VRmixin::localShS=VRmixin::getLocalSkS().getDualSpace();
00062 
00063 SketchSpace& VRmixin::worldSkS=VRmixin::getWorldSkS();
00064 ShapeSpace& VRmixin::worldShS=VRmixin::getWorldSkS().getDualSpace();
00065 
00066 Shape<AgentData> VRmixin::theAgent;
00067 
00068 Socket *VRmixin::camDialogSock=NULL;
00069 Socket *VRmixin::camSketchSock=NULL;
00070 Socket *VRmixin::localDialogSock=NULL;
00071 Socket *VRmixin::localSketchSock=NULL;
00072 Socket *VRmixin::worldDialogSock=NULL;
00073 Socket *VRmixin::worldSketchSock=NULL;
00074 
00075 MapBuilder* VRmixin::mapBuilder = NULL;
00076 Lookout* VRmixin::lookout = NULL;
00077 #ifdef TGT_HAS_WALK
00078 Pilot* VRmixin::pilot = NULL;
00079 #endif
00080 #if (defined(TGT_HAS_ARMS) || !defined(STRICT_TGT_MODEL)) && !defined(TGT_IS_AIBO)
00081 Grasper* VRmixin::grasper = NULL;
00082 #endif
00083 
00084 ShapeBasedParticleFilter* VRmixin::particleFilter = NULL; // will be set by startCrew
00085 
00086 unsigned int VRmixin::instanceCount = 0;
00087 unsigned int VRmixin::crewCount = 0;
00088 
00089 VRmixin::VRmixin() {
00090   if ( instanceCount++ == 0 ) {
00091     // only want to do the following once
00092     //cout << "Initializing VRmixin statics" << endl;
00093     if (theOne != NULL) {
00094       if ( ! mapBuilder->isRetained() )
00095   cerr << "VRmixin statics already constructed!?!?!" << endl;
00096       return;
00097     }
00098     theOne=this;
00099   
00100     camSkS.requireIdx();
00101     localSkS.requireIdx();
00102     worldSkS.requireIdx();
00103     
00104     camDialogSock=wireless->socket(Socket::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE);
00105     camSketchSock=wireless->socket(Socket::SOCK_STREAM, 1024, SKETCH_BUFFER_SIZE);
00106     worldDialogSock=wireless->socket(Socket::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE);
00107     worldSketchSock=wireless->socket(Socket::SOCK_STREAM, 1024, SKETCH_BUFFER_SIZE);
00108     localDialogSock=wireless->socket(Socket::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE);
00109     localSketchSock=wireless->socket(Socket::SOCK_STREAM, 1024, SKETCH_BUFFER_SIZE);
00110     
00111     wireless->setReceiver(camDialogSock->sock, &camDialogSockCallback);
00112     wireless->setReceiver(worldDialogSock->sock, &worldDialogSockCallback);
00113     wireless->setReceiver(localDialogSock->sock, &localDialogSockCallback);
00114     
00115     wireless->setDaemon(camDialogSock,   true);
00116     wireless->setDaemon(camSketchSock,      true);
00117     wireless->setDaemon(worldDialogSock, true);
00118     wireless->setDaemon(worldSketchSock,    true);
00119     wireless->setDaemon(localDialogSock, true);
00120     wireless->setDaemon(localSketchSock,    true);
00121     
00122     wireless->listen(camDialogSock,   CAM_DIALOG_PORT);
00123     wireless->listen(camSketchSock,      CAM_SKETCH_PORT);
00124     wireless->listen(worldDialogSock, WORLD_DIALOG_PORT);
00125     wireless->listen(worldSketchSock,    WORLD_SKETCH_PORT);
00126     wireless->listen(localDialogSock, LOCAL_DIALOG_PORT);
00127     wireless->listen(localSketchSock,    LOCAL_SKETCH_PORT);
00128     
00129     camSkS.viewer->setDialogSocket(camDialogSock,     CAM_DIALOG_PORT);
00130     camSkS.viewer->setSketchSocket(camSketchSock,           CAM_SKETCH_PORT);
00131     localSkS.viewer->setDialogSocket(localDialogSock, LOCAL_DIALOG_PORT);
00132     localSkS.viewer->setSketchSocket(localSketchSock,       LOCAL_SKETCH_PORT);
00133     worldSkS.viewer->setDialogSocket(worldDialogSock, WORLD_DIALOG_PORT);
00134     worldSkS.viewer->setSketchSocket(worldSketchSock,       WORLD_SKETCH_PORT);
00135 
00136     theAgent = Shape<AgentData>(worldShS);
00137     theAgent->setColor(rgb(0,0,255));
00138   }
00139 }
00140 
00141 VRmixin::~VRmixin() {
00142   if ( --instanceCount == 0 ) {
00143     // if ( mapBuilder->isRetained() ) return;
00144     cout << "Destructing VRmixin statics" << endl;
00145     if (theOne == NULL) {
00146       cerr << "VRmixin statics already destructed!?!?!" << endl;
00147       return;
00148     }
00149     theOne=NULL;
00150     
00151     wireless->setDaemon(camDialogSock,  false);
00152     wireless->setDaemon(camSketchSock,     false);
00153     wireless->setDaemon(localDialogSock,false);
00154     wireless->setDaemon(localSketchSock,   false);
00155     wireless->setDaemon(worldDialogSock,false);
00156     wireless->setDaemon(worldSketchSock,   false);
00157     
00158     wireless->close(camSketchSock->sock);
00159     wireless->close(camDialogSock->sock);
00160     wireless->close(localSketchSock->sock);
00161     wireless->close(localDialogSock->sock);
00162     wireless->close(worldSketchSock->sock);
00163     wireless->close(worldDialogSock->sock);
00164     
00165     // clear each ShapeSpace first because it may contain rendering links to the SketchSpace
00166     camShS.clear();
00167     camSkS.bumpRefreshCounter(); // release visible sketches
00168     camSkS.clear();
00169     
00170     localShS.clear();
00171     localSkS.bumpRefreshCounter(); // release visible sketches
00172     localSkS.clear();
00173     
00174     theAgent = Shape<AgentData>();
00175     worldShS.clear();
00176     worldSkS.bumpRefreshCounter(); // release visible sketches
00177     worldSkS.clear();
00178     
00179     camSkS.freeIndexes();
00180     localSkS.freeIndexes();
00181     worldSkS.freeIndexes();
00182   }
00183 }
00184 
00185 void VRmixin::startCrew() {
00186   if ( crewCount++ == 0 ) {
00187     cout << "Starting crew." << endl;
00188     mapBuilder = new MapBuilder;
00189     lookout = new Lookout;
00190 #ifdef TGT_HAS_WALK
00191     pilot = new Pilot;
00192 #endif
00193 #if (defined(TGT_HAS_ARMS) || !defined(STRICT_TGT_MODEL)) && !defined(TGT_IS_AIBO)
00194     grasper = new Grasper;
00195 #endif
00196     if ( particleFilter == NULL )
00197       particleFilter = new ShapeBasedParticleFilter(camShS,localShS,worldShS);
00198 
00199     mapBuilder->start();
00200     lookout->start();
00201 #ifdef TGT_HAS_WALK
00202     pilot->start();
00203 #endif
00204 #if (defined(TGT_HAS_ARMS) || !defined(STRICT_TGT_MODEL)) && !defined(TGT_IS_AIBO)
00205     grasper->start();
00206 #endif
00207   }
00208 }
00209 
00210 void VRmixin::stopCrew() {
00211   if ( --crewCount == 0 ) {
00212     cout << "Stopping crew." << endl;
00213     // reference counting should delete these:
00214 #if (defined(TGT_HAS_ARMS) || !defined(STRICT_TGT_MODEL)) && !defined(TGT_IS_AIBO)
00215     grasper->stop();
00216 #endif
00217 #ifdef TGT_HAS_WALK
00218     pilot->stop();
00219 #endif
00220     lookout->stop();
00221     mapBuilder->stop();
00222     delete particleFilter;
00223     particleFilter = NULL;
00224   }
00225 }
00226   
00227 #ifdef TGT_HAS_CAMERA
00228 void VRmixin::projectToGround() {
00229   projectToGround(kine->linkToBase(CameraFrameOffset));
00230 }
00231 #endif
00232 
00233 void VRmixin::projectToGround(const fmat::Transform& camToBase) {
00234   projectToGround(camToBase, kine->calculateGroundPlane());
00235 }
00236 
00237 void VRmixin::projectToGround(const fmat::Transform& camToBase, const PlaneEquation& groundplane) {
00238   groundShS.clear();
00239   groundShS.importShapes(camShS.allShapes());
00240   vector<ShapeRoot> &groundShapes_vec = groundShS.allShapes();
00241   for(size_t i = 0; i < groundShapes_vec.size(); i++)
00242     groundShapes_vec[i]->projectToGround(camToBase, groundplane);
00243 }
00244 
00245 int VRmixin::camDialogSockCallback(char *buf, int bytes) {
00246   static std::string incomplete;
00247   dialogCallback(buf, bytes, incomplete, theOne->camSkS, theOne->camShS);
00248   return 0;
00249 }
00250 
00251 int VRmixin::localDialogSockCallback(char *buf, int bytes) {
00252   static std::string incomplete;
00253   dialogCallback(buf, bytes, incomplete, theOne->localSkS, theOne->localShS);
00254   return 0;
00255 }
00256 
00257 int VRmixin::worldDialogSockCallback(char *buf, int bytes) {
00258   static std::string incomplete;
00259   dialogCallback(buf, bytes, incomplete, theOne->worldSkS, theOne->worldShS);
00260   return 0;
00261 }
00262 
00263 void VRmixin::dialogCallback(char* buf, int bytes, std::string& incomplete,
00264            SketchSpace& SkS, ShapeSpace& ShS) {
00265   std::string s(buf,bytes);
00266   // std::cout << "***** dialogCallback: '" << s << "'\n";
00267   while(s.size()>0) {
00268     size_t endline=s.find('\n');
00269     if(endline==std::string::npos) {
00270       incomplete+=s;
00271       return;
00272     }
00273     else {
00274       incomplete+=s.substr(0,endline);
00275       theOne->processSketchRequest(incomplete,SkS,ShS);
00276       incomplete.erase();
00277       s=s.substr(endline+1);
00278     }
00279   }
00280   return;
00281 }
00282 
00283 bool VRmixin::encodeSketch(const SketchDataRoot& image)
00284 {
00285   unsigned int avail = SKETCH_BUFFER_SIZE-1;
00286   Socket* sketchSock = image.getSpace().viewer->getSketchSocket();
00287   char* buf=(char*)sketchSock->getWriteBuffer(avail);
00288   ASSERTRETVAL(buf!=NULL,"could not get buffer",false);
00289   unsigned int used = image.saveBuffer(buf, avail);
00290   sketchSock->write(used);
00291   return true;
00292 }
00293 
00294 //! Import a color-segmented image as a Sketch<uchar>
00295 Sketch<uchar> VRmixin::sketchFromSeg() {
00296   Sketch<uchar> cam(camSkS, "camimage");
00297   cam->setColorMap(segMap);
00298   size_t const npixels = cam->getNumPixels();
00299   cmap_t* seg_image = ProjectInterface::defSegmentedColorGenerator->getImage(CAM_LAYER,CAM_CHANNEL);
00300   memcpy(cam->getRawPixels(), seg_image, npixels);
00301   return cam;
00302 }
00303 
00304 //! Import channel n as a Sketch<uchar>
00305 Sketch<uchar> VRmixin::sketchFromChannel(const RawCameraGenerator::channel_id_t chan) {
00306   const RawCameraGenerator::channel_id_t the_chan =
00307     (chan >= 0 && chan < RawCameraGenerator::NUM_CHANNELS) ? chan : RawCameraGenerator::CHAN_Y;
00308   Sketch<uchar> cam(camSkS,"sketchFromChannel");
00309   cam->setColorMap(grayMap);
00310   uchar* campixels = cam->getRawPixels();
00311   int const incr = ProjectInterface::defRawCameraGenerator->getIncrement(CAM_LAYER);
00312   int const skip = ProjectInterface::defRawCameraGenerator->getSkip(CAM_LAYER);
00313   uchar* chan_ptr = ProjectInterface::defRawCameraGenerator->getImage(CAM_LAYER,the_chan);
00314   if(chan_ptr==NULL) {
00315     memset(campixels,0,cam->getHeight()*cam->getWidth());
00316   } else {
00317     chan_ptr -= incr;  // back up by one pixel to prepare for loop
00318     for (unsigned int row = 0; row < cam->getHeight(); row++) {
00319       for (unsigned int col = 0; col < cam->getWidth(); col++)
00320         *campixels++ = *(chan_ptr += incr);
00321       chan_ptr += skip;
00322     }
00323   }
00324   return cam;
00325 }
00326 
00327 Sketch<uchar> VRmixin::sketchFromRawY() {
00328   return sketchFromChannel(RawCameraGenerator::CHAN_Y);
00329 }
00330   
00331 Sketch<usint> VRmixin::sketchFromDepth() {
00332   Sketch<usint> depth(camSkS,"sketchFromDepth");
00333   depth->setColorMap(jetMapScaled);
00334   usint* depthpixels = depth->getRawPixels();
00335   int const incr = ProjectInterface::defRawDepthGenerator->getIncrement(CAM_LAYER);
00336   int const skip = ProjectInterface::defRawDepthGenerator->getSkip(CAM_LAYER);
00337   uchar* chanY_ptr = ProjectInterface::defRawDepthGenerator->getImage(CAM_LAYER, RawCameraGenerator::CHAN_Y);
00338   uchar* chanU_ptr = ProjectInterface::defRawDepthGenerator->getImage(CAM_LAYER, RawCameraGenerator::CHAN_U);
00339   for (unsigned int row = 0; row < depth->getHeight(); row++) {
00340     for (unsigned int col = 0; col < depth->getWidth(); col++)
00341       *depthpixels++ = *(chanY_ptr += incr) | (*(chanU_ptr += incr))<<8;
00342     chanY_ptr += skip;
00343     chanU_ptr += skip;
00344   }
00345   return depth;
00346 }
00347 
00348 Sketch<yuv> VRmixin::sketchFromYUV() {
00349   Sketch<yuv> cam(camSkS,"sketchFromYUV");
00350   cam->setColorMap(segMap);
00351   yuv* campixels = cam->getRawPixels();
00352   int const incr = ProjectInterface::defRawCameraGenerator->getIncrement(CAM_LAYER);
00353   int const skip = ProjectInterface::defRawCameraGenerator->getSkip(CAM_LAYER);
00354   uchar* chanY_ptr = ProjectInterface::defRawCameraGenerator->getImage(CAM_LAYER,RawCameraGenerator::CHAN_Y);
00355   uchar* chanU_ptr = ProjectInterface::defRawCameraGenerator->getImage(CAM_LAYER,RawCameraGenerator::CHAN_U);
00356   uchar* chanV_ptr = ProjectInterface::defRawCameraGenerator->getImage(CAM_LAYER,RawCameraGenerator::CHAN_V);
00357   if ( chanY_ptr == NULL )
00358     memset(campixels,0,cam->getHeight()*cam->getWidth()*sizeof(rgb));
00359   else {
00360     // back up by one pixel to prepare for loop
00361     chanY_ptr -= incr;
00362     chanU_ptr -= incr;
00363     chanV_ptr -= incr;
00364     for (unsigned int row = 0; row < cam->getHeight(); row++) {
00365       for (unsigned int col = 0; col < cam->getWidth(); col++)
00366         *campixels++ = yuv(*(chanY_ptr += incr), *(chanU_ptr += incr), *(chanV_ptr += incr));
00367       chanY_ptr += skip;
00368       chanU_ptr += skip;
00369       chanV_ptr += skip;
00370     }
00371   }
00372   return cam;
00373 }
00374 
00375 //! Import the results of the region generator as a vector of Shape<BlobData>
00376 vector<Shape<BlobData> >
00377 VRmixin::getBlobsFromRegionGenerator(const color_index color, 
00378              const int minarea,
00379              const BlobData::BlobOrientation_t orient, 
00380              const coordinate_t height,
00381              const int maxblobs) {
00382   vector<Shape<BlobData> > result;
00383   const CMVision::run<uchar> *sketch_buffer = reinterpret_cast<const CMVision::run<uchar>*>
00384     (ProjectInterface::defRLEGenerator->getImage(CAM_LAYER,CAM_CHANNEL));
00385   const CMVision::color_class_state* ccs = reinterpret_cast<const CMVision::color_class_state*>
00386     (ProjectInterface::defRegionGenerator->getImage(CAM_LAYER,CAM_CHANNEL));
00387   //  cout << "Color " << color << " name '" << ccs[color].name 
00388   //   << "' has " << ccs[color].num << " regions." << endl;
00389   const rgb rgbvalue = ProjectInterface::getColorRGB(color);
00390   const CMVision::region* list_head = ccs[color].list;
00391   for (int i=0; list_head!=NULL && i<maxblobs && list_head->area >= minarea; list_head = list_head->next, i++) {
00392     BlobData* blobdat = BlobData::new_blob(camShS,*list_head, sketch_buffer, orient, height, rgbvalue);
00393     result.push_back(Shape<BlobData>(blobdat));
00394   }
00395   return result;
00396 }
00397 
00398 void VRmixin::processSketchRequest(const std::string &line,
00399            SketchSpace& SkS, 
00400            ShapeSpace& ShS)
00401 {
00402   Socket* dialogSock = SkS.viewer->getDialogSocket();
00403   if(line.compare(0,strlen("size"),"size")==0) {
00404     dialogSock->printf("size begin\n");
00405     dialogSock->printf("width %d\nheight %d\n",int(SkS.getWidth()),int(SkS.getHeight()));
00406     dialogSock->printf("size end\n");
00407   }
00408   else if(line.compare(0,strlen("list"),"list")==0) {
00409     dialogSock->printf("list begin\n");
00410     SkS.viewer->writeBigString(SkS.getTmatForGUI());  
00411     SkS.viewer->writeBigString(SkS.getSketchListForGUI());  
00412     SkS.viewer->writeBigString(ShS.getShapeListForGUI()); 
00413     dialogSock->printf("list end\n");
00414   } else if(line.compare(0,strlen("get"),"get")==0) {
00415     std::string tempstring = line.substr(strlen("get"),
00416            line.length()-strlen("get"));
00417     std::istringstream ist(tempstring);
00418     int requested_id = -1;
00419     ist >> requested_id;
00420     dialogSock->printf("get read:%d\n",requested_id);
00421     SketchDataRoot* sketchptr=(SkS.retrieveSketch(requested_id));
00422     if(sketchptr != NULL)
00423       encodeSketch(*sketchptr);
00424     dialogSock->printf("get end\n");
00425   } else {
00426     dialogSock->printf("Invalid command\n");
00427   }
00428 }
00429 
00430 } // namespace

DualCoding 5.1CVS
Generated Fri Mar 16 05:23:48 2012 by Doxygen 1.6.3