diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/BehaviorBase.cc ./Behaviors/BehaviorBase.cc --- ../Tekkotsu_3.0/Behaviors/BehaviorBase.cc 2006-09-27 17:15:52.000000000 -0400 +++ ./Behaviors/BehaviorBase.cc 2007-06-14 02:24:03.000000000 -0400 @@ -36,7 +36,8 @@ SetAutoDelete(false); if(started) std::cerr << "Behavior " << getName() << " deleted while running: use 'RemoveReference', not 'delete'" << std::endl; - erouter->removeListener(this); + if(erouter!=NULL) + erouter->removeListener(this); getRegistryInstance().erase(this); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controller.cc ./Behaviors/Controller.cc --- ../Tekkotsu_3.0/Behaviors/Controller.cc 2006-09-18 14:08:05.000000000 -0400 +++ ./Behaviors/Controller.cc 2007-11-18 01:47:00.000000000 -0500 @@ -7,13 +7,13 @@ #include "Shared/get_time.h" #include "Sound/SoundManager.h" #include "Events/TextMsgEvent.h" +#include "Shared/RobotInfo.h" #include "Shared/ERS210Info.h" #include "Shared/ERS220Info.h" +#include "Shared/ERS2xxInfo.h" #include "Shared/ERS7Info.h" #include "Shared/string_util.h" -#ifndef PLATFORM_APERIOS -# include "local/sim/Simulator.h" -#endif +#include "Shared/ProjectInterface.h" #include Controller * Controller::theOneController=NULL; @@ -27,7 +27,7 @@ EventBase Controller::cancel; using namespace string_util; - +using namespace std; void Controller::DoStart() { BehaviorBase::DoStart(); @@ -38,7 +38,7 @@ sndman->loadFile(config->controller.cancel_snd); erouter->addListener(this,EventBase::estopEGID); // Turn on wireless - gui_comm=wireless->socket(SocketNS::SOCK_STREAM, 2048, 32000); + gui_comm=wireless->socket(Socket::SOCK_STREAM, 2048, 32000); wireless->setReceiver(gui_comm->sock, gui_comm_callback); wireless->setDaemon(gui_comm,true); wireless->listen(gui_comm->sock, config->controller.gui_port); @@ -61,8 +61,10 @@ motman->removeMotion(display); display=MotionManager::invalid_MC_ID; //these two lines help prevent residual display in case that was the only MotionCommand using LEDs +#ifdef TGT_HAS_LEDS for(unsigned int i=LEDOffset; isetOutput(NULL,i,0.f); +#endif gui_comm->printf("goodbye\n"); wireless->setDaemon(gui_comm,false); wireless->close(gui_comm); @@ -282,38 +284,57 @@ return 0; } +/*! Select which model is running and call initButtons with the appropriate button offsets + * This could be somewhat simplified by using capabilities.getButtonOffset(), (wouldn't need + * the ERS2xx case with essentially duplicated ERS210 and ERS220 cases), but this + * style has the advantage that the symbols are checked by the compiler so there's no + * chance of a typo in a button name going unnoticed. */ void Controller::init() { - if(state->robotDesign & WorldState::ERS210Mask) { - nextItem=EventBase(EventBase::buttonEGID,ERS210Info::HeadFrButOffset,EventBase::deactivateETID,0); - prevItem=EventBase(EventBase::buttonEGID,ERS210Info::HeadBkButOffset,EventBase::deactivateETID,0); - nextItemFast=EventBase(EventBase::buttonEGID,ERS210Info::HeadFrButOffset,EventBase::statusETID,666); - prevItemFast=EventBase(EventBase::buttonEGID,ERS210Info::HeadBkButOffset,EventBase::statusETID,666); - selectItem=EventBase(EventBase::buttonEGID,ERS210Info::ChinButOffset,EventBase::deactivateETID,250); - cancel=EventBase(EventBase::buttonEGID,ERS210Info::BackButOffset,EventBase::deactivateETID,250); - } else if(state->robotDesign & WorldState::ERS220Mask) { - nextItem=EventBase(EventBase::buttonEGID,ERS220Info::TailLeftButOffset,EventBase::deactivateETID,0); - prevItem=EventBase(EventBase::buttonEGID,ERS220Info::TailRightButOffset,EventBase::deactivateETID,0); - //the 220 doesn't really support the next two because it's using boolean buttons + if(TargetName == ERS2xxInfo::TargetName) { + // compatability mode, see which of the targets is actually running + // Note using ERS2xxInfo namespace to get appropriate offsets! + // could remove duplication with "direct" 210/220 cases below by using something like: + // capabilities.getButtonOffset(ERS210Info::outputNames[ERS210Info::fooButOffset]) + if(RobotName == ERS210Info::TargetName) { + initButtons(666,250,ERS2xxInfo::HeadFrButOffset,ERS2xxInfo::HeadBkButOffset,ERS2xxInfo::HeadFrButOffset,ERS2xxInfo::HeadBkButOffset,ERS2xxInfo::ChinButOffset,ERS2xxInfo::BackButOffset); + } else if(RobotName == ERS220Info::TargetName) { + //the 220 doesn't really support "fast" because it's using boolean buttons + //i'm using a "hack" on the 210 because the pressure sensitivity causes status + //events to continually be sent but since this is just on/off, it only gets the + //activate/deactivate. To fix this, override nextItemFast and prevItemFast with + // timers and do timer management in processEvents() + initButtons(666,50,ERS2xxInfo::TailLeftButOffset,ERS2xxInfo::TailRightButOffset,ERS2xxInfo::TailLeftButOffset,ERS2xxInfo::TailRightButOffset,ERS2xxInfo::TailCenterButOffset,ERS2xxInfo::BackButOffset); + } else { + cerr << "Controller: Unsupported 2xx model '" << RobotName << "'! Appears to have buttons, but Controller doesn't know how to use them." << endl; + } + } else if(RobotName == ERS210Info::TargetName) { + initButtons(666,250,ERS210Info::HeadFrButOffset,ERS210Info::HeadBkButOffset,ERS210Info::HeadFrButOffset,ERS210Info::HeadBkButOffset,ERS210Info::ChinButOffset,ERS210Info::BackButOffset); + } else if(RobotName == ERS220Info::TargetName) { + //the 220 doesn't really support "fast" because it's using boolean buttons //i'm using a "hack" on the 210 because the pressure sensitivity causes status //events to continually be sent but since this is just on/off, it only gets the - //activate/deactivate. To fix this, make these timers and do timer management - //in processEvents() - nextItemFast=EventBase(EventBase::buttonEGID,ERS220Info::TailLeftButOffset,EventBase::statusETID,666); - prevItemFast=EventBase(EventBase::buttonEGID,ERS220Info::TailRightButOffset,EventBase::statusETID,666); - selectItem=EventBase(EventBase::buttonEGID,ERS220Info::TailCenterButOffset,EventBase::deactivateETID,50); - cancel=EventBase(EventBase::buttonEGID,ERS220Info::BackButOffset,EventBase::deactivateETID,50); - } else if(state->robotDesign & WorldState::ERS7Mask) { - nextItem=EventBase(EventBase::buttonEGID,ERS7Info::FrontBackButOffset,EventBase::deactivateETID,0); - prevItem=EventBase(EventBase::buttonEGID,ERS7Info::RearBackButOffset,EventBase::deactivateETID,0); - nextItemFast=EventBase(EventBase::buttonEGID,ERS7Info::FrontBackButOffset,EventBase::statusETID,500); - prevItemFast=EventBase(EventBase::buttonEGID,ERS7Info::RearBackButOffset,EventBase::statusETID,500); - selectItem=EventBase(EventBase::buttonEGID,ERS7Info::MiddleBackButOffset,EventBase::deactivateETID,25); - cancel=EventBase(EventBase::buttonEGID,ERS7Info::HeadButOffset,EventBase::deactivateETID,25); + //activate/deactivate. To fix this, override nextItemFast and prevItemFast with + // timers and do timer management in processEvents() + initButtons(666,50,ERS220Info::TailLeftButOffset,ERS220Info::TailRightButOffset,ERS220Info::TailLeftButOffset,ERS220Info::TailRightButOffset,ERS220Info::TailCenterButOffset,ERS220Info::BackButOffset); + } else if(RobotName == ERS7Info::TargetName) { + initButtons(500,25,ERS7Info::FrontBackButOffset,ERS7Info::RearBackButOffset,ERS7Info::FrontBackButOffset,ERS7Info::RearBackButOffset,ERS7Info::MiddleBackButOffset,ERS7Info::HeadButOffset); } else { - serr->printf("Controller: Unsupported model!\n"); +#ifdef TGT_HAS_BUTTONS + cerr << "Controller: Unsupported model '" << RobotName << "'! Appears to have buttons, but Controller doesn't know how to use them." << endl; +#endif } } +void Controller::initButtons(unsigned fastTime, unsigned downTime, unsigned nextB, unsigned prevB, unsigned nextFastB, unsigned prevFastB, unsigned selectB, unsigned cancelB) { + nextItem=EventBase(EventBase::buttonEGID,nextB,EventBase::deactivateETID,0); + prevItem=EventBase(EventBase::buttonEGID,prevB,EventBase::deactivateETID,0); + nextItemFast=EventBase(EventBase::buttonEGID,nextFastB,EventBase::statusETID,fastTime); + prevItemFast=EventBase(EventBase::buttonEGID,prevFastB,EventBase::statusETID,fastTime); + selectItem=EventBase(EventBase::buttonEGID,selectB,EventBase::deactivateETID,downTime); + cancel=EventBase(EventBase::buttonEGID,cancelB,EventBase::deactivateETID,downTime); +} + + bool Controller::select(ControlBase* item, const std::string& name) { // Depth first const std::vector& slots = item->getSlots(); @@ -488,31 +509,31 @@ #ifdef PLATFORM_APERIOS serr->printf("!sim command invalid -- not running in simulator!\n"); #else - Simulator::sendCommand(s.substr(offsets[1])); + ProjectInterface::sendCommand(s.substr(offsets[1])); #endif } else setNext(cmdstack.top()->takeInput(s)); } } -int Controller::setConfig(const char *str) { - char buf[80]; - strncpy(buf, str, 79); - char *value=index(buf, '='); - char *key=index(buf, '.'); - if (key==NULL || value==NULL) return -1; - if (key>=value) return -1; - *key=0; - key++; - *value=0; - value++; - Config::section_t section=config->parseSection(buf); - if (section==Config::sec_invalid) return -2; - config->setValue(section, key, value, true); - //void *val_set=config->setValue(section, key, value, true); - // might want to catch setValue's return value and do - // something special for some config values? - // (such as reboot a subsystem to reload new settings) +int Controller::setConfig(const std::string& str) { + string::size_type eq=str.find('='); + if(eq==string::npos) + return -2; + plist::ObjectBase* entry = config->resolveEntry(string_util::trim(str.substr(0,eq))); + if(entry==NULL) { + string::size_type p=str.find('.'); + string sec=string_util::trim(str.substr(0,p)); + string key=string_util::trim(str.substr(p+1,eq-p-1)); + string val=string_util::trim(str.substr(eq+1)); + if(config->setValue(sec,key,val)==NULL) + return -2; + return 0; + } + plist::PrimitiveBase* prim = dynamic_cast(entry); + if(prim==NULL) + return -2; + prim->set(string_util::trim(str.substr(eq+1))); return 0; } @@ -538,8 +559,10 @@ //these two lines help prevent residual display in case that was the only MotionCommand using LEDs motman->setPriority(display,MotionManager::kIgnoredPriority); isControlling=false; +#ifdef TGT_HAS_LEDS for(unsigned int i=LEDOffset; isetOutput(NULL,i,0.f); +#endif erouter->removeTrapper(this); cmdstack.top()->pause(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controller.h ./Behaviors/Controller.h --- ../Tekkotsu_3.0/Behaviors/Controller.h 2005-09-01 14:53:06.000000000 -0400 +++ ./Behaviors/Controller.h 2007-06-28 00:36:19.000000000 -0400 @@ -147,17 +147,20 @@ static int console_callback(char *buf, int bytes); //!< called by wireless when someone has entered new data on the tekkotsu console (NOT cin) protected: - //! assigns appropriate values to the static event bases + //! calls initButtons with the appropriate button offsets for the host robot model void init(); - + + //! assigns appropriate values to the static event bases + void initButtons(unsigned fastTime, unsigned downTime, unsigned nextB, unsigned prevB, unsigned nextFastB, unsigned prevFastB, unsigned selectB, unsigned cancelB); + //! called with each line that's entered on the tekkotsu console or from the GUI void takeLine(const std::string& s); //! called with slots (options), a name to lookup; will select the named control - bool Controller::select(ControlBase* item, const std::string& name); + bool select(ControlBase* item, const std::string& name); //! sets a config value - some values may require additional processing (done here) to have the new values take effect - int setConfig(const char *str); + int setConfig(const std::string& str); //! maintains top Control /*! @param next one of: @li NULL: pop() ::cmdstack @li ::cmdstack.top(): nothing @li other address: ::push(@a next) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/BatteryCheckControl.h ./Behaviors/Controls/BatteryCheckControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/BatteryCheckControl.h 2005-01-25 15:06:39.000000000 -0500 +++ ./Behaviors/Controls/BatteryCheckControl.h 2007-06-05 14:03:24.000000000 -0400 @@ -54,8 +54,8 @@ std::string s("refresh\n"); s+=getName()+"\n1\n0\n0\nPower remain: "; s+=tmp; - s+="%\nSee console output for details\n"; - s+="status\nPower remaining: "; + s+="%\n0\nSee console output for details\n"; + s+="status\n1\nPower remaining: "; s+=tmp; s+="%\n"; gui_comm->write((const byte*)s.c_str(),s.size()); @@ -68,7 +68,7 @@ } //! calls refresh() to redisplay with new information if it's not a vibration event virtual void processEvent(const EventBase& event) { - if(event.getSourceID()!=PowerSourceID::VibrationSID) + if(event.getSourceID()!=PowerSrcID::VibrationSID) refresh(); } virtual ControlBase * doSelect() { @@ -83,19 +83,19 @@ sout->printf("\tCurrent:\t%g\n",state->sensors[PowerCurrentOffset]); sout->printf("\tTemperature:\t%g\n",state->sensors[PowerThermoOffset]); sout->printf("\tFlags:\t"); - if(state->powerFlags[PowerSourceID::BatteryConnectSID]) + if(state->powerFlags[PowerSrcID::BatteryConnectSID]) sout->printf("BatteryConnect "); - if(state->powerFlags[PowerSourceID::DischargingSID]) + if(state->powerFlags[PowerSrcID::DischargingSID]) sout->printf("Discharging "); - if(state->powerFlags[PowerSourceID::ChargingSID]) + if(state->powerFlags[PowerSrcID::ChargingSID]) sout->printf("Charging "); - if(state->powerFlags[PowerSourceID::ExternalPowerSID]) + if(state->powerFlags[PowerSrcID::ExternalPowerSID]) sout->printf("ExternalPower "); - if(state->powerFlags[PowerSourceID::PowerGoodSID]) + if(state->powerFlags[PowerSrcID::PowerGoodSID]) sout->printf("PowerGood "); - if(state->powerFlags[PowerSourceID::LowPowerWarnSID]) + if(state->powerFlags[PowerSrcID::LowPowerWarnSID]) sout->printf("LowPowerWarn "); - if(state->powerFlags[PowerSourceID::BatteryEmptySID]) + if(state->powerFlags[PowerSrcID::BatteryEmptySID]) sout->printf("BatteryEmpty "); sout->printf("\n"); if(display_id!=MotionManager::invalid_MC_ID) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/BehaviorSwitchControl.h ./Behaviors/Controls/BehaviorSwitchControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/BehaviorSwitchControl.h 2006-09-01 14:21:20.000000000 -0400 +++ ./Behaviors/Controls/BehaviorSwitchControl.h 2007-05-22 00:24:26.000000000 -0400 @@ -5,7 +5,7 @@ #include "ControlBase.h" #include "Behaviors/BehaviorBase.h" #include "Shared/ReferenceCounter.h" -#include "Shared/Factory.h" +#include "Shared/Factories.h" #include "Shared/debuget.h" #include "Events/TextMsgEvent.h" @@ -178,7 +178,7 @@ //! Allows proper switching between major behaviors, calling DoStart and DoStop -template < class B, class Al = Factory< B > > +template < class B, class Al = typename Factory0Arg::template Factory > class BehaviorSwitchControl : public BehaviorSwitchControlBase { public: //! constructor, can use this to toggle a single behavior on and off @@ -237,14 +237,14 @@ virtual void startmine() { if(!retained) { Al allocator; - mybeh=allocator.construct(); + mybeh=allocator(); mybeh->setName(getName()); if(behgrp!=NULL) behgrp->curBehavior=mybeh; } else { if(mybeh==NULL) { Al allocator; - mybeh=allocator.construct(); + mybeh=allocator(); mybeh->setName(getName()); mybeh->AddReference(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/ConfigurationEditor.cc ./Behaviors/Controls/ConfigurationEditor.cc --- ../Tekkotsu_3.0/Behaviors/Controls/ConfigurationEditor.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Controls/ConfigurationEditor.cc 2007-11-12 23:16:00.000000000 -0500 @@ -0,0 +1,238 @@ +#include "ConfigurationEditor.h" +#include "Behaviors/Controls/NullControl.h" +#include "Shared/plistCollections.h" +#include "Shared/Config.h" +#include "Shared/string_util.h" +#include "Wireless/Wireless.h" +#include + +using namespace std; + +void ConfigurationEditor::init() { + if(root==NULL) + setRootCollection(config); + pushSlot(NULL); // just to mark as having sub-nodes, will replace during refresh +} + +void ConfigurationEditor::refresh() { + plist::Collection * curcol = (path.size()==0) ? root : dynamic_cast(root->resolveEntry(path)); + if(curcol==NULL) { + clearSlots(); + pushSlot(new NullControl("[NULL Collection]")); + ControlBase::refresh(); + return; + } + for(std::vector::const_iterator it=options.begin(); it!=options.end(); ++it) { + if(StringInputControl * input = dynamic_cast(*it)) { + if(input->getLastInput().size()>0) { + std::string key=input->getName(); + if(dynamic_cast(curcol)) + key=key.substr(0,key.find('=')); + plist::PrimitiveBase * prim = dynamic_cast(curcol->resolveEntry(key)); + if(prim==NULL) { + std::cerr << "ERROR: key " << key << " was set but does not correspond to a primitive value" << std::endl; + continue; + } + try { + prim->set(input->getLastInput()); + } catch(const std::exception& e) { + std::cerr << "ERROR: unable to set key " << key << " to value " << input->getLastInput() << '\n' + << " An exception occurred: " << e.what() << std::endl; + } catch(...) { + std::cerr << "ERROR: unable to set key '" << key << "' to value '" << input->getLastInput() << "', an exception occurred." << std::endl; + } + } + } + } + + for(std::vector::iterator it=options.begin(); it!=options.end(); ++it) + if(*it!=NULL && *it!=&load && *it!=&save) + delete *it; + options.clear(); + pushSlot(&load); + pushSlot(&save); + pushSlot(NULL); + if(curcol->size()==0) { + pushSlot(new NullControl("[Empty Collection]")); + } else if(plist::Dictionary * d = dynamic_cast(curcol)) { + for(plist::Dictionary::const_iterator it=d->begin(); it!=d->end(); ++it) { + if(plist::NamedEnumerationBase * neb = dynamic_cast(it->second)) { + pushSlot(new NamedEnumerationEditor(it->first+"="+neb->get(),d->getComment(it->first),*neb)); + } else if(plist::PrimitiveBase * po = dynamic_cast(it->second)) { + pushSlot(new StringInputControl(it->first+"="+po->get(),d->getComment(it->first))); + } else if(dynamic_cast(it->second)) { + ConfigurationEditor * sube = new ConfigurationEditor(it->first,d->getComment(it->first),root); + sube->setPath(path.size()==0 ? it->first : path+plist::Collection::subCollectionSep()+it->first); + pushSlot(sube); + } else { + std::cerr << "WARNING: unknown type for " << it->first << ": " << it->second->toString() << std::endl; + } + } + } else if(plist::ArrayBase * a = dynamic_cast(curcol)) { + for(unsigned int i=0; i!=a->size(); ++i) { + if(plist::NamedEnumerationBase * neb = dynamic_cast(&a->getEntry(i))) { + pushSlot(new NamedEnumerationEditor(neb->get(),a->getComment(i),*neb)); + } else if(plist::PrimitiveBase * po = dynamic_cast(&a->getEntry(i))) { + pushSlot(new StringInputControl(po->get(),a->getComment(i))); + } else if(dynamic_cast(&a->getEntry(i))) { + ConfigurationEditor * sube = new ConfigurationEditor("",a->getComment(i),root); + stringstream ss; + if(path.size()==0) + ss << i; + else + ss << path << plist::Collection::subCollectionSep() << i; + sube->setPath(ss.str()); + pushSlot(sube); + } else { + std::cerr << "WARNING: unknown type for entry " << i << ": " << a->getEntry(i).toString() << std::endl; + } + } + } + ControlBase::refresh(); +} + +void ConfigurationEditor::clearSlots() { + // don't erase load or save controls -- we'll reuse them + for(std::vector::iterator it=options.begin(); it!=options.end(); ++it) + if(*it==&load || *it==&save) + *it=NULL; + ControlBase::clearSlots(); +} + +void ConfigurationEditor::setRootCollection(plist::Collection* rootCollection) { + if(root==rootCollection) + return; + root=rootCollection; + load.setRootCollection(root); + save.setRootCollection(root); + for(unsigned int i=0; i(options[i])) + confe->setRootCollection(root); +} + +void ConfigurationEditor::setPath(const std::string& p) { + path=p; +} + +plist::Dictionary& ConfigurationEditor::getObjectTemplates() { + static plist::Dictionary dict; + if(dict.size()==0) { + //first call, set up + dict.addEntry("float",new plist::Primitive); + dict.addEntry("int",new plist::Primitive); + dict.addEntry("int (unsigned)",new plist::Primitive); + dict.addEntry("string",new plist::Primitive); + dict.addEntry("sub-array",new plist::Array); + dict.addEntry("sub-dictionary",new plist::Dictionary); + } + return dict; +} + +ControlBase* ConfigurationEditor::LoadSettings::selectedFile(const std::string& f) { + if(rootcol==NULL) { + std::cerr << "ERROR: Unable to load, no plist::Collection has been provided" << std::endl; + return NULL; + } + rootcol->loadFile(f.c_str()); + return NULL; +} +ControlBase* ConfigurationEditor::SaveSettings::selectedFile(const std::string& f) { + if(rootcol==NULL) { + std::cerr << "ERROR: Unable to save, no plist::Collection has been provided" << std::endl; + return NULL; + } + rootcol->saveFile(f.c_str()); + return NULL; +} + +void ConfigurationEditor::AddCollectionEntry::refresh() { + options.clear(); + for(plist::Dictionary::const_iterator it=ConfigurationEditor::getObjectTemplates().begin(); it!=ConfigurationEditor::getObjectTemplates().end(); ++it) { + if(tgt->canContain(*it->second)) { + pushSlot(new ConfigurationEditor::NewCollectionEntry(it->first,*tgt,static_cast(*it->second->clone()))); + } + } +} + +void ConfigurationEditor::NewCollectionEntry::refresh() { + std::string key; + if(options.size()>0 && options[0]!=NULL) + key=dynamic_cast(*options[0]).getLastInput(); + options.clear(); + StringInputControl * keyEdit=NULL; + if(dynamic_cast(tgt)) { + keyEdit = new StringInputControl("Key: "+key,"Enter key for the dictionary entry"); + } else if(dynamic_cast(tgt)) { + if(key=="") + key="end"; + keyEdit = new StringInputControl("Position: "+key,"Enter an index position or keyword 'end', optionally followed by '-n' to offset from the end"); + } + keyEdit->takeInput(key); + pushSlot(keyEdit); + if(plist::PrimitiveBase * po = dynamic_cast(obj)) { + pushSlot(new StringInputControl(po->get(),"Enter the intial value for the item")); + } else if(plist::Collection * c = dynamic_cast(obj)) { + ConfigurationEditor * sube = new ConfigurationEditor("sub-entries...","Add entries to the new collection",c); + pushSlot(sube); + } else if(obj!=NULL) { + std::cerr << "WARNING: unknown type for NewCollectionEntry editor" << ": " << obj->toString() << std::endl; + } + pushSlot(NULL); + pushSlot(new NullControl("Commit Entry")); +} + +ControlBase * ConfigurationEditor::NewCollectionEntry::doSelect() { + if(hilights.size()!=1 || hilights.front()!=options.size()-1) + return ControlBase::doSelect(); + + if(plist::Dictionary* d = dynamic_cast(tgt)) { + std::string key = dynamic_cast(*options[0]).getLastInput(); + d->addEntry(key,obj); + } else if(plist::ArrayBase* a = dynamic_cast(tgt)) { + std::string key = dynamic_cast(*options[0]).getLastInput(); + int idx; + if(key=="" || string_util::makeLower(key).substr(0,3)=="end") { + idx=a->size(); + if(key.size()>3) + idx+=atoi(key.substr(3).c_str()); + } else { + idx=atoi(key.c_str()) % (options.size()+1); + if(idx<0) + idx+=options.size()+1; + } + reinterpret_cast*>(a)->addEntry(idx,obj); + } + return NULL; +} + +void ConfigurationEditor::NamedEnumerationEditor::refresh() { + options.clear(); + std::map names; + tgt->getPreferredNames(names); + for(std::map::const_iterator it=names.begin(); it!=names.end(); ++it) + pushSlot(new NullControl(it->second)); + ControlBase::refresh(); + if(gui_comm!=NULL && wireless->isConnected(gui_comm->sock)) { + if(userPrompt.size()>0) + gui_comm->printf("status\n%td\n%s\n",std::count(userPrompt.begin(),userPrompt.end(),'\n'),userPrompt.c_str()); + } +} + +ControlBase * ConfigurationEditor::NamedEnumerationEditor::doSelect() { + if(hilights.size()!=1) + return this; + clearLastInput(); + tgt->set(options[hilights.front()]->getName()); + return NULL; +} + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.2 $ + * $State: Exp $ + * $Date: 2007/11/13 04:16:00 $ + */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/ConfigurationEditor.h ./Behaviors/Controls/ConfigurationEditor.h --- ../Tekkotsu_3.0/Behaviors/Controls/ConfigurationEditor.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Controls/ConfigurationEditor.h 2007-01-30 17:56:18.000000000 -0500 @@ -0,0 +1,171 @@ +//-*-c++-*- +#ifndef INCLUDED_ConfigurationEditor_h +#define INCLUDED_ConfigurationEditor_h + +#include "Behaviors/Controls/ControlBase.h" +#include "Behaviors/Controls/FileInputControl.h" +#include "Behaviors/Controls/StringInputControl.h" + +//! Provides interactive editing and loading/saving of a plist::Collection +class ConfigurationEditor : public ControlBase { + + // **************************** // + // ******* CONSTRUCTORS ******* // + // **************************** // +public: + //! default constructor + ConfigurationEditor(plist::Collection * rootCollection=NULL) + : ControlBase("ConfigurationEditor","Provides interactive editing and loading/saving of a plist::Collection"), + root(rootCollection), path(), load(rootCollection), save(rootCollection) + {init();} + //! constructor which allows a custom name + ConfigurationEditor(const std::string& n, plist::Collection * rootCollection=NULL) + : ControlBase(n,"Provides interactive editing and loading/saving of a plist::Collection"), + root(rootCollection), path(), load(rootCollection), save(rootCollection) + {init();} + //! constructor which allows a custom name and tooltip + ConfigurationEditor(const std::string& n, const std::string& d, plist::Collection * rootCollection=NULL) + : ControlBase(n,d), root(rootCollection), path(), load(rootCollection), save(rootCollection) + {init();} + + //! destructor, have to do our custom clearSlots before the superclass tries to + virtual ~ConfigurationEditor() { clearSlots(); } + +protected: + //! common initialization regardless of constructor + virtual void init(); + + + + // **************************** // + // ********* METHODS ********** // + // **************************** // +public: + //! called when a child has deactivated and this control should refresh its display, or some other event (such as the user pressing the refresh button) has happened to cause a refresh to be needed + virtual void refresh(); + + //! need to override clearing so we don't delete #load and #save + virtual void clearSlots(); + + //! sets the root of the collection being managed + virtual void setRootCollection(plist::Collection* rootCollection); + + //! sets the path to the sub-collection being managed + virtual void setPath(const std::string& p); + + //! returns a dictionary of plist objects which may be added as new entries to collections being edited + static plist::Dictionary& getObjectTemplates(); + + + // **************************** // + // ********* MEMBERS ********** // + // **************************** // +protected: + plist::Collection * root; //!< the root of collection being edited (i.e. may be the parent or other ancestor of the collection this editor is targeting, see #path) + std::string path; //!< the names of the sub-collections from #root to get to the collection this instance is actually targeting + + //! provides a file browser to load a plist from the file system + class LoadSettings : public FileInputControl { + public: + //! constructor, if rootCollection is NULL, you must call setRootCollection() with a non-NULL value at some point before user tries to activate the control + LoadSettings(plist::Collection * rootCollection) : FileInputControl("Load...","Load settings from disk","config"), rootcol(rootCollection) {} + //! assigns #rootcol + virtual void setRootCollection(plist::Collection* rootCollection) { rootcol=rootCollection; } + protected: + virtual ControlBase* selectedFile(const std::string& f); + plist::Collection * rootcol; //!< the collection to be saved (generally the top level of the collection, even if currently editing within a sub-collection) + private: + LoadSettings(const LoadSettings&); //!< not supported + LoadSettings& operator=(const LoadSettings&); //!< not supported + }; + LoadSettings load; //!< reuse the same load instance instead of regenerating a new one each refresh (saves user's "working directory") + + //! provides a file browser to save a plist from the file system + class SaveSettings : public FileInputControl { + public: + //! constructor, if rootCollection is NULL, you must call setRootCollection() with a non-NULL value at some point before user tries to activate the control + SaveSettings(plist::Collection * rootCollection) : FileInputControl("Save...","Save settings to disk","config"), rootcol(rootCollection) { setAcceptNonExistant(true); } + //! assigns #rootcol + virtual void setRootCollection(plist::Collection* rootCollection) { rootcol=rootCollection; } + protected: + virtual ControlBase* selectedFile(const std::string& f); + plist::Collection * rootcol; //!< the collection to be saved (generally the top level of the collection, even if currently editing within a sub-collection) + private: + SaveSettings(const SaveSettings&); //!< not supported + SaveSettings& operator=(const SaveSettings&); //!< not supported + }; + SaveSettings save; //!< reuse the same save instance instead of regenerating a new one each refresh (saves user's "working directory") + + //! displays a list of template objects (see ConfigurationEditor::getObjectTemplates()) which can be added to a target collection + class AddCollectionEntry : public ControlBase { + public: + AddCollectionEntry(plist::Collection& target) : ControlBase("Add New Entry"), tgt(&target) {} + virtual void refresh(); + virtual void deactivate() { clearSlots(); ControlBase::deactivate(); } + protected: + plist::Collection * tgt; + private: + AddCollectionEntry(const AddCollectionEntry&); //!< not supported + AddCollectionEntry& operator=(const AddCollectionEntry&); //!< not supported + }; + + //! provides interface to set up a new collection entry before inserting it + class NewCollectionEntry : public ControlBase { + public: + NewCollectionEntry(const std::string& n, plist::Collection& target, plist::ObjectBase& templ) : ControlBase(n), tgt(&target), obj(&templ) {} + virtual void refresh(); + virtual void deactivate() { clearSlots(); ControlBase::deactivate(); } + virtual ControlBase * doSelect(); + protected: + plist::Collection * tgt; + plist::ObjectBase * obj; + private: + NewCollectionEntry(const NewCollectionEntry&); //!< not supported + NewCollectionEntry& operator=(const NewCollectionEntry&); //!< not supported + }; + + //! based on a string input control for easier mixing with other primitives (which just use a basic string input control as an editor) + /*! If selected, provides a submenu with symbolic options to better prompt the user with valid values */ + class NamedEnumerationEditor : public StringInputControl { + public: + //! constructor + NamedEnumerationEditor(const std::string& n, const std::string& prompt, plist::NamedEnumerationBase& target) : StringInputControl(n,prompt), tgt(&target) {} + virtual void refresh(); + //! purposely clearing slots on deactivate to avoid having sub-menus -- don't want to appear as a collection + virtual void deactivate() { clearSlots(); StringInputControl::deactivate(); } + //! handles selecting one of the symbolic values + virtual ControlBase * doSelect(); + //! override to only allow one hilight (first in the list) + virtual void setHilights(const std::vector& hi) { + if(hi.empty()) + StringInputControl::setHilights(hi); + else // go straight to control base + ControlBase::setHilights(std::vector(1,hi.front())); + } + protected: + plist::NamedEnumerationBase * tgt; //!< the value being edited + private: + NamedEnumerationEditor(const NamedEnumerationEditor&); //!< not supported + NamedEnumerationEditor& operator=(const NamedEnumerationEditor&); //!< not supported + }; + + + // **************************** // + // ********** OTHER *********** // + // **************************** // +private: + ConfigurationEditor(const ConfigurationEditor&); //!< you can override, but don't call this... + ConfigurationEditor& operator=(const ConfigurationEditor&); //!< you can override, but don't call this... +}; + +/*! @file + * @brief Defines ConfigurationEditor, which provides interactive editing and loading/saving of a plist::Collection + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.1 $ + * $State: Exp $ + * $Date: 2007/01/30 22:56:18 $ + */ +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/ControlBase.cc ./Behaviors/Controls/ControlBase.cc --- ../Tekkotsu_3.0/Behaviors/Controls/ControlBase.cc 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/ControlBase.cc 2007-01-30 17:56:18.000000000 -0500 @@ -70,14 +70,18 @@ ss << "refresh\n" << getName() << '\n' << options.size() << '\n'; - for(unsigned int i=0; igetDescription(); ss << options[i]->options.size() << '\n' << (binary_search(hilights.begin(),hilights.end(),i)?1:0) << '\n' << options[i]->getName() << '\n' - << options[i]->getDescription().c_str() << '\n'; + << std::count(desc.begin(),desc.end(),'\n') << '\n' + << desc << '\n'; + } + } // do { //cout << "Writing " << ss.str().size() << "..."; gui_comm->write((const byte*)ss.str().c_str(),ss.str().size()); @@ -207,8 +211,10 @@ return this; } else { //Level 3: GUI - if(prompt.size()>0) - gui_comm->printf("status\n%s\n",prompt.c_str()); + if(prompt.size()>0) { + unsigned int lines=std::count(prompt.begin(),prompt.end(),'\n'); + gui_comm->printf("status\n%u\n%s\n",lines,prompt.c_str()); + } return this; } } @@ -262,12 +268,7 @@ clearMenu(); doRewrite=false; } - if(ambiguous) - serr->printf("ControlBase(\"%s\")::takeInput(\"%s\") was ambiguous\n",name.c_str(),args[0].c_str()); - else - serr->printf("ControlBase(\"%s\")::takeInput(\"%s\") was not a valid index or option name.\n",name.c_str(),args[0].c_str()); - refresh(); - return this; + return invalidInput(str,ambiguous); } else if(choiceprintf("ControlBase(\"%s\")::takeInput(\"%s\") was ambiguous\n",name.c_str(),args[0].c_str()); - else - serr->printf("ControlBase(\"%s\")::takeInput(\"%d\") is not a valid selection\n",name.c_str(),choice); - refresh(); - return this; + return invalidInput(str,ambiguous); } } //see what we got... @@ -397,6 +393,15 @@ } } +ControlBase* ControlBase::invalidInput(const std::string& msg, bool ambiguous) { + if(ambiguous) + serr->printf("ControlBase(\"%s\")::takeInput(\"%s\") was ambiguous\n",name.c_str(),msg.c_str()); + else + serr->printf("ControlBase(\"%s\")::takeInput(\"%s\") was not a valid index or option name.\n",name.c_str(),msg.c_str()); + refresh(); + return this; +} + float ControlBase::hilightsAvg() const { if(hilights.size()==0) return -1; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/ControlBase.h ./Behaviors/Controls/ControlBase.h --- ../Tekkotsu_3.0/Behaviors/Controls/ControlBase.h 2004-11-03 22:01:31.000000000 -0500 +++ ./Behaviors/Controls/ControlBase.h 2006-10-30 16:26:23.000000000 -0500 @@ -68,7 +68,7 @@ //! @name Constructors/Destructors ControlBase() : name("(null name)"), description(), hilights(), options(), doRewrite(false), display_id(MotionManager::invalid_MC_ID), gui_comm(NULL) {} //!< Contructor - ControlBase(const std::string& n) : name(n), description(), hilights(), options(), doRewrite(false), display_id(MotionManager::invalid_MC_ID), gui_comm(NULL) {} //!< Contructor, initializes with a name + ControlBase(const std::string& n) : name(n), description((n.size()>16)?n:std::string()), hilights(), options(), doRewrite(false), display_id(MotionManager::invalid_MC_ID), gui_comm(NULL) {} //!< Contructor, initializes with a name ControlBase(const std::string& n, const std::string& d) : name(n), description(d), hilights(), options(), doRewrite(false), display_id(MotionManager::invalid_MC_ID), gui_comm(NULL) {} //!< Contructor, initializes with a name //! Destructor @@ -142,6 +142,11 @@ //! clears the display (if use_VT100 is on) virtual void clearMenu(); + + //! called by takeInput if the input doesn't match any slots or matches multiple slots -- the ControlBase implementation displays an error and returns itself + /*! @param msg the input originally sent to takeInput() + * @param ambiguous true if the input matched more than one item, false if it didn't match any */ + virtual ControlBase* invalidInput(const std::string& msg, bool ambiguous); //! returns the average of the hilighted indicies - used to know to play the "next" sound, or the "prev" sound when the hilight changes float hilightsAvg() const; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/EventLogger.cc ./Behaviors/Controls/EventLogger.cc --- ../Tekkotsu_3.0/Behaviors/Controls/EventLogger.cc 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/EventLogger.cc 2007-11-11 18:57:18.000000000 -0500 @@ -19,12 +19,14 @@ unsigned int EventLogger::logSocketRefCount=0; int EventLogger::port=10080; EventLogger * EventLogger::theOne=NULL; +EventLogger::queuedEvents_t EventLogger::queuedEvents; +EventLogger::transStack_t EventLogger::transStack; EventLogger::StateMachineListener EventLogger::smProcess; EventLogger::EventLogger() : ControlBase("Event Logger","Allows you to see/log all of the un-trapped events as they are generated"), - logfilePath(), logfile(), verbosity(0), expected(), listen(), queuedEvents() { + logfilePath(), logfile(), verbosity(0), listen() { for(unsigned int i=0; isocket(SocketNS::SOCK_STREAM,1024,1<<15); + logSocket=wireless->socket(Socket::SOCK_STREAM,1024,1<<15); wireless->setDaemon(logSocket); wireless->setReceiver(logSocket, callback); wireless->listen(logSocket,port); @@ -45,7 +47,6 @@ } EventLogger::~EventLogger() { - expected.clear(); while(!queuedEvents.empty()) queuedEvents.pop(); clearSlots(); @@ -104,7 +105,6 @@ if(options[EventBase::numEGIDs+2]->getName()[1]=='X') sout->printf("EVENT: %s\n",logdata.c_str()); if(logSocket!=NULL && wireless->isConnected(logSocket->sock)) { - xmlDoc * doc = xmlNewDoc((const xmlChar*)"1.0"); xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)""); xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"log"); xmlNode * desc = xmlNewNode(NULL,(const xmlChar*)"param"); @@ -113,7 +113,9 @@ xmlSetProp(desc,(const xmlChar*)"name",(const xmlChar*)"description"); xmlSetProp(desc,(const xmlChar*)"value",(const xmlChar*)event.getDescription(true,3).c_str()); xmlBuffer* buf=xmlBufferCreate(); + xmlDoc * doc = xmlNewDoc((const xmlChar*)"1.0"); int n=xmlNodeDump(buf,doc,cur,0,1); + xmlFreeNode(cur); xmlFreeDoc(doc); byte * nbuf = logSocket->getWriteBuffer(n+1); if(nbuf!=NULL) { @@ -125,101 +127,79 @@ } checkLogFile(); if(logfile) - logfile << logdata << endl; + logfile << logdata << std::endl; } void EventLogger::logImage(FilterBankGenerator& fbg, unsigned int layer, unsigned int channel, const BehaviorBase* source/*=NULL*/) { - if(logSocket!=NULL && wireless->isConnected(logSocket->sock)) { + if(logSocket==NULL || !wireless->isConnected(logSocket->sock)) + return; - char * binbuf; - unsigned int len; - if(JPEGGenerator* jpeg=dynamic_cast(&fbg)) { - binbuf=(char*)jpeg->getImage(layer,channel); - len=jpeg->getImageSize(layer,channel); - } else { - fbg.selectSaveImage(layer,channel); - len=fbg.getBinSize(); - binbuf=new char[len]; - fbg.saveBuffer(binbuf,len); - } - string b64buf=base64::encode(binbuf,len); - if(binbuf!=(char*)fbg.getImage(layer,channel)) //cached, should be a simple return - delete [] binbuf; - - xmlDoc * doc = xmlNewDoc((const xmlChar*)"1.0"); - xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"event"); - xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"image"); - if(source!=NULL) - xmlSetProp(cur,(const xmlChar*)"sid",(const xmlChar*)source->getName().c_str()); - char timebuf[20]; - snprintf(timebuf,20,"%d",get_time()); - xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)timebuf); - xmlNewChild(cur,NULL,(const xmlChar*)"image",(const xmlChar*)b64buf.c_str()); - xmlBuffer* buf=xmlBufferCreate(); - int n=xmlNodeDump(buf,doc,cur,0,1); - xmlFreeDoc(doc); - byte * nbuf = logSocket->getWriteBuffer(n+1); - if(nbuf!=NULL) { - memcpy(nbuf,xmlBufferContent(buf),n); - nbuf[n]='\n'; - logSocket->write(n+1); - } - xmlBufferFree(buf); - } + char * binbuf; + unsigned int len; + if(JPEGGenerator* jpeg=dynamic_cast(&fbg)) { + binbuf=(char*)jpeg->getImage(layer,channel); + len=jpeg->getImageSize(layer,channel); + } else { + fbg.selectSaveImage(layer,channel); + len=fbg.getBinSize(); + binbuf=new char[len]; + fbg.saveBuffer(binbuf,len); + } + std::string b64buf=base64::encode(binbuf,len); + if(binbuf!=(char*)fbg.getImage(layer,channel)) //cached, should be a simple return + delete [] binbuf; + + xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"event"); + xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"image"); + if(source!=NULL) + xmlSetProp(cur,(const xmlChar*)"sid",(const xmlChar*)source->getName().c_str()); + char timebuf[20]; + snprintf(timebuf,20,"%d",get_time()); + xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)timebuf); + xmlNewChild(cur,NULL,(const xmlChar*)"image",(const xmlChar*)b64buf.c_str()); + queuedEvents.push(cur); + if(transStack.empty()) + dumpQueuedEvents(); } void EventLogger::logMessage(std::string msg, const BehaviorBase* source/*=NULL*/, const char* icon/*=NULL*/, unsigned int placement/*=0*/) { - if(logSocket!=NULL && wireless->isConnected(logSocket->sock)) { - xmlDoc * doc = xmlNewDoc((const xmlChar*)"1.0"); - xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"event"); - xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"userlog"); - if(source!=NULL) - xmlSetProp(cur,(const xmlChar*)"sid",(const xmlChar*)source->getName().c_str()); - if(icon!=NULL) - xmlSetProp(cur,(const xmlChar*)"icon",(const xmlChar*)icon); - const unsigned int len=20; - char sbuf[len]; - snprintf(sbuf,len,"%d",placement); - xmlSetProp(cur,(const xmlChar*)"voff",(const xmlChar*)sbuf); - snprintf(sbuf,len,"%d",get_time()); - xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)sbuf); - xmlNodeSetContent(cur,(const xmlChar*)msg.c_str()); - xmlBuffer* buf=xmlBufferCreate(); - int n=xmlNodeDump(buf,doc,cur,0,1); - xmlFreeDoc(doc); - byte * nbuf = logSocket->getWriteBuffer(n+1); - if(nbuf!=NULL) { - memcpy(nbuf,xmlBufferContent(buf),n); - nbuf[n]='\n'; - logSocket->write(n+1); - } - xmlBufferFree(buf); - } + if(logSocket==NULL || !wireless->isConnected(logSocket->sock)) + return; + + xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"event"); + xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"userlog"); + if(source!=NULL) + xmlSetProp(cur,(const xmlChar*)"sid",(const xmlChar*)source->getName().c_str()); + if(icon!=NULL) + xmlSetProp(cur,(const xmlChar*)"icon",(const xmlChar*)icon); + const unsigned int len=20; + char sbuf[len]; + snprintf(sbuf,len,"%d",placement); + xmlSetProp(cur,(const xmlChar*)"voff",(const xmlChar*)sbuf); + snprintf(sbuf,len,"%d",get_time()); + xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)sbuf); + xmlNodeSetContent(cur,(const xmlChar*)msg.c_str()); + queuedEvents.push(cur); + if(transStack.empty()) + dumpQueuedEvents(); } void EventLogger::logWebcam(const BehaviorBase* source/*=NULL*/) { - if(logSocket!=NULL && wireless->isConnected(logSocket->sock)) { - xmlDoc * doc = xmlNewDoc((const xmlChar*)"1.0"); - xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"event"); - xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"webcam"); - if(source!=NULL) - xmlSetProp(cur,(const xmlChar*)"sid",(const xmlChar*)source->getName().c_str()); - const unsigned int len=20; - char sbuf[len]; - snprintf(sbuf,len,"%d",get_time()); - xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)sbuf); - xmlNodeSetContent(cur,(const xmlChar*)" "); - xmlBuffer* buf=xmlBufferCreate(); - int n=xmlNodeDump(buf,doc,cur,0,1); - xmlFreeDoc(doc); - byte * nbuf = logSocket->getWriteBuffer(n+1); - if(nbuf!=NULL) { - memcpy(nbuf,xmlBufferContent(buf),n); - nbuf[n]='\n'; - logSocket->write(n+1); - } - xmlBufferFree(buf); - } + if(logSocket==NULL || !wireless->isConnected(logSocket->sock)) + return; + + xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"event"); + xmlSetProp(cur,(const xmlChar*)"type",(const xmlChar*)"webcam"); + if(source!=NULL) + xmlSetProp(cur,(const xmlChar*)"sid",(const xmlChar*)source->getName().c_str()); + const unsigned int len=20; + char sbuf[len]; + snprintf(sbuf,len,"%d",get_time()); + xmlSetProp(cur,(const xmlChar*)"time",(const xmlChar*)sbuf); + xmlNodeSetContent(cur,(const xmlChar*)" "); + queuedEvents.push(cur); + if(transStack.empty()) + dumpQueuedEvents(); } void EventLogger::clearSlots() { @@ -255,50 +235,53 @@ } -void EventLogger::spider(const StateNode* n, unsigned int depth/*=0*/) { +void EventLogger::spider(const StateNode* n, xmlNode* parent/*=NULL*/) { if(n==NULL) return; + xmlNode * cur = xmlNewNode(NULL,(const xmlChar*)"state"); + ASSERTRET(cur!=NULL,"EventLogger::spider() could not allocate new xml state node"); + xmlSetProp(cur,(const xmlChar*)"class",(const xmlChar*)n->getClassName().c_str()); + xmlSetProp(cur,(const xmlChar*)"id",(const xmlChar*)n->getName().c_str()); + const std::vector& subnodes=n->getNodes(); - if(subnodes.size()==0) { - // it's a leaf node, no subnodes or transitions between them - indent(depth); - logSocket->printf("\n", n->getClassName().c_str(), n->getName().c_str()); - } else { - - // first output current node's info - indent(depth); - logSocket->printf("\n", n->getClassName().c_str(), n->getName().c_str()); + if(subnodes.size()>0) { + // it's not a leaf node, has subnodes and transitions between them std::set transitions; // now recurse on sub-nodes, extracting all of the subnodes transitions for(unsigned int i=0; i& curt=subnodes[i]->getTransitions(); transitions.insert(curt.begin(),curt.end()); } // now output transitions between subnodes we collected in previous step for(std::set::const_iterator it=transitions.begin(); it!=transitions.end(); it++) { - indent(depth+1); - logSocket->printf("\n", (*it)->getClassName().c_str(), (*it)->getName().c_str()); - const std::vector& incoming=(*it)->getSources(); - for(unsigned int i=0; iprintf("%s\n",incoming[i]->getName().c_str()); + xmlNode * t = xmlAddChild(cur,xmlNewNode(NULL,(const xmlChar*)"transition")); + ASSERTRET(t!=NULL,"EventLogger::spider() could not allocate new xml transition node"); + xmlSetProp(t,(const xmlChar*)"class",(const xmlChar*)(*it)->getClassName().c_str()); + xmlSetProp(t,(const xmlChar*)"id",(const xmlChar*)(*it)->getName().c_str()); + + typedef std::vector statevec_t; + const statevec_t& incoming=(*it)->getSources(); + for(statevec_t::const_iterator nit=incoming.begin(); nit!=incoming.end(); ++nit) { + xmlNode * sn = xmlAddChild(t,xmlNewNode(NULL,(const xmlChar*)"source")); + ASSERTRET(sn!=NULL,"EventLogger::spider() could not allocate new xml transition source node"); + xmlNodeSetContent(sn,(const xmlChar*)(*nit)->getName().c_str()); } - const std::vector& outgoing=(*it)->getDestinations(); - for(unsigned int i=0; iprintf("%s\n",outgoing[i]->getName().c_str()); + const statevec_t& outgoing=(*it)->getDestinations(); + for(statevec_t::const_iterator nit=outgoing.begin(); nit!=outgoing.end(); ++nit) { + xmlNode * sn = xmlAddChild(t,xmlNewNode(NULL,(const xmlChar*)"destination")); + ASSERTRET(sn!=NULL,"EventLogger::spider() could not allocate new xml transition source node"); + xmlNodeSetContent(sn,(const xmlChar*)(*nit)->getName().c_str()); } - indent(depth+1); - logSocket->printf("\n"); } - - indent(depth); - logSocket->printf("\n"); } + if(parent==NULL) + dumpNode(cur); + else + xmlAddChild(parent,cur); } bool EventLogger::isListening(const StateNode* n) { @@ -389,13 +372,13 @@ return 0; } -void EventLogger::processStateMachineEvent(const EventBase& event) { +void EventLogger::processStateMachineEvent(const EventBase& e) { if(!wireless->isConnected(logSocket->sock) || listen.size()==0) return; - - if(event.getGeneratorID()==EventBase::stateTransitionEGID) { + + if(e.getGeneratorID()==EventBase::stateTransitionEGID) { bool care=false; - const Transition * trans = reinterpret_cast(event.getSourceID()); + const Transition * trans = reinterpret_cast(e.getSourceID()); const std::vector& incoming=trans->getSources(); const std::vector& outgoing=trans->getDestinations(); for(std::vector::const_iterator it=incoming.begin(); it!=incoming.end() && !care; it++) @@ -404,62 +387,75 @@ care=isListening(*it); if(!care) return; - - if(expected.size()!=0) { - queuedEvents.push(event); + + if(e.getTypeID()==EventBase::activateETID) { + xmlNode * root = xmlNewNode(NULL,(const xmlChar*)"event"); + xmlNode * fire = xmlAddChild(root,xmlNewNode(NULL,(const xmlChar*)"fire")); + xmlSetProp(fire,(const xmlChar*)"id",(const xmlChar*)trans->getName().c_str()); + const unsigned int len=20; + char sbuf[len]; + snprintf(sbuf,len,"%d",e.getTimeStamp()); + xmlSetProp(fire,(const xmlChar*)"time",(const xmlChar*)sbuf); + transStack.push(root); + queuedEvents.push(root); } else { - logSocket->printf("\n"); - indent(1); - logSocket->printf("\n",trans->getName().c_str(),event.getTimeStamp()); - expected.insert(incoming.begin(),incoming.end()); - expected.insert(outgoing.begin(),outgoing.end()); - while(queuedEvents.size()>0) { - EventBase qe=queuedEvents.front(); - queuedEvents.pop(); - processEvent(qe); - } + ASSERTRET(!transStack.empty(),"got a transition deactivate that I should care about, but I didn't see the activate"); + transStack.pop(); + if(transStack.empty()) + dumpQueuedEvents(); } - - } else if(event.getGeneratorID()==EventBase::stateMachineEGID) { - if(event.getTypeID()==EventBase::statusETID) + + } else if(e.getGeneratorID()==EventBase::stateMachineEGID) { + if(e.getTypeID()==EventBase::statusETID) + return; + const StateNode * beh=reinterpret_cast(e.getSourceID()); + if(!isListening(beh)) + return; + if(e.getTypeID()!=EventBase::activateETID && e.getTypeID()!=EventBase::deactivateETID) { + serr->printf("WARNING: Unrecognized TypeID %d\n",e.getTypeID()); return; - const StateNode * beh=reinterpret_cast(event.getSourceID()); - expected_t::iterator it=expected.find(beh); - char * format; - if(isListening(beh)) { - if(it==expected.end()) { //if not found - if(queuedEvents.size()==0) - format="\n"; // unexpected - else { - queuedEvents.push(event); - return; - } - } else - format=" \n"; // expected as part of transition - if(event.getTypeID()==EventBase::activateETID) - logSocket->printf(format,"start",beh->getName().c_str(),event.getTimeStamp()); - else if(event.getTypeID()==EventBase::deactivateETID) - logSocket->printf(format,"stop",beh->getName().c_str(),event.getTimeStamp()); - else - serr->printf("WARNING: Unrecognized TypeID %d\n",event.getTypeID()); } - if(it!=expected.end()) { //was found - expected.erase(it); - if(expected.size()==0) { - logSocket->printf("\n"); - while(queuedEvents.size()>0) { - EventBase qe=queuedEvents.front(); - queuedEvents.pop(); - processEvent(qe); - } - } + + xmlNode * root = transStack.empty() ? xmlNewNode(NULL,(const xmlChar*)"event") : transStack.top(); + const char* sttypestr = (e.getTypeID()==EventBase::activateETID) ? "statestart" : "statestop"; + xmlNode * st = xmlAddChild(root,xmlNewNode(NULL,(const xmlChar*)sttypestr)); + xmlSetProp(st,(const xmlChar*)"id",(const xmlChar*)beh->getName().c_str()); + const unsigned int len=20; + char sbuf[len]; + snprintf(sbuf,len,"%d",e.getTimeStamp()); + xmlSetProp(st,(const xmlChar*)"time",(const xmlChar*)sbuf); + + if(transStack.empty()) { + queuedEvents.push(root); + dumpQueuedEvents(); } - + } else { - serr->printf("WARNING: Unknown event %s (%s)\n",event.getName().c_str(),event.getDescription().c_str()); + serr->printf("WARNING: Unknown event %s (%s)\n",e.getName().c_str(),e.getDescription().c_str()); } } +void EventLogger::dumpQueuedEvents() { + xmlDoc * doc = xmlNewDoc((const xmlChar*)"1.0"); + while(!queuedEvents.empty()) { + dumpNode(queuedEvents.front(),doc); + queuedEvents.pop(); + } + xmlFreeDoc(doc); +} + +void EventLogger::dumpNode(xmlNode* node, xmlDoc* doc/*=NULL*/) { + xmlBuffer* buf=xmlBufferCreate(); + int n=xmlNodeDump(buf,doc,node,0,1); + byte * nbuf = logSocket->getWriteBuffer(n+1); + if(nbuf!=NULL) { + memcpy(nbuf,xmlBufferContent(buf),n); + nbuf[n]='\n'; + logSocket->write(n+1); + } + xmlBufferFree(buf); + xmlFreeNode(node); +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/EventLogger.h ./Behaviors/Controls/EventLogger.h --- ../Tekkotsu_3.0/Behaviors/Controls/EventLogger.h 2006-09-16 02:28:06.000000000 -0400 +++ ./Behaviors/Controls/EventLogger.h 2007-03-02 12:20:48.000000000 -0500 @@ -7,12 +7,73 @@ #include #include #include +#include class FilterBankGenerator; class BehaviorBase; class StateNode; -//! allows logging of events to the console or a file +//! allows logging of events to the console or a file, also provides some remote logging facilities over #logSocket, required by Storyboard tool +/*! Users' behaviors can call logMessage(), logImage(), and logWebcam() to insert the corresponding data into #logSocket via an XML 'event' node. + * + * The protocol used with #logSocket is: + * - 'list' - send list of all instantiated StateNodes + * - 'spider name' - spider the current structure of StateNode named name + * - 'listen name' - send updates regarding the activation status of name and its subnodes; you can specify a state which is not yet running + * - 'ignore name' - cancels a previous listen command + * - 'clear' - cancels all previous listen commands; should be called at the beginning or end of each connection, preferably both + * + * Each of those commands should be terminated with a newline - + * i.e. one command per line + * + * After a list command, the first line will be the number + * of StateNodes, followed by that number of lines, one StateNode + * name per line. + * + * After a spider command, an XML description of the model + * will be sent. If no matching StateNode is found, an warning will + * be displayed on #serr, and an empty model + * ("") returned over the network + * connection. + * + * All other commands give no direct response - listen can be + * executed before the specified StateNode is yet running, and ignore + * doesn't care whether or not the specified StateNode was actually + * being listened for. + * + * The format of the model is: + @verbatim + + + + + + + + + + + ]>@endverbatim + * + * The format of status updates following a listen command is: + @verbatim + + + + + + + + + + + + ]>@endverbatim + * + * The 'event' node is also used for the results of logImage(), logMessage(), and logWebcam(). +*/ class EventLogger : public ControlBase, public EventListener { public: //!constructor @@ -70,7 +131,8 @@ void checkLogFile(); //! dumps all of the transitions and subnodes of a given statenode - void spider(const StateNode* n, unsigned int depth=0); + /*! if parent is NULL, will dump the results over #logSocket, otherwise adds the xml tree as a child of @a parent */ + void spider(const StateNode* n, xmlNode* parent=NULL); //! returns true iff @a n or one of its parents is found in #listen bool isListening(const StateNode* n); @@ -88,6 +150,13 @@ /*!this is called by the StateMachineListener, which is subscribed to only * those machines which have been requested by the remote monitor */ virtual void processStateMachineEvent(const EventBase& event); + + //! dumps elements of #queuedEvents over #logSocket, popping and freeing as it goes + static void dumpQueuedEvents(); + + //! writes an xmlNode out over #logSocket, freeing @a node when complete + /*! uses @a doc if provided, otherwise makes a new temporary one which is then deleted again before the function returns */ + static void dumpNode(xmlNode* node, xmlDoc* doc=NULL); //!address of the logfile, if any (empty string is no logfile) std::string logfilePath; @@ -109,14 +178,14 @@ typedef std::set registry_t; //!< the type of the behavior registry (BehaviorBase::registry) - typedef std::multiset expected_t; //!< the type of #expected - expected_t expected; //!< a set of behaviors which are involved with an impending transition - their next stateMachineEGID event should be ignored - typedef std::set listen_t; //!< the type of #listen listen_t listen; //!< a set of state machine names which should have their subnodes monitored - typedef std::queue queuedEvents_t; //!< the type of #queuedEvents - queuedEvents_t queuedEvents; //!< used if a transition causes other transitions, those transitions need to be remembered + typedef std::queue queuedEvents_t; //!< the type of #queuedEvents + static queuedEvents_t queuedEvents; //!< if logImage/logMessage/etc. are called during a transition, need to queue them until the transition event is complete + + typedef std::stack transStack_t; //!< the type of #transStack + static transStack_t transStack; //!< if another transition occurs during the processing of another, have to recurse on processing the new transition first }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/FileBrowserControl.cc ./Behaviors/Controls/FileBrowserControl.cc --- ../Tekkotsu_3.0/Behaviors/Controls/FileBrowserControl.cc 2005-02-02 13:20:27.000000000 -0500 +++ ./Behaviors/Controls/FileBrowserControl.cc 2007-01-28 20:16:57.000000000 -0500 @@ -1,4 +1,6 @@ #include "FileBrowserControl.h" +#include "NullControl.h" +#include "Shared/Config.h" #include #include #include @@ -39,25 +41,49 @@ } ControlBase * FileBrowserControl::takeInput(const std::string& msg) { - if(options.size()==1 && options.front()==NULL) + if(msg.size()==0) + return this; + if(msg.find('/')==string::npos) { + if(options.size()==1 && options.front()==NULL) + rebuildmenu(); + return ControlBase::takeInput(msg); + } else { + string::size_type pos=msg.rfind('/'); + if(msg[0]=='/') { + if(msg.substr(0,root.size())!=root) + return this; + if(msg.size()>root.size() && msg[root.size()]!='/') + return this; + paths.clear(); + if(pos<=root.size()) + return this; + appendPath(msg.substr(root.size(),pos-root.size())); + } else { + appendPath(msg.substr(0,pos)); + } rebuildmenu(); - return ControlBase::takeInput(msg); + if(msg.size()>pos+1) + return ControlBase::takeInput(msg.substr(pos+1)); + return this; + } } void FileBrowserControl::setRoot(const std::string& path) { - root=path; + root=config->portPath(path); if(root[root.size()-1]=='/') root.erase(root.size()-1); paths.clear(); } -void FileBrowserControl::setPath(const std::string& path) { - for(unsigned int i=0; id_name).append(1,'/'))); + pushSlot(new NullControl(std::string(ent->d_name).append(1,'/'),makePath(ent->d_name),this)); } else { std::string nm=(makePath(ent->d_name)); if(match(nm,filter)) - pushSlot(new ControlBase(ent->d_name)); + pushSlot(new NullControl(ent->d_name,makePath(ent->d_name),this)); } } ent=readdir(dir); } closedir(dir); if(options.size()==0) - pushSlot(new ControlBase("[empty directory]")); + pushSlot(new NullControl("[empty directory]",makePath(),this)); else { hilights.push_back(0); /* for(unsigned int i=0; iportPath(config->motion.root)), cp(calp) + : FileBrowserControl("Load Calibration...","",config->motion.root), cp(calp) { setFilter("*.txt"); } //!Constructor LoadCalibration(const std::string& n,WalkMC::CalibrationParam* calp) - : FileBrowserControl(n,"",config->portPath(config->motion.root)), cp(calp) + : FileBrowserControl(n,"",config->motion.root), cp(calp) { setFilter("*.txt"); } //!Constructor LoadCalibration(const std::string& n, const std::string& d,WalkMC::CalibrationParam* calp) - : FileBrowserControl(n,d,config->portPath(config->motion.root)), cp(calp) + : FileBrowserControl(n,d,config->motion.root), cp(calp) { setFilter("*.txt"); } protected: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/LoadPostureControl.h ./Behaviors/Controls/LoadPostureControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/LoadPostureControl.h 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/LoadPostureControl.h 2007-08-05 12:16:04.000000000 -0400 @@ -7,7 +7,9 @@ #include "Motion/MMAccessor.h" #include "Motion/EmergencyStopMC.h" #include "Events/EventRouter.h" -#include "Motion/LedMC.h" +#ifdef TGT_HAS_LEDS +# include "Motion/LedMC.h" +#endif #include "Sound/SoundManager.h" #include @@ -17,7 +19,7 @@ public: //! Constructor LoadPostureControl(const std::string& n, MotionManager::MC_ID estop_id) - : FileBrowserControl(n,"Loads a posture from user-selected file",config->portPath(config->motion.root)), + : FileBrowserControl(n,"Loads a posture from user-selected file",config->motion.root), estopid(estop_id), ledid(MotionManager::invalid_MC_ID), file() { setFilter("*.pos"); @@ -27,6 +29,7 @@ virtual ~LoadPostureControl() { erouter->removeListener(this); motman->removeMotion(ledid); + ledid=MotionManager::invalid_MC_ID; } //! only called when e-stop has been turned off and we're waiting to load a file @@ -55,11 +58,19 @@ } else { //we have to wait for the estop to be turned off sndman->playFile("donkey.wav"); +#ifdef TGT_HAS_LEDS SharedObject led; led->cset(FaceLEDMask,0); - led->cycle(BotLLEDMask,1000,3,0,0); - led->cycle(BotRLEDMask,1000,3,0,500); + unsigned int botl = capabilities.findButtonOffset(ERS210Info::buttonNames[ERS210Info::BotLLEDOffset]); + unsigned int botr = capabilities.findButtonOffset(ERS210Info::buttonNames[ERS210Info::BotRLEDOffset]); + if(botl==-1U || botr==-1U) { + botl=LEDOffset; + botr=NumLEDs>1 ? botl+1 : botl; + } + led->cycle(1<<(botl-LEDOffset),1000,3,0,0); + led->cycle(1<<(botr-LEDOffset),1000,3,0,500); ledid=motman->addPersistentMotion(led); +#endif erouter->addListener(this,EventBase::estopEGID,estopid,EventBase::deactivateETID); } return this; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/LoadWalkControl.h ./Behaviors/Controls/LoadWalkControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/LoadWalkControl.h 2006-09-09 00:32:17.000000000 -0400 +++ ./Behaviors/Controls/LoadWalkControl.h 2007-01-28 20:16:57.000000000 -0500 @@ -12,7 +12,7 @@ public: //! constructor, pass the MC_ID of the WalkMC which you want to save LoadWalkControl(const std::string& n, MotionManager::MC_ID w) - : FileBrowserControl(n,"Loads a set of walk parameters from a file specified by user",config->portPath(config->motion.root)), walk_id(w), thewalk(NULL) + : FileBrowserControl(n,"Loads a set of walk parameters from a file specified by user",config->motion.root), walk_id(w), thewalk(NULL) { setFilter("*.prm"); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/NetworkStatusControl.h ./Behaviors/Controls/NetworkStatusControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/NetworkStatusControl.h 2005-10-25 17:25:33.000000000 -0400 +++ ./Behaviors/Controls/NetworkStatusControl.h 2006-11-22 00:19:21.000000000 -0500 @@ -24,7 +24,7 @@ //! stops listening for power events and sets display to invalid virtual void pause() { - erouter->removeListener(this); + erouter->remove(this); ControlBase::pause(); } //! calls report() @@ -60,7 +60,7 @@ ControlBase::refresh(); } virtual void deactivate() { - erouter->removeListener(this); + erouter->remove(this); ControlBase::deactivate(); } //! refresh the control whenever an event is received diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/NullControl.h ./Behaviors/Controls/NullControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/NullControl.h 2003-09-25 11:26:11.000000000 -0400 +++ ./Behaviors/Controls/NullControl.h 2006-10-30 16:57:08.000000000 -0500 @@ -9,12 +9,15 @@ public: //!Constructor - NullControl() : ControlBase() {} + explicit NullControl(ControlBase * inputRedirectTgt=NULL) : ControlBase(), inputRedirect(inputRedirectTgt) {} //!Constructor - NullControl(const std::string& n) : ControlBase(n) {} + explicit NullControl(const std::string& n, ControlBase * inputRedirectTgt=NULL) : ControlBase(n), inputRedirect(inputRedirectTgt) {} //!Constructor - NullControl(const std::string& n, const std::string& d) : ControlBase(n,d) {} + NullControl(const std::string& n, const std::string& d, ControlBase * inputRedirectTgt=NULL) : ControlBase(n,d), inputRedirect(inputRedirectTgt) {} + virtual void setInputRedirect(ControlBase* inputRedirectTgt) { inputRedirect=inputRedirectTgt; } //!< sets #inputRedirect + virtual ControlBase* getInputRedirect() const { return inputRedirect; } //!< returns #inputRedirect + //@{ //! returns NULL virtual ControlBase * activate(MotionManager::MC_ID , Socket * ) { return NULL; } @@ -23,8 +26,20 @@ virtual ControlBase * doNextItem() { return NULL; } virtual ControlBase * doPrevItem() { return NULL; } virtual ControlBase * doReadStdIn(const std::string& /*prompt*/=std::string()) { return NULL; } - virtual ControlBase * takeInput(const std::string& /*msg*/) { return NULL; } //@} + + //! returns NULL unless #inputRedirect is set, in which case it will return inputRedirect->takeInput(msg) + virtual ControlBase * takeInput(const std::string& msg) { return (inputRedirect==NULL) ? NULL : inputRedirect->takeInput(msg); } + +protected: + //! the target to receiving forwarding of any calls to takeInput() + /*! this is handy if this instance is some feedback to the user, and any input they + * enter with this control selected only makes sense to be handled by the parent */ + ControlBase* inputRedirect; + +private: + NullControl(const NullControl&); //!< you can override, but don't call this... + NullControl& operator=(const NullControl&); //!< you can override, but don't call this... }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/PlaySoundControl.h ./Behaviors/Controls/PlaySoundControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/PlaySoundControl.h 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/PlaySoundControl.h 2007-01-28 20:16:57.000000000 -0500 @@ -10,7 +10,7 @@ public: //! Constructor PlaySoundControl(const std::string& n) - : FileBrowserControl(n,"Plays a sound from a user specified sound file",config->portPath(config->sound.root)) + : FileBrowserControl(n,"Plays a sound from a user specified sound file",config->sound.root) { setFilter("*.wav"); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/PostureEditor.cc ./Behaviors/Controls/PostureEditor.cc --- ../Tekkotsu_3.0/Behaviors/Controls/PostureEditor.cc 2006-09-09 00:32:18.000000000 -0400 +++ ./Behaviors/Controls/PostureEditor.cc 2007-11-18 01:47:00.000000000 -0500 @@ -48,9 +48,11 @@ // start off with current pose pose.takeSnapshot(); pose.setWeights(1); +#ifdef TGT_HAS_LEDS // clear the LEDs though for(unsigned int i=LEDOffset; i reach; reachID=motman->addPersistentMotion(reach); @@ -124,11 +126,15 @@ } } } else if(e.getGeneratorID()==EventBase::timerEGID) { +#ifndef TGT_HAS_LEDS + pose.takeSnapshot(); +#else //doing a manual copy instead of just takeSnapshot() so we don't disturb the LED settings for(unsigned int i=0; ioutputs[i]; for(unsigned int i=LEDOffset+NumLEDs; ioutputs[i]; +#endif if(e.getSourceID()==0) // source==1 indicates it's a forged event sent from refresh -- don't inf. recurse refresh(); } else { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/RunSequenceControl.h ./Behaviors/Controls/RunSequenceControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/RunSequenceControl.h 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/RunSequenceControl.h 2007-08-05 12:16:04.000000000 -0400 @@ -5,7 +5,12 @@ #include "FileBrowserControl.h" #include "Motion/MotionSequenceMC.h" #include "Motion/EmergencyStopMC.h" -#include "Motion/LedMC.h" +#include "Shared/RobotInfo.h" +#ifdef TGT_HAS_LEDS +# include "Shared/ERS210Info.h" +# include "Motion/LedMC.h" +#endif +#include "Events/EventRouter.h" #include "Sound/SoundManager.h" #include "Motion/MMAccessor.h" #include "Shared/TimeET.h" @@ -28,7 +33,7 @@ public: //! Constructor, sets filter to *.mot RunSequenceControl(const std::string& n, MotionManager::MC_ID estop_id) - : FileBrowserControl(n,"Runs a motion sequence from a user-specified file",config->portPath(config->motion.root)), + : FileBrowserControl(n,"Runs a motion sequence from a user-specified file",config->motion.root), estopid(estop_id), ledid(MotionManager::invalid_MC_ID), waitingFile() { setFilter("*.mot"); @@ -38,6 +43,7 @@ virtual ~RunSequenceControl() { erouter->removeListener(this); motman->removeMotion(ledid); + ledid=MotionManager::invalid_MC_ID; } //! only called when e-stop has been turned off and we're waiting to load a file @@ -45,6 +51,7 @@ erouter->removeListener(this); runFile(); motman->removeMotion(ledid); + ledid=MotionManager::invalid_MC_ID; } protected: @@ -65,11 +72,19 @@ } else { //we have to wait for the estop to be turned off sndman->playFile("donkey.wav"); +#ifdef TGT_HAS_LEDS SharedObject led; led->cset(FaceLEDMask,0); - led->cycle(BotLLEDMask,1000,3,0,0); - led->cycle(BotRLEDMask,1000,3,0,500); + unsigned int botl = capabilities.findButtonOffset(ERS210Info::buttonNames[ERS210Info::BotLLEDOffset]); + unsigned int botr = capabilities.findButtonOffset(ERS210Info::buttonNames[ERS210Info::BotRLEDOffset]); + if(botl==-1U || botr==-1U) { + botl=LEDOffset; + botr=NumLEDs>1 ? botl+1 : botl; + } + led->cycle(1<<(botl-LEDOffset),1000,3,0,0); + led->cycle(1<<(botr-LEDOffset),1000,3,0,500); ledid=motman->addPersistentMotion(led); +#endif erouter->addListener(this,EventBase::estopEGID,estopid,EventBase::deactivateETID); } return this; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/SensorObserverControl.cc ./Behaviors/Controls/SensorObserverControl.cc --- ../Tekkotsu_3.0/Behaviors/Controls/SensorObserverControl.cc 2006-10-02 18:11:38.000000000 -0400 +++ ./Behaviors/Controls/SensorObserverControl.cc 2007-06-05 14:04:36.000000000 -0400 @@ -65,7 +65,7 @@ sndman->playFile(config->controller.select_snd); if(wasListening!=(numListeners>0)) { if(numListeners>0) - erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID); + erouter->addListener(this,EventBase::sensorEGID,SensorSrcID::UpdatedSID); else erouter->removeListener(this); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/ShutdownControl.cc ./Behaviors/Controls/ShutdownControl.cc --- ../Tekkotsu_3.0/Behaviors/Controls/ShutdownControl.cc 2005-08-31 17:55:12.000000000 -0400 +++ ./Behaviors/Controls/ShutdownControl.cc 2007-06-13 14:14:12.000000000 -0400 @@ -2,7 +2,7 @@ #ifdef PLATFORM_APERIOS # include #else -# include "local/sim/SharedGlobals.h" +# include "Shared/ProjectInterface.h" #endif ControlBase * ShutdownControl::doSelect() { @@ -10,8 +10,7 @@ OBootCondition bc(0); OPENR::Shutdown(bc); #else - if(globals!=NULL) - globals->signalShutdown(); + ProjectInterface::sendCommand("quit"); #endif return NULL; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/SimulatorAdvanceFrameControl.h ./Behaviors/Controls/SimulatorAdvanceFrameControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/SimulatorAdvanceFrameControl.h 2006-08-30 10:26:44.000000000 -0400 +++ ./Behaviors/Controls/SimulatorAdvanceFrameControl.h 2007-11-10 17:58:05.000000000 -0500 @@ -4,18 +4,13 @@ #include "Behaviors/Controls/NullControl.h" #ifdef PLATFORM_APERIOS -# warning SimulatorAdvanceFrameControl is only useful when running in simulation! +# warning SimulatorAdvanceFrameControl is available on Aperios! #else -# include "local/sim/Simulator.h" +# include "Shared/ProjectInterface.h" #endif //! Requests the next camera frame and sensor data, for use when running in simulation -/*! There are a number of options regarding control of input data and - * flow of time. This is only applicable when using a non-realtime - * source (such as loading logged data from disk) and the simulator's - * AdvanceOnAccess is 'false' (this is "advance on request" -- the - * same data may be accessed multiple times until you manually - * request the next frame) */ +/*! Note that this won't increment the simulator time if triggered while paused... */ class SimulatorAdvanceFrameControl : public NullControl { public: @@ -32,7 +27,7 @@ #ifndef PLATFORM_APERIOS virtual ControlBase * activate(MotionManager::MC_ID disp_id, Socket * gui) { - Simulator::sendCommand("advance"); + ProjectInterface::sendCommand("advance"); return NullControl::activate(disp_id,gui); } @@ -49,6 +44,7 @@ } protected: + //! ideally, this should return true only when the simulator is paused or the data source is frozen... bool canManuallyAdvance() const { return true; } #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/StringInputControl.cc ./Behaviors/Controls/StringInputControl.cc --- ../Tekkotsu_3.0/Behaviors/Controls/StringInputControl.cc 2003-07-28 01:54:32.000000000 -0400 +++ ./Behaviors/Controls/StringInputControl.cc 2007-01-30 17:56:18.000000000 -0500 @@ -27,6 +27,7 @@ << "0\n" << "0\n" << "Waiting for input...\n" + << std::count(userPrompt.begin(),userPrompt.end(),'\n') << '\n' << userPrompt << "\n"; gui_comm->write((const byte*)ss.str().c_str(),ss.str().size()); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/StringInputControl.h ./Behaviors/Controls/StringInputControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/StringInputControl.h 2004-03-22 19:55:01.000000000 -0500 +++ ./Behaviors/Controls/StringInputControl.h 2007-01-30 17:56:18.000000000 -0500 @@ -26,7 +26,7 @@ } //! returns last call to takeInput() - virtual const std::string& getLastInput() { return lastInput; } + virtual const std::string& getLastInput() const { return lastInput; } //! clears the last input (i.e. so you can easily tell later if new input is entered) virtual void clearLastInput() { takeInput(""); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/TorqueCalibrate.cc ./Behaviors/Controls/TorqueCalibrate.cc --- ../Tekkotsu_3.0/Behaviors/Controls/TorqueCalibrate.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Controls/TorqueCalibrate.cc 2007-11-12 23:16:00.000000000 -0500 @@ -0,0 +1,215 @@ +#include "TorqueCalibrate.h" +#include "Behaviors/Controls/NullControl.h" +#include "Shared/WorldState.h" +#include "Shared/Config.h" +#include "Events/EventRouter.h" +#include "Motion/MMAccessor.h" +#include "Motion/PIDMC.h" +#include "Motion/MotionSequenceMC.h" +#include "Sound/SoundManager.h" +#include +#include + +//better to put this here instead of the header +using namespace std; + + +//***************************// +//***** TorqueCalibrate *****// +//***************************// + +void TorqueCalibrate::record(unsigned int joint, float sensorDist, float maxDuty, float maxForce) const { + std::ofstream log(filename.c_str(),std::ios::app); + if(!log) { + serr->printf("ERROR: could not open %s for writing log\n",filename.c_str()); + sndman->playFile("fart.wav"); + } else { + log << joint << '\t' << sensorDist << '\t' << maxDuty << '\t' << maxForce << std::endl; + sndman->playFile("camera.wav"); + } + std::cout << "DATA: " << joint << '\t' << sensorDist << '\t' << maxDuty << '\t' << maxForce << std::endl; +} + +void TorqueCalibrate::refresh() { + if(filenameInput->getLastInput()!=filename) { + filename=filenameInput->getLastInput(); + std::string::size_type f=filename.rfind("/"); + filenameInput->setName("Storage: "+filename.substr(f==string::npos?0:f+1)); + std::string desc="Location where data will be appended to any previous contents"; + filenameInput->setDescription(desc+": "+filename); + std::ofstream log(filename.c_str(),std::ios::app); + if(!log) + serr->printf("ERROR: could not open %s for writing log\n",filename.c_str()); + } + ControlBase::refresh(); +} + + +//******************************************************// +//***** TorqueCalibrate::TakeMeasurementControl *****// +//******************************************************// + +ControlBase * TorqueCalibrate::TakeMeasurementControl::activate(MotionManager::MC_ID disp_id, Socket * gui) { +#ifdef TGT_HAS_BUTTONS +# ifdef TGT_ERS7 + erouter->addListener(this,EventBase::buttonEGID,FrontBackButOffset,EventBase::activateETID); + erouter->addListener(this,EventBase::buttonEGID,MiddleBackButOffset,EventBase::activateETID); + erouter->addListener(this,EventBase::buttonEGID,RearBackButOffset,EventBase::activateETID); +# else + erouter->addListener(this,EventBase::buttonEGID,BackButOffset,EventBase::activateETID); +# endif +#else +# warning TorqueCalibrate control needs some kind of trigger, target model does not have any buttons? +#endif + cstate=ZERO_JOINT; + SharedObject pidmc(0); + pidID=motman->addPersistentMotion(pidmc,MotionManager::kHighPriority); + return ControlBase::activate(disp_id,gui); +} + +void TorqueCalibrate::TakeMeasurementControl::processEvent(const EventBase& event) { + if(cstate==ZERO_JOINT && event.getGeneratorID()==EventBase::buttonEGID) { + basePosition=state->outputs[joint]; + transition(RECORD_POSITION); + } else if(cstate==DO_PULSE && event.getGeneratorID()==EventBase::sensorEGID) { + if(std::abs(state->pidduties[joint-PIDJointOffset]) > maxDuty) + maxDuty=std::abs(state->pidduties[joint-PIDJointOffset]); + std::cout << "Duty: " << state->pidduties[joint-PIDJointOffset] << std::endl; + } else if(cstate==DO_PULSE && event.getGeneratorID()==EventBase::timerEGID) { + erouter->removeListener(this,EventBase::sensorEGID); + } else if(cstate==DO_PULSE && event.getGeneratorID()==EventBase::motmanEGID) { + pulseID=MotionManager::invalid_MC_ID; + std::cout << "Max duty: " << maxDuty << std::endl; + transition(RECORD_FORCE); + } else { + std::cerr << "Unhandled event " << event.getName() << std::endl; + } +} + +void TorqueCalibrate::TakeMeasurementControl::refresh() { + clearSlots(); + switch(cstate) { + case ZERO_JOINT: + pushSlot(new NullControl("Position the joint")); + pushSlot(new NullControl("and press a back button")); + break; + case RECORD_POSITION: + pushSlot(new NullControl("What is the length of")); + pushSlot(new NullControl("the lever arm? (cm)")); + pushSlot(new NullControl("(Dist. from axis of")); + pushSlot(new NullControl("rot. to force sensor)")); + break; + case INPUT_PULSE: + pushSlot(new NullControl("Enter the position")); + pushSlot(new NullControl("offset to attempt")); + pushSlot(new NullControl("(radians -- bigger")); + pushSlot(new NullControl("offset means apply")); + pushSlot(new NullControl("more force...)")); + break; + case DO_PULSE: + pushSlot(new NullControl("Running...")); + break; + case RECORD_FORCE: { + char res[256]; + snprintf(res,256,"Max duty was: %g",maxDuty); + pushSlot(new NullControl(res)); + pushSlot(NULL); + pushSlot(new NullControl("Enter the maximum")); + pushSlot(new NullControl("force (N)")); + break; + } + } + ControlBase::refresh(); +} + +ControlBase * TorqueCalibrate::TakeMeasurementControl::takeInput(const std::string& msg) { + switch(cstate) { + case ZERO_JOINT: + case DO_PULSE: + break; + case RECORD_POSITION: + sensorDist=atof(msg.c_str()); + if(sensorDist==0) { + sndman->playFile("fart.wav"); + return NULL; + } + transition(INPUT_PULSE); + break; + case INPUT_PULSE: { + float offset=atof(msg.c_str()); + SharedObject ms; + ms->advanceTime(350); + if(offset>.1) { + // move slowly at first in case not quite against sensor + ms->setOutputCmd(joint,basePosition+offset/4); + ms->advanceTime(300); + ms->setOutputCmd(joint,basePosition+offset/2); + ms->advanceTime(200); + // hard push at the end + ms->setOutputCmd(joint,basePosition+offset); + ms->advanceTime(500); + } else { + ms->setOutputCmd(joint,basePosition+offset); + ms->advanceTime(700); + } + ms->setOutputCmd(joint,basePosition+offset); + ms->advanceTime(300); + erouter->addTimer(this,0,ms->getTime(),false); + ms->setOutputCmd(joint,basePosition); + ms->advanceTime(200); + ms->setOutputCmd(joint,basePosition); + pulseID=motman->addPrunableMotion(ms); + transition(DO_PULSE); + } break; + case RECORD_FORCE: { + float f=atof(msg.c_str()); + if(f!=0) + parent.record(joint,sensorDist,maxDuty,f); + else + sndman->playFile("fart.wav"); + transition(INPUT_PULSE); + } break; + } + return this; +} + +void TorqueCalibrate::TakeMeasurementControl::deactivate() { + erouter->remove(this); + motman->removeMotion(pidID); + pidID=MotionManager::invalid_MC_ID; + if(pulseID!=MotionManager::invalid_MC_ID) { + motman->removeMotion(pulseID); + pulseID=MotionManager::invalid_MC_ID; + } + ControlBase::deactivate(); +} + +void TorqueCalibrate::TakeMeasurementControl::transition(State_t newstate) { + MMAccessor(pidID)->setAllPowerLevel(1); + erouter->removeListener(this); + cstate=newstate; + if(cstate==RECORD_POSITION || cstate==INPUT_PULSE || cstate==RECORD_FORCE) + sndman->playFile("ping.wav"); + else + sndman->playFile("barkhigh.wav"); + refresh(); + if(cstate==DO_PULSE) { + maxDuty=0; + float pidSetting[] = {DefaultPIDs[joint][0],0,0}; + MMAccessor(pidID)->setPID(joint,pidSetting); + erouter->addListener(this,EventBase::sensorEGID); + erouter->addListener(this,EventBase::motmanEGID,pulseID,EventBase::deactivateETID); + } +} + + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.4 $ + * $State: Exp $ + * $Date: 2007/11/13 04:16:00 $ + */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/TorqueCalibrate.h ./Behaviors/Controls/TorqueCalibrate.h --- ../Tekkotsu_3.0/Behaviors/Controls/TorqueCalibrate.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Controls/TorqueCalibrate.h 2007-04-05 02:24:09.000000000 -0400 @@ -0,0 +1,122 @@ +//-*-c++-*- +#ifndef INCLUDED_TorqueCalibrate_h +#define INCLUDED_TorqueCalibrate_h + +#include "Behaviors/Controls/ControlBase.h" +#include "Behaviors/Controls/FileInputControl.h" +#include "Motion/MotionManager.h" +#include "Events/EventListener.h" + +//! Provides an interface for making measurements to correlate PID duty cycle and actual force output for each of the motors +class TorqueCalibrate : public ControlBase { + + // **************************** // + // ******* CONSTRUCTORS ******* // + // **************************** // + // Not all of these necessarily make sense to implement... feel free + // to remove those which don't -- none are required. + +public: + //! default constructor + TorqueCalibrate() + : ControlBase("TorqueCalibrate","Provides an interface for making measurements to correlate PID duty cycle and actual force output for each of the motors"), + filename(config->portPath("data/torque.dat")), filenameInput(NULL) + {init();} + //! constructor which allows a custom name + TorqueCalibrate(const std::string& n) + : ControlBase(n,"Provides an interface for making measurements to correlate PID duty cycle and actual force output for each of the motors"), + filename(config->portPath("data/torque.dat")), filenameInput(NULL) + {init();} + //! constructor which allows a custom name and tooltip + TorqueCalibrate(const std::string& n, const std::string& d) + : ControlBase(n,d), + filename(config->portPath("data/torque.dat")), filenameInput(NULL) + {init();} + + //! destructor + virtual ~TorqueCalibrate() {} + +protected: + class TakeMeasurementControl : public ControlBase, public EventListener { + public: + TakeMeasurementControl(const TorqueCalibrate& tcParent, unsigned int jointToMeasure) + : ControlBase(outputNames[jointToMeasure]), parent(tcParent), joint(jointToMeasure), + basePosition(state->outputs[jointToMeasure]), maxDuty(0), sensorDist(0), cstate(ZERO_JOINT), + pidID(MotionManager::invalid_MC_ID), pulseID(MotionManager::invalid_MC_ID) + {} + virtual ControlBase * activate(MotionManager::MC_ID disp_id, Socket * gui); + virtual void processEvent(const EventBase& event); + virtual void refresh(); + virtual ControlBase * takeInput(const std::string& msg); + virtual void deactivate(); + protected: + //! the states the TakeMeasurementControl goes through when recording measurements + enum State_t { + ZERO_JOINT, //!< turn off PID of joints, allow user to reposition them to the force sensor + RECORD_POSITION, //!< record the length of the lever arm (distance from point of rotation to force sensor) + INPUT_PULSE, //!< wait for user to specify size of pulse to perform + DO_PULSE, //!< make the joint do the pulse + RECORD_FORCE //!< wait for user to report the recorded force applied + }; + + //! requests a transition to another state + void transition(State_t newstate); + + const TorqueCalibrate& parent; + unsigned int joint; + float basePosition; + float maxDuty; + float sensorDist; + State_t cstate; + MotionManager::MC_ID pidID; + MotionManager::MC_ID pulseID; + }; + + //! initialization + virtual void init() { + pushSlot(filenameInput=new FileInputControl("Storage: ","Location where data will be appended to any previous contents","")); + pushSlot(NULL); + for(unsigned int i=PIDJointOffset; isetAcceptNonExistant(true); + filenameInput->takeInput(filename); + filename=""; //force refresh + } + + + // **************************** // + // ********* METHODS ********** // + // **************************** // +public: + void record(unsigned int joint, float sensorDist, float maxDuty, float maxForce) const; + virtual void refresh(); + + + // **************************** // + // ********* MEMBERS ********** // + // **************************** // +protected: + std::string filename; + FileInputControl * filenameInput; + + + // **************************** // + // ********** OTHER *********** // + // **************************** // +private: + TorqueCalibrate(const TorqueCalibrate&); //!< you can override, but don't call this... + TorqueCalibrate& operator=(const TorqueCalibrate&); //!< you can override, but don't call this... +}; + +/*! @file + * @brief Defines TorqueCalibrate, which provides an interface for making measurements to correlate PID duty cycle and actual force output for each of the motors + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.1 $ + * $State: Exp $ + * $Date: 2007/04/05 06:24:09 $ + */ +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/ValueEditControl.h ./Behaviors/Controls/ValueEditControl.h --- ../Tekkotsu_3.0/Behaviors/Controls/ValueEditControl.h 2005-08-07 00:11:03.000000000 -0400 +++ ./Behaviors/Controls/ValueEditControl.h 2007-06-28 00:36:19.000000000 -0400 @@ -12,6 +12,7 @@ #include "Shared/ERS220Info.h" #include "Shared/ERS7Info.h" #include "Wireless/Wireless.h" +#include "Behaviors/Controller.h" #include #include @@ -40,32 +41,17 @@ } //! will increment/decrement the current and then assign it to the target when head buttons pressed virtual void processEvent(const EventBase& e) { - if(state->robotDesign&WorldState::ERS210Mask) { - switch(e.getSourceID()) { - case ERS210Info::HeadFrButOffset: doNextItem(); doSelect(); break; - case ERS210Info::HeadBkButOffset: doNextItem(); doSelect(); break; - default: - serr->printf("*** WARNING ValueEditControl got an unasked for event\n"); - break; - } - } else if(state->robotDesign&WorldState::ERS220Mask) { - switch(e.getSourceID()) { - case ERS220Info::HeadFrButOffset: doNextItem(); doSelect(); break; - case ERS220Info::HeadBkButOffset: doNextItem(); doSelect(); break; - default: - serr->printf("*** WARNING ValueEditControl got an unasked for event\n"); - break; - } - } else if(state->robotDesign&WorldState::ERS7Mask) { - switch(e.getSourceID()) { - case ERS7Info::FrontBackButOffset: doNextItem(); doSelect(); break; - case ERS7Info::RearBackButOffset: doNextItem(); doSelect(); break; - default: - serr->printf("*** WARNING ValueEditControl got an unasked for event\n"); - break; - } + if(e==Controller::nextItem) { + doNextItem(); + doSelect(); + } else if(e==Controller::prevItem) { + doPrevItem(); + doSelect(); + } else { + serr->printf("*** WARNING ValueEditControl got an unasked for event\n"); } } + //! displays current value virtual void refresh() { //Do console only if GUI is connected @@ -82,22 +68,8 @@ //! request to continue receiving events so we can modify the value while running virtual void pause() { - unsigned int FrButOffset,BkButOffset; - if(state->robotDesign&WorldState::ERS210Mask) { - FrButOffset=ERS210Info::HeadFrButOffset; - BkButOffset=ERS210Info::HeadBkButOffset; - } else if(state->robotDesign&WorldState::ERS220Mask) { - FrButOffset=ERS220Info::HeadFrButOffset; - BkButOffset=ERS220Info::HeadBkButOffset; - } else if(state->robotDesign&WorldState::ERS7Mask) { - FrButOffset=ERS7Info::FrontBackButOffset; - BkButOffset=ERS7Info::RearBackButOffset; - } else { - serr->printf("ValueEditControl: Unsupported model!\n"); - return; - } - erouter->addListener(this,EventBase(EventBase::buttonEGID,FrButOffset,EventBase::deactivateETID,0)); - erouter->addListener(this,EventBase(EventBase::buttonEGID,BkButOffset,EventBase::deactivateETID,0)); + erouter->addListener(this,Controller::nextItem); + erouter->addListener(this,Controller::prevItem); // erouter->addListener(this,EventBase(EventBase::buttonEGID,ChinButOffset,EventBase::deactivateETID,0)); StringInputControl::pause(); } @@ -120,13 +92,13 @@ } //! adds one to the current value virtual ControlBase * doNextItem() { - cur++; + cur=(T)(cur+1); refresh(); return this; } //! subtracts one from the current value virtual ControlBase * doPrevItem() { - cur--; + cur=(T)(cur-1); refresh(); return this; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/WalkCalibration.cc ./Behaviors/Controls/WalkCalibration.cc --- ../Tekkotsu_3.0/Behaviors/Controls/WalkCalibration.cc 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/WalkCalibration.cc 2007-11-12 23:16:00.000000000 -0500 @@ -209,9 +209,9 @@ ControlBase::refresh(); if(gui_comm!=NULL && wireless->isConnected(gui_comm->sock)) { if(status.size()==0) - gui_comm->printf("status\n# Samples: fs=%d fr=%d sr=%d br=%d bs=%d r=%d\n",cnts[0], cnts[1], cnts[2], cnts[3], cnts[4], cnts[5]); + gui_comm->printf("status\n1\n# Samples: fs=%d fr=%d sr=%d br=%d bs=%d r=%d\n",cnts[0], cnts[1], cnts[2], cnts[3], cnts[4], cnts[5]); else - gui_comm->printf("status\n%s\n",status.c_str()); + gui_comm->printf("status\n%td\n%s\n",std::count(status.begin(),status.end(),'\n'),status.c_str()); } } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/WaypointWalkControl.cc ./Behaviors/Controls/WaypointWalkControl.cc --- ../Tekkotsu_3.0/Behaviors/Controls/WaypointWalkControl.cc 2006-09-18 14:07:54.000000000 -0400 +++ ./Behaviors/Controls/WaypointWalkControl.cc 2007-11-11 18:57:18.000000000 -0500 @@ -59,7 +59,7 @@ sscanf(localizationCtl->getLastInput().c_str(),"%g %g %g",&x,&y,&a); MMAccessor walk(walk_id); walk->setCurPos(x+walk->getCurX(),y+walk->getCurY(),a+walk->getCurA()); - cout << "Position is now " << walk->getCurX() << ' ' << walk->getCurY() << ' ' << walk->getCurA() << endl; + std::cout << "Position is now " << walk->getCurX() << ' ' << walk->getCurY() << ' ' << walk->getCurA() << std::endl; localizationCtl->clearLastInput(); } @@ -161,7 +161,7 @@ pushSlot(new ValueEditControl("Turn Speed (in rad/s)",&curway.turnSpeed)); char desc[256]; snprintf(desc,256,"Types: EGO=%d, OFF=%d, ABS=%d",WaypointWalkMC::Waypoint::POSTYPE_EGOCENTRIC,WaypointWalkMC::Waypoint::POSTYPE_OFFSET,WaypointWalkMC::Waypoint::POSTYPE_ABSOLUTE); - pushSlot(new ValueEditControl("Pos. coord. system",desc,(int*)&curway.posType)); + pushSlot(new ValueEditControl("Pos. coord. system",desc,&curway.posType)); ToggleControl * tmptgl; pushSlot(tmptgl=new ToggleControl("Angle is relative")); tmptgl->setStatus(curway.angleIsRelative); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/AlanBehavior.h ./Behaviors/Demos/AlanBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/AlanBehavior.h 2005-06-01 01:47:45.000000000 -0400 +++ ./Behaviors/Demos/AlanBehavior.h 2007-11-12 13:00:38.000000000 -0500 @@ -29,7 +29,7 @@ // creates a PostureMC class to move the joint(s) and adds it to global MotionManager pose_id=motman->addPersistentMotion(SharedObject()); // subscribe to sensor updated events through the global EventRouter - erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID); + erouter->addListener(this,EventBase::sensorEGID,SensorSrcID::UpdatedSID); } virtual void DoStop() { @@ -60,16 +60,16 @@ //state is a global instantiation of WorldState, kept up to date by framework; //pressure is in range 0 to 1 - we use the pressure on the front head button here float pressure=0; - if(state->robotDesign&WorldState::ERS210Mask) { - pressure=state->buttons[ERS210Info::HeadFrButOffset]; + if(RobotName == ERS210Info::TargetName) { + pressure=state->buttons[capabilities.getButtonOffset("HeadFrBut")]; std::cout << "HeadFrBut Pressure: " << pressure << std::endl; - } else if(state->robotDesign&WorldState::ERS7Mask) { + } else if(RobotName == ERS7Info::TargetName) { pressure=state->buttons[ERS7Info::HeadButOffset]; std::cout << "HeadBut Pressure: " << pressure << std::endl; } else { //only really works on the ERS-210 or ERS-7 models - the others don't have a proper pressure sensor //(the 220's antenna-thing is close, but doesn't give a continuous range) - std::cout << "Unknown model" << std::endl; + std::cout << "Unsupported/unknown model" << std::endl; erouter->removeListener(this); // stops getting events (and timers, if we had any) return; } @@ -83,9 +83,9 @@ //let's do the whole thing again with the other head button for the other leg: // (cutting out a some of the intermediary steps this time) joint=RFrLegOffset+RotatorOffset; - if(state->robotDesign&WorldState::ERS210Mask) - pose_mc->setOutputCmd(joint,outputRanges[joint][MaxRange]*state->buttons[ERS210Info::HeadBkButOffset]); - else if(state->robotDesign&WorldState::ERS7Mask) //ERS7 doesn't have another head button, we'll use one of its back buttons + if(RobotName == ERS210Info::TargetName) + pose_mc->setOutputCmd(joint,outputRanges[joint][MaxRange]*state->buttons[capabilities.getButtonOffset(ERS210Info::buttonNames[ERS210Info::HeadBkButOffset])]); + else if(RobotName == ERS7Info::TargetName) //ERS7 doesn't have another head button, we'll use one of its back buttons pose_mc->setOutputCmd(joint,outputRanges[joint][MaxRange]*state->buttons[ERS7Info::FrontBackButOffset]); // notice that there's no "check in" for pose_mc @@ -93,7 +93,7 @@ } else { //should never happen - cout << "Unhandled Event:" << event.getName() << endl; + std::cout << "Unhandled Event:" << event.getName() << std::endl; } } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/BanditMachine.h ./Behaviors/Demos/BanditMachine.h --- ../Tekkotsu_3.0/Behaviors/Demos/BanditMachine.h 2006-09-18 14:07:57.000000000 -0400 +++ ./Behaviors/Demos/BanditMachine.h 2007-11-12 13:00:38.000000000 -0500 @@ -50,8 +50,8 @@ StateNode *decide=addNode(new DecideNode("Decide",bandit,left,right)); StateNode *recoverl=addNode(new OutputNode("\nBadPressLeft",std::cout,wait)); StateNode *recoverr=addNode(new OutputNode("\nBadPressRight",std::cout,wait)); - left->addTransition(new SmoothCompareTrans(wait,&state->pidduties[LFrLegOffset+RotatorOffset],CompareTrans::LT,-.07,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7)); - right->addTransition(new SmoothCompareTrans(wait,&state->pidduties[RFrLegOffset+RotatorOffset],CompareTrans::LT,-.07,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7)); + left->addTransition(new SmoothCompareTrans(wait,&state->pidduties[LFrLegOffset+RotatorOffset],CompareTrans::LT,-.07,EventBase(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID),.7)); + right->addTransition(new SmoothCompareTrans(wait,&state->pidduties[RFrLegOffset+RotatorOffset],CompareTrans::LT,-.07,EventBase(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID),.7)); wait->addTransition(new TimeOutTrans(decide,2000)); left->addTransition(new TimeOutTrans(recoverl,1500)); right->addTransition(new TimeOutTrans(recoverr,1500)); @@ -180,7 +180,7 @@ virtual void DoStop() { erouter->removeListener(this); b.reward(reward); - cout << endl; + std::cout << std::endl; reward=false; StateNode::DoStop(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/CameraBehavior.cc ./Behaviors/Demos/CameraBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Demos/CameraBehavior.cc 2006-09-18 14:07:57.000000000 -0400 +++ ./Behaviors/Demos/CameraBehavior.cc 2007-07-16 14:31:40.000000000 -0400 @@ -1,9 +1,7 @@ #include "CameraBehavior.h" #include "Events/EventRouter.h" #include "Events/TextMsgEvent.h" -#include "Shared/ERS210Info.h" -#include "Shared/ERS220Info.h" -#include "Shared/ERS7Info.h" +#include "Shared/RobotInfo.h" #include "Wireless/Socket.h" #include "Shared/WorldState.h" #include "Sound/SoundManager.h" @@ -26,13 +24,9 @@ void CameraBehavior::DoStart() { BehaviorBase::DoStart(); - if(state->robotDesign&WorldState::ERS210Mask) { - camera_click.setSourceID(ERS210Info::HeadFrButOffset); - } else if(state->robotDesign&WorldState::ERS220Mask) { - camera_click.setSourceID(ERS220Info::HeadFrButOffset); - } else if(state->robotDesign&WorldState::ERS7Mask) { - camera_click.setSourceID(ERS7Info::HeadButOffset); - } + if(capabilities.findButtonOffset("HeadBut")!=-1U) // if there is a head button, use it for the trigger + camera_click.setSourceID(capabilities.getButtonOffset("HeadBut")); + // (otherwise, just stick with the default button 0 as set in camera_click constructor) initIndex(); sndman->loadFile("camera.wav"); ledID=motman->addPersistentMotion(SharedObject()); @@ -63,11 +57,15 @@ { MMAccessor leds(ledID); +#if defined(TGT_ERS7) || defined(TGT_ERS210) || defined(TGT_ERS220) || defined(TGT_ERS2xx) leds->cset(FaceLEDMask,2.0/3.0); leds->set(TopBrLEDMask,1); +#else + leds->set(~0,1); +#endif } - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE) { + if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_NONE) { //this is our own odd little format, would be nice to save a TIFF or something instead // open file @@ -76,7 +74,7 @@ return; //! write actual image data - if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_COLOR) { + if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_COLOR) { FilterBankGenerator * gen=ProjectInterface::defInterleavedYUVGenerator; // just an alias for readability gen->selectSaveImage(ProjectInterface::doubleLayer,InterleavedYUVGenerator::CHAN_YUV); unsigned int len=gen->saveFileStream(f); @@ -85,9 +83,9 @@ sndman->playFile(config->controller.error_snd); return; } - } else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) { + } else if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL) { FilterBankGenerator * gen=ProjectInterface::defRawCameraGenerator; // just an alias for readability - gen->selectSaveImage(ProjectInterface::doubleLayer,config->vision.rawcam_channel); + gen->selectSaveImage(ProjectInterface::doubleLayer,config->vision.rawcam.channel); unsigned int len=gen->saveFileStream(f); if(len==0) { serr->printf("Error saving file\n"); @@ -99,15 +97,15 @@ // close file fclose(f); - } else if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_JPEG) { + } else if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_JPEG) { //save a JPEG image JPEGGenerator * jpeg=NULL; // we'll set this to pick between the color jpeg or a single channel grayscale jpeg unsigned int chan=0; // and this will hold the channel to use out of that jpeg generator - if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_COLOR) + if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_COLOR) jpeg=dynamic_cast(ProjectInterface::defColorJPEGGenerator); - else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) { + else if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL) { jpeg=dynamic_cast(ProjectInterface::defGrayscaleJPEGGenerator); - chan=config->vision.rawcam_channel; + chan=config->vision.rawcam.channel; } if(jpeg!=NULL) { unsigned int tmp_q=jpeg->getQuality(); //temporary storage so we can reset the default @@ -133,15 +131,15 @@ jpeg->setQuality(tmp_q); } - } else if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_PNG) { - //save a JPEG image + } else if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_PNG) { + //save a PNG image PNGGenerator * png=NULL; // we'll set this to pick between the color png or a single channel grayscale png unsigned int chan=0; // and this will hold the channel to use out of that png generator - if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_COLOR) + if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_COLOR) png=dynamic_cast(ProjectInterface::defColorPNGGenerator); - else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) { + else if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL) { png=dynamic_cast(ProjectInterface::defGrayscalePNGGenerator); - chan=config->vision.rawcam_channel; + chan=config->vision.rawcam.channel; } if(png!=NULL) { // open file @@ -166,10 +164,21 @@ { MMAccessor leds(ledID); leds->clear(); +#if defined(TGT_ERS7) || defined(TGT_ERS210) || defined(TGT_ERS220) || defined(TGT_ERS2xx) leds->flash(TopBrLEDMask,700); leds->flash(TopLLEDMask|TopRLEDMask,500); leds->flash(MidLLEDMask|MidRLEDMask,300); leds->flash(BotLLEDMask|BotRLEDMask,100); +#else + if(NumLEDs>3) + leds->flash(1<<3,700); + if(NumLEDs>2) + leds->flash(1<<2,500); + if(NumLEDs>1) + leds->flash(1<<1,300); + if(NumLEDs>0) + leds->flash(1<<0,100); +#endif } sout->printf("done\n"); @@ -226,7 +235,6 @@ sout->printf("The next saved image will go to %simg%05d\n",path.c_str(),index); } - /*! @file * @brief Implements CameraBehavior, for taking pictures * @author ejt (Creator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/CameraBehavior.h ./Behaviors/Demos/CameraBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/CameraBehavior.h 2004-11-10 20:45:35.000000000 -0500 +++ ./Behaviors/Demos/CameraBehavior.h 2007-06-28 00:36:20.000000000 -0400 @@ -15,8 +15,8 @@ * to transmit them over. * * Image format is chosen by current config settings for the - * Config::vision_config::rawcam_compression and - * Config::vision_config::rawcam_channel. However, the double + * Config::vision_config::RawCamConfig::compression and + * Config::vision_config::RawCamConfig::channel. However, the double * resolution layer is always saved instead of whatever the current * config skip value indicates. */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/ChaseBallBehavior.cc ./Behaviors/Demos/ChaseBallBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Demos/ChaseBallBehavior.cc 2004-10-16 21:16:10.000000000 -0400 +++ ./Behaviors/Demos/ChaseBallBehavior.cc 2007-11-16 10:19:40.000000000 -0500 @@ -6,9 +6,8 @@ #include "Motion/WalkMC.h" #include "Shared/WMclass.h" #include "Shared/ProjectInterface.h" - -//! Converts degrees to radians -inline double DtoR(double deg) { return (deg/180.0*M_PI); } +#include "Shared/ERS7Info.h" +#include "Motion/MMAccessor.h" void ChaseBallBehavior::DoStart() { BehaviorBase::DoStart(); @@ -26,39 +25,58 @@ //this could be cleaned up event-wise (only use a timer when out of view) void ChaseBallBehavior::processEvent(const EventBase& event) { - WMreg(chase_ball_behavior); - WMvari_(float, horiz, 0, chase_ball_behavior); - WMvari_(float, vert, 0, chase_ball_behavior); - + WMreg(chase_ball_behavior); + WMvari_(float, horiz, 0, chase_ball_behavior); + WMvari_(float, vert, 0, chase_ball_behavior); + if(event.getGeneratorID()==EventBase::visObjEGID && event.getTypeID()==EventBase::statusETID) { horiz=static_cast(&event)->getCenterX(); vert=static_cast(&event)->getCenterY(); + std::cout << get_time() << ' ' << horiz << ' ' << vert << std::endl; } - + + // For portability, look to see if the host hardware has a head pan & tilt joints, + // using ERS-7's namespace to look up the canonical "name" of the pan and tilt joints. + // Note if you were coding for a specific robot, could just do "tiltIdx = HeadOffset + TiltOffset" + // directly and not bother with this... + const char * const * ERS7HeadNames = &ERS7Info::outputNames[ERS7Info::HeadOffset]; + const unsigned int panIdx = capabilities.findOutputOffset(ERS7HeadNames[ERS7Info::PanOffset]); + const unsigned int tiltIdx = capabilities.findOutputOffset(ERS7HeadNames[ERS7Info::TiltOffset]); + if(panIdx==-1U || tiltIdx==-1U) + return; // guess we're headless, leave now... + +#if defined(TGT_QBOTPLUS) || defined(TGT_QWERK) + // these *should* be millimeters per second, but we haven't calibrated Qwerk yet + // so these are some unitless speed measurement for now :( + const float FAST = 32, SLOW = 20; +#else + // these are millimeters per second + const float FAST = 160, SLOW = 100; +#endif + + // We use the "Walk" motion command, but if it's wheel based, the WalkMC will still handle it anyway WalkMC * walker = (WalkMC*)motman->checkoutMotion(walker_id); - if(state->outputs[HeadOffset+PanOffset]<-.05 || state->outputs[HeadOffset+PanOffset]>.05) - walker->setTargetVelocity(100,0,state->outputs[HeadOffset+PanOffset]); + if(state->outputs[panIdx]<-.05 || state->outputs[panIdx]>.05) + walker->setTargetVelocity(SLOW,0,state->outputs[panIdx]); else - walker->setTargetVelocity(160,0,0); + walker->setTargetVelocity(FAST,0,0); // target straight ahead, full speed! motman->checkinMotion(walker_id); - - // cout << inview << ' ' << horiz << ' ' << vert << endl; - - double tilt=state->outputs[HeadOffset+TiltOffset]-vert*M_PI/7.5; - double pan=state->outputs[HeadOffset+PanOffset]-horiz*M_PI/6; - if(tiltDtoR(40)) - tilt=DtoR(40); - if(pan>DtoR(80)) - pan=DtoR(80); - if(pancheckoutMotion(headpointer_id); - headpointer->setJoints(tilt,pan,0); - motman->checkinMotion(headpointer_id); + + // proportional control to home in on the ball + // http://en.wikipedia.org/wiki/Proportional_control + double tilt=state->outputs[tiltIdx]-vert*CameraFOV/7.5; + double pan=state->outputs[panIdx]-horiz*CameraFOV/6; + + // We'll limit tilt and pan to their range of motion, but this isn't actually necessary, just demonstration: + tilt = std::max(tilt, outputRanges[tiltIdx][MinRange]); + tilt = std::min(tilt, outputRanges[tiltIdx][MaxRange]); + pan = std::max(pan, outputRanges[panIdx][MinRange]); + pan = std::min(pan, outputRanges[panIdx][MaxRange]); + + //! for comparison, this is a one-line version of the checkout/checkin used for the WalkMC + MMAccessor(headpointer_id)->setJoints(tilt,pan,0); } - + /*! @file * @brief Implements ChaseBallBehavior, which runs around after whatever the dog sees * @author ejt (Creator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/DrawVisObjBoundBehavior.h ./Behaviors/Demos/DrawVisObjBoundBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/DrawVisObjBoundBehavior.h 2006-06-30 12:37:03.000000000 -0400 +++ ./Behaviors/Demos/DrawVisObjBoundBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -48,12 +48,12 @@ unsigned char color; const FilterBankEvent& fbe=dynamic_cast(e); if(e.getGeneratorID()==EventBase::visRawCameraEGID) { - layer=fbe.getNumLayers()-1-config->vision.rawcam_y_skip; + layer=fbe.getNumLayers()-1-config->vision.rawcam.y_skip; chan=RawCameraGenerator::CHAN_Y; color=255; } else if(e.getGeneratorID()==EventBase::visSegmentEGID) { - layer=fbe.getNumLayers()-1-config->vision.segcam_skip; - chan=config->vision.segcam_channel; + layer=fbe.getNumLayers()-1-config->vision.segcam.skip; + chan=config->vision.segcam.channel; color=7; } else { std::cerr << "WARNING: " << getClassName() << " received vision event from unknown generator" << std::endl; @@ -68,7 +68,7 @@ //this is only needed until RLEGraphics is in place // in the mean time, we trigger the RLE generator to recompress the modified seg cam image - if(config->vision.segcam_compression==Config::vision_config::COMPRESS_RLE) + if(config->vision.segcam.compression==Config::vision_config::SegCamConfig::COMPRESS_RLE) ProjectInterface::defRLEGenerator->invalidateCaches(); drawn++; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/ExploreMachine.cc ./Behaviors/Demos/ExploreMachine.cc --- ../Tekkotsu_3.0/Behaviors/Demos/ExploreMachine.cc 2005-12-15 13:51:35.000000000 -0500 +++ ./Behaviors/Demos/ExploreMachine.cc 2007-06-26 00:27:43.000000000 -0400 @@ -1,27 +1,15 @@ +#include "Shared/RobotInfo.h" +#ifdef TGT_HAS_IR_DISTANCE + #include "ExploreMachine.h" #include "Behaviors/Nodes/WalkNode.h" #include "Behaviors/Transitions/SmoothCompareTrans.h" #include "Behaviors/Transitions/TimeOutTrans.h" -#include "Shared/ERS210Info.h" -#include "Shared/ERS220Info.h" -#include "Shared/ERS7Info.h" #include "Wireless/Socket.h" #include "Shared/WorldState.h" void ExploreMachine::setup() { //cout << "Explore SETUP " << issetup << "..."; - unsigned int IRDistOffset; - if(state->robotDesign&WorldState::ERS210Mask) - IRDistOffset=ERS210Info::IRDistOffset; - else if(state->robotDesign&WorldState::ERS220Mask) - IRDistOffset=ERS220Info::IRDistOffset; - else if(state->robotDesign&WorldState::ERS7Mask) - IRDistOffset=ERS7Info::NearIRDistOffset; - else { - serr->printf("ExploreMachine: Unsupported model!\n"); - return; - } - SharedObject walk; walkid=motman->addPersistentMotion(walk); @@ -31,7 +19,7 @@ start=addNode(turn=new WalkNode(getName()+"::turn",0,0,0.5f)); turn->setMC(walkid); - move->addTransition(new SmoothCompareTrans(turn,&state->sensors[IRDistOffset],CompareTrans::LT,350,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7)); + move->addTransition(new SmoothCompareTrans(turn,&state->sensors[IRDistOffset],CompareTrans::LT,350,EventBase(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID),.7)); turn->addTransition(new TimeOutTrans(move,2000)); StateNode::setup(); @@ -41,7 +29,7 @@ void ExploreMachine::DoStart() { StateNode::DoStart(); start->DoStart(); - //erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID); + //erouter->addListener(this,EventBase::sensorEGID,SensorSrcID::UpdatedSID); erouter->addListener(this,EventBase::stateMachineEGID,(size_t)turn,EventBase::activateETID); } @@ -72,8 +60,10 @@ * @author ejt (Creator) * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.3 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.5 $ * $State: Exp $ - * $Date: 2005/12/15 18:51:35 $ + * $Date: 2007/06/26 04:27:43 $ */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/ExploreMachine.h ./Behaviors/Demos/ExploreMachine.h --- ../Tekkotsu_3.0/Behaviors/Demos/ExploreMachine.h 2005-12-15 13:51:36.000000000 -0500 +++ ./Behaviors/Demos/ExploreMachine.h 2007-06-26 00:27:43.000000000 -0400 @@ -6,6 +6,11 @@ #include "Behaviors/Nodes/WalkNode.h" #include "Motion/MotionManager.h" +#include "Shared/RobotInfo.h" +#ifndef TGT_HAS_IR_DISTANCE +#error ExploreMachine requires a distance rangefinder via IRDistOffset +#endif + //! A state machine for exploring an environment (or searching for an object) class ExploreMachine : public StateNode { public: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/FollowHeadBehavior.cc ./Behaviors/Demos/FollowHeadBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Demos/FollowHeadBehavior.cc 2006-09-05 16:30:21.000000000 -0400 +++ ./Behaviors/Demos/FollowHeadBehavior.cc 2007-11-12 13:00:38.000000000 -0500 @@ -1,3 +1,6 @@ +#include "Shared/RobotInfo.h" +#ifdef TGT_HAS_BUTTONS + #include "FollowHeadBehavior.h" #include "Events/EventRouter.h" #include "Shared/debuget.h" @@ -7,6 +10,8 @@ #include "Motion/WalkMC.h" #include "Motion/PIDMC.h" +using namespace std; + FollowHeadBehavior::FollowHeadBehavior() : BehaviorBase("FollowHeadBehavior"), head_release(EventBase::buttonEGID,ChinButOffset,EventBase::activateETID,0), @@ -68,6 +73,8 @@ } } +#endif + /*! @file * @brief Implements FollowHeadBehavior, walks where the head is pointing * @author ejt (Creator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/FollowHeadBehavior.h ./Behaviors/Demos/FollowHeadBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/FollowHeadBehavior.h 2004-11-10 20:45:36.000000000 -0500 +++ ./Behaviors/Demos/FollowHeadBehavior.h 2007-03-04 20:19:08.000000000 -0500 @@ -1,5 +1,5 @@ //-*-c++-*- -#ifndef INCLUDED_FollowHeadBehavior_h_ +#if !defined(INCLUDED_FollowHeadBehavior_h_) && defined(TGT_HAS_BUTTONS) #define INCLUDED_FollowHeadBehavior_h_ #include "Behaviors/BehaviorBase.h" diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/GroundPlaneBehavior.h ./Behaviors/Demos/GroundPlaneBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/GroundPlaneBehavior.h 2006-03-03 18:08:39.000000000 -0500 +++ ./Behaviors/Demos/GroundPlaneBehavior.h 2007-11-12 13:00:38.000000000 -0500 @@ -10,6 +10,8 @@ #include "Shared/ERS7Info.h" #include "Shared/ERS2xxInfo.h" #include "Shared/WorldState.h" +#include "Events/VisionObjectEvent.h" +#include "Shared/ProjectInterface.h" //! Reports the location of the center of the camera image on the ground plane class GroundPlaneBehavior : public BehaviorBase { @@ -17,24 +19,26 @@ //! constructor GroundPlaneBehavior() : BehaviorBase("GroundPlaneBehavior"), - head_release(EventBase::buttonEGID,(state->robotDesign&WorldState::ERS7Mask)?(int)ERS7Info::HeadButOffset:(int)ERS2xxInfo::HeadFrButOffset,EventBase::activateETID,0), - head_lock(EventBase::buttonEGID,(state->robotDesign&WorldState::ERS7Mask)?(int)ERS7Info::HeadButOffset:(int)ERS2xxInfo::HeadFrButOffset,EventBase::deactivateETID,0), - clock(EventBase::timerEGID,0,EventBase::statusETID,250) + head_release(EventBase::buttonEGID,HeadButOffset,EventBase::activateETID,0), + head_lock(EventBase::buttonEGID,HeadButOffset,EventBase::deactivateETID,0), + target_toggle(EventBase::buttonEGID,ChinButOffset,EventBase::activateETID), + targeting(false), + visual_target(EventBase::visObjEGID,ProjectInterface::visYellowBallSID,EventBase::statusETID), + last_seen(0), + clock(EventBase::timerEGID,0,EventBase::statusETID,250) { } virtual void DoStart() { BehaviorBase::DoStart(); // do this first erouter->addListener(this,head_release); erouter->addListener(this,head_lock); + erouter->addListener(this,target_toggle); processEvent(clock); } - - virtual void DoStop() { - erouter->removeListener(this); - BehaviorBase::DoStop(); // do this last - } - + virtual void processEvent(const EventBase& e) { + using std::cout; + using std::endl; if(e==clock) { //This is the direction gravity is pulling - probably a good way to find out //the attitude of the robot, assuming it is not moving. @@ -65,7 +69,41 @@ processEvent(clock); } else if(e==head_lock) { motman->addPrunableMotion(SharedObject(HeadOffset,HeadOffset+NumHeadJoints,1)); - erouter->removeListener(this,clock); + erouter->removeTimer(this,clock); + } else if(e==target_toggle) { + if(targeting) { + erouter->removeListener(this,visual_target); + targeting=false; + } else { + erouter->addListener(this,visual_target); + targeting=true; + } + sndman->playFile("yap.wav"); + } else if(e==visual_target) { + cout << '.' << std::flush; + if(get_time()(e); + + cout << "Target position: " << visob.getCenterX()<< " " << visob.getCenterY() << " normalized: " << visob.getCenterX()/visob.getXrange()<< " " << visob.getCenterY()/visob.getYrange() << endl; + + //First we determine the ground plane + NEWMAT::ColumnVector p=kine->calculateGroundPlane(); + cout << "Ground plane: " << p(1)<<"x + " << p(2)<<"y + " << p(3)<<"z = 1" << endl; + + //Project to ground plane - we do it twice here, once for camera frame and once for base frame + NEWMAT::ColumnVector ray(4); + config->vision.computeRay(visob.getCenterX()/visob.getXrange(),visob.getCenterY()/visob.getYrange(),ray(1),ray(2),ray(3)); + ray(4)=1; + NEWMAT::ColumnVector hit; + //cout <<"Current head:\n"<outputs[HeadOffset] <<' '<< state->outputs[HeadOffset+1] <<' '<< state->outputs[HeadOffset+2] << endl <getTransform(CameraFrameOffset); + hit=kine->projectToPlane(CameraFrameOffset,ray,BaseFrameOffset,p,CameraFrameOffset); + cout << "Intersection_camera: (" << hit(1)<<','<projectToPlane(CameraFrameOffset,ray,BaseFrameOffset,p,BaseFrameOffset); + cout << "Intersection_base: (" << hit(1)<<','<robotDesign & WorldState::ERS7Mask) { - head_release.setSourceID(ERS7Info::HeadButOffset); - head_lock.setSourceID(ERS7Info::HeadButOffset); - } else if(state->robotDesign & WorldState::ERS210Mask) { - head_release.setSourceID(ERS210Info::HeadFrButOffset); - head_lock.setSourceID(ERS210Info::HeadFrButOffset); - } else if(state->robotDesign & WorldState::ERS220Mask) { - head_release.setSourceID(ERS220Info::HeadFrButOffset); - head_lock.setSourceID(ERS220Info::HeadFrButOffset); - } + head_release.setSourceID(HeadButOffset); + head_lock.setSourceID(HeadButOffset); head.getRegion()->AddReference(); } //! destructor diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/HelloWorldBehavior.h ./Behaviors/Demos/HelloWorldBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/HelloWorldBehavior.h 2004-11-10 20:45:36.000000000 -0500 +++ ./Behaviors/Demos/HelloWorldBehavior.h 2007-11-21 16:58:24.000000000 -0500 @@ -4,6 +4,7 @@ #include "Behaviors/BehaviorBase.h" #include "Wireless/Wireless.h" +#include "Behaviors/Controller.h" //! Demonstrates serr, sout, and cout class HelloWorldBehavior : public BehaviorBase { @@ -19,27 +20,37 @@ BehaviorBase::DoStart(); //now do your code: - for(unsigned int i=0; i<100; i++) - serr->printf("Hello serr! This is %d\n",i); - for(unsigned int i=0; i<10; i++) - sout->printf("Hello sout! This is %d\n",i); - for(unsigned int i=0; i<10; i++) - cout << "Hello cout! This is " << i << endl; - for(unsigned int i=0; i<10; i++) - printf("Hello printf! This is %d\n",i); + const unsigned int LINES=3; + for(unsigned int i=1; i<=LINES; i++) + serr->printf("Hello serr! This is %d of %d\n", i, LINES); + for(unsigned int i=1; i<=LINES; i++) + sout->printf("Hello sout! This is %d of %d\n", i, LINES); + for(unsigned int i=1; i<=LINES; i++) + std::cout << "Hello cout! This is " << i << " of " << LINES << std::endl; + for(unsigned int i=1; i<=LINES; i++) + printf("Hello printf! This is %d of %d\n", i, LINES); - //we'll just stop right away since this Behavior has no 'active' state. - DoStop(); //Note that you could also override this DoStop function... + // This will popup a message in the ControllerGUI, if one is connected + std::vector errmsg; + errmsg.push_back("Hello World! This is an informational message via the Controller\n" + "More messages have been sent on the console (cout, sout, etc.)"); + Controller::loadGUI("org.tekkotsu.mon.ControllerErr","",0,errmsg); + + // just stop right away since this Behavior has no 'active' state. + DoStop(); // Note that you could also override this DoStop function... } + //! static function allows GUI to present tooltip before any allocation + /*! Not required to implement, but nice! */ static std::string getClassDescription() { - // This string will be shown by the HelpControl or by the tooltips - // of the Controller GUI (not required, but nice) - return "A little demo of text output"; + return "A little demo of text output, sends some lines of text " + "to serr, sout, cout, and printf."; } + + //! virtual function provides description of instance of unknown type + /*! Usually just a matter of forwarding call to getClassDescription(). + * Again, not required to do, but nice! :) */ virtual std::string getDescription() const { - // We override this function to return the string we supplied - // above (not required, but nice) return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/KinematicSampleBehavior2.h ./Behaviors/Demos/KinematicSampleBehavior2.h --- ../Tekkotsu_3.0/Behaviors/Demos/KinematicSampleBehavior2.h 2005-06-01 01:47:45.000000000 -0400 +++ ./Behaviors/Demos/KinematicSampleBehavior2.h 2007-11-12 13:00:38.000000000 -0500 @@ -35,6 +35,8 @@ } virtual void processEvent(const EventBase& e) { + using std::cout; + using std::endl; if(e.getGeneratorID()==EventBase::buttonEGID) { switch(e.getSourceID()) { case LFrPawOffset: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/LocalizationBehavior.h ./Behaviors/Demos/LocalizationBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/LocalizationBehavior.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Demos/LocalizationBehavior.h 2007-11-11 18:57:18.000000000 -0500 @@ -0,0 +1,275 @@ +//-*-c++-*- +#ifndef INCLUDED_LocalizationBehavior_h_ +#define INCLUDED_LocalizationBehavior_h_ + +#include "Behaviors/BehaviorBase.h" +#include "Events/EventRouter.h" +#include "DualCoding/DualCoding.h" +//these are included indirectly via DualCoding.h: +//#include "Shared/ParticleFilter.h" +//#include "Shared/LocalizationParticle.h" + +#include "Motion/LedMC.h" +#include "Motion/MMAccessor.h" +#include "Motion/MotionManager.h" + +//! A behavior which tracks the robots location using a dual-coding-based "shape sensor" +/*! The behavior draws 10% of the particles on the world map for visualization, and updates + * the motion model once a second if no landmarks have been seen, so you can + * press "refresh" in the world map and get an updated view of how the particles + * have moved. + * + * The landmarks are expected to be arranged as defined by setupLandmarksOnMap(). + * If you want to define what your world looks like, edit the function to provide your own layout.*/ +class LocalizationBehavior : public DualCoding::VisualRoutinesBehavior { +public: + + //! constructor + LocalizationBehavior() : VisualRoutinesBehavior("LocalizationBehavior"), + mapreq(DualCoding::MapBuilderRequest::localMap), lastvis(-1U), leds_id(MotionManager::invalid_MC_ID) + {} + + virtual void DoStart() { + VisualRoutinesBehavior::DoStart(); // do this first (required) + + // PARTICLE FILTER SETUP + // have to wait to do this in DoStart instead of constructor because the global + // VRmixin::particleFilter isn't created until a client behavior is started. + + // changing some parameters in the default resampler + typedef DualCoding::PFShapeLocalization::LowVarianceResamplingPolicy ResamplingPolicy; + if(ResamplingPolicy* resample = dynamic_cast(particleFilter->getResamplingPolicy())) { + // by default, resampling occurs on each update (delay=0) + // Since groundplane projection is quite noisy while walking, we'll need quite a few more + // samples before we get a good estimate of particle accuracy + resample->resampleDelay=30; + + // by default the minimum is -FLT_MAX (essentially no minimum) + // we'll require particles to have at least some feasability or we'll randomize to try to re-localize + resample->minAcceptableWeight=log(1.0e-13); // logarthmic scale, avoids numeric issues (configurable) + } + + // If you want to change the resampling variance: + // This controls how "tight" the cluster can get after we evaluate the particles + // Regarding the typedef: every resampling policy embeds a distribution policy, the + // default policy is specified by the particle's own DistributionPolicy typedef + typedef DualCoding::PFShapeLocalization::particle_type::DistributionPolicy DistributionPolicy; + if(DistributionPolicy* dp = dynamic_cast(&particleFilter->getResamplingPolicy()->getDistributionPolicy())) { + dp->positionVariance*=1; + dp->orientationVariance*=1; + } + + // specifying motion model variance (how much do particles spread over time) + // note that if we tracked robot velocity as a particle parameter, we could use resampling variance instead... + // (and then get an estimate of actual velocity as well!) + typedef HolonomicMotionModel MotionModel; + if(MotionModel * motion = dynamic_cast(particleFilter->getMotionModel())) { + // these are currently the default parameters, but explicitly reset for demonstration: + motion->setVariance(.25,.25,.25); + } + + + // MAP BUILDER REQUEST SETUP + const int pink_index = ProjectInterface::getColorIndex("pink"); + const int yellow_index = ProjectInterface::getColorIndex("yellow"); + //const int orange_index = ProjectInterface::getColorIndex("orange"); + mapreq.objectColors[DualCoding::ellipseDataType].insert(pink_index); + mapreq.objectColors[DualCoding::ellipseDataType].insert(yellow_index); + //mapreq.objectColors[ellipseDataType].insert(orange_index); + + // a hard coded gound plane corresponding to the default walk parameters + // better to let it figure it out from sensors while walking, but this is better if standing still... (but only in the walk position!) + //mapreq.setCustomGroundPlane(0.20944, 115); + mapreq.maxDist=2000; + + + // EVENT LISTENER SETUP + // only do processing on camera frames where there's possibly something to see + erouter->addListener(this, EventBase::visObjEGID, ProjectInterface::visPinkBallSID, EventBase::statusETID); + erouter->addListener(this, EventBase::visObjEGID, ProjectInterface::visYellowBallSID, EventBase::statusETID); + //erouter->addListener(this, EventBase::visObjEGID, //ProjectInterface::visOrangeSID, EventBase::statusETID); + + erouter->addTimer(this,-1U,1000,true); // update motion model regularly (even if not seeing anything) + + + // MOTION COMMAND SETUP + // using leds for displaying confidence + SharedObject leds_mc; + leds_id = motman->addPersistentMotion(leds_mc); + } + + virtual void DoStop() { + motman->removeMotion(leds_id); + VisualRoutinesBehavior::DoStop(); // do this last (required) + } + + //! this function defines the expected layout of the world + void setupLandmarksOnMap() { + // a pair of ellipses (pink and yellow) + NEW_SHAPE(pinkm,DualCoding::EllipseData,new DualCoding::EllipseData(worldShS,DualCoding::Point(65,0,0,DualCoding::allocentric),27.5,27.5)); + pinkm->setColor("pink"); + pinkm->setMobile(false); + NEW_SHAPE(yellowm,DualCoding::EllipseData,new DualCoding::EllipseData(worldShS,DualCoding::Point(-65,0,0,DualCoding::allocentric),27.5,27.5)); + yellowm->setColor("yellow"); + yellowm->setMobile(false); + + // a square marked by ellipses in each corner + // pink on the "top" edge, and yellow on the "bottom" + /* + NEW_SHAPE(pinkm,EllipseData,new EllipseData(worldShS,Point(700,700,0,allocentric),27.5,27.5)); + pinkm->setColor("pink"); + pinkm->setMobile(false); + NEW_SHAPE(yellowm,EllipseData,new EllipseData(worldShS,Point(700,0,0,allocentric),27.5,27.5)); + yellowm->setColor("yellow"); + yellowm->setMobile(false); + NEW_SHAPE(pink2m,EllipseData,new EllipseData(worldShS,Point(0,700,0,allocentric),27.5,27.5)); + pink2m->setColor("pink"); + pink2m->setMobile(false); + NEW_SHAPE(yellow2m,EllipseData,new EllipseData(worldShS,Point(0,0,0,allocentric),27.5,27.5)); + yellow2m->setColor("yellow"); + yellow2m->setMobile(false); + */ + } + + //! by uncommenting some of the erouter calls, you can make it skip frames (currently tries to process all) + virtual void processEvent(const EventBase& event) { + switch (event.getGeneratorID()){ + + case EventBase::visObjEGID: + { + // update local map + const VisionObjectEvent &visev = dynamic_cast(event); + unsigned int curvis = visev.getFrame(); + if (curvis == lastvis){ + std::cout << "Current = Previous" << std::endl; + //erouter->removeListener(this,event); + //erouter->addTimer(this,event.getSourceID(),1000,false); + return ; + } + lastvis = curvis; + std::cout << "Localizing off of " << event.getName() << "... " << std::endl; + + //unsigned int mapreq_id = + mapBuilder.executeRequest(mapreq); + // we're using an "immediate" map builder request, so we don't have to wait for the event... + //erouter->addListener(this, EventBase::mapbuilderEGID, mapreq_id, EventBase::statusETID); + + // now update the particle filter + worldShS.clear(); // clear particles and other junk we may have drawn on the map as feedback + setupLandmarksOnMap(); // refresh the landmarks + particleFilter->update(); // ask the particle filter to match the local space against the world space for each particle + erouter->addTimer(this,-1U,1000,true); // delay motion model update (since we just updated on previous line) + + // now update the display + updateAgentOnMap(); + displayParticlesOnMap(); + ledSettings(); + + //erouter->removeListener(this,event); + //erouter->addTimer(this,event.getSourceID(), 1000,false); + break; + } + + case EventBase::timerEGID: + { + if(event.getSourceID()==-1U) { + std::cout << "Updating motion model!" << std::endl; + particleFilter->updateMotion(); + + // refresh the display + worldShS.clear(); + setupLandmarksOnMap(); + displayParticlesOnMap(); + updateAgentOnMap(); + + } else { + // this won't be called unless you comment-in the lines which skip camera frames + std::cout << "Re-enabling vision listener" << std::endl; + erouter->addListener(this, EventBase::visObjEGID, event.getSourceID(), EventBase::statusETID); + } + break; + } + + default: + std::cout << "Unexpected event: " << event.getDescription() << std::endl; + break; + } + } + + //! places the agent at the most likely particle + void updateAgentOnMap() { + const DualCoding::PFShapeLocalization::particle_type& p = particleFilter->getBestParticle(); + std::cout << "Best index: " << particleFilter->getBestIndex() << " with score: " << p.weight << std::endl; + mapBuilder.setAgent(DualCoding::Point(p.x,p.y), p.theta); + std::cout << "DATA1 Current positions: " << p.x << " " << p.y << " " << p.theta << std::endl; + } + + //! draws a sample (10%) of the particles on the map + void displayParticlesOnMap() { + particleFilter->displayParticles(); + //or manually: + /*if(particleFilter->getParticles().size() < 10) + cout << "CURRENT PARTICLES LESS THAN 10!" << endl; + for(unsigned int i = 0; i < particleFilter->getParticles().size(); i+=10) { + const ShapeLocalizationPF::particle_type& p = particleFilter->getParticles()[i]; + NEW_SHAPE(pt, PointData, new PointData(worldShS, Point(p.x,p.y,0,allocentric))); + }*/ + } + + //! updates the LEDs to show the confidence interval; the smaller the confidence interval, the more LEDs will turn on + void ledSettings() { + float confidence = particleFilter->getConfidenceInterval(); + std::cout << std::endl << "Confidence: " << confidence << std::endl << std::endl; + MMAccessor leds_acc(leds_id); + + float c = 0; + if(confidence < 500 && confidence>=0) { + //linear dropoff: + // c=(1-confidence/500); + + //or exponential dropoff: + c=exp(-(confidence-60)/150); + } + leds_acc->displayPercent(c,LedEngine::major,LedEngine::major); + } + + static std::string getClassDescription() { return "A behavior which tracks the robots location using a dual-coding-based \"shape sensor\""; } + virtual std::string getDescription() const { return getClassDescription(); } + + +protected: + //! used to request the DualCoding::MapBuilder project cam-space shapes to the local-space + DualCoding::MapBuilderRequest mapreq; + + //! serial number of the last processed camera frame + /*! if there are multiple landmarks in the same image, we don't want to process + * the same image multiple times for each landmark. Tracking the camera frame + * makes sure we only do each frame at most once */ + unsigned int lastvis; + + //! used to display the confidence of the particle filter on the LEDs + MotionManager::MC_ID leds_id; + + +private: + // Providing declarations for these functions will avoid a compiler warning if + // you have any class members which are pointers. However, as it is, an error + // will result if you inadvertantly cause a call to either (which is probably + // a good thing, unless you really intended to copy/assign a behavior, in + // which case simply provide implementations for the functions) + LocalizationBehavior(const LocalizationBehavior&); //!< don't call (copy constructor) + LocalizationBehavior& operator=(const LocalizationBehavior&); //!< don't call (assignment operator) +}; + +/*! @file + * @brief Defines LocalizationBehavior, which tracks the robots location using a dual-coding-based "shape sensor" + * @author Ashley Johnson and Ethan Tira-Thompson (Creators) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.6 $ + * $State: Exp $ + * $Date: 2007/11/11 23:57:18 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/LookForSoundBehavior.h ./Behaviors/Demos/LookForSoundBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/LookForSoundBehavior.h 2004-12-22 20:47:06.000000000 -0500 +++ ./Behaviors/Demos/LookForSoundBehavior.h 2007-08-05 12:16:04.000000000 -0400 @@ -5,6 +5,9 @@ #include "Behaviors/BehaviorBase.h" #include "Motion/HeadPointerMC.h" #include "Events/DataEvent.h" +#include "Events/EventRouter.h" +#include "Shared/ODataFormats.h" +#include "Motion/MMAccessor.h" //! Turns head to sound source, estimated by average volume difference between left and right ears class LookForSoundBehavior : public BehaviorBase { @@ -51,7 +54,7 @@ // If there is sufficient energy coming in if( l+r > sz*1000.){ MMAccessor mc(mc_id); - double cur = state->outputs[ERS7Info::HeadOffset+1]; + double cur = state->outputs[HeadOffset+PanOffset]; if( r > 1.3*l) // Move your head righward mc->setJoints( 0, cur-.2*M_PI/(r/l), 0); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/MotionStressTestBehavior.h ./Behaviors/Demos/MotionStressTestBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/MotionStressTestBehavior.h 2005-08-07 00:11:03.000000000 -0400 +++ ./Behaviors/Demos/MotionStressTestBehavior.h 2007-11-12 13:00:38.000000000 -0500 @@ -31,7 +31,7 @@ ms->setOutputCmd(i,0); MotionManager::MC_ID id=motman->addPrunableMotion(ms); curMotions.push(id); - cout << get_time() << "\tAdded id " << id << endl; + std::cout << get_time() << "\tAdded id " << id << std::endl; addMS(LFrLegOrder,3000); addMS(RFrLegOrder,4000); addMS(LBkLegOrder,5000); @@ -50,11 +50,11 @@ virtual void processEvent(const EventBase& e) { if(e.getTypeID()==EventBase::deactivateETID) { if(e.getSourceID()!=curMotions.front()) { - cout << e.getSourceID() << " is not mine or is out of order" << endl; + std::cout << e.getSourceID() << " is not mine or is out of order" << std::endl; } else { curMotions.pop(); } - cout << get_time() << "\t Removed id " << e.getSourceID() << endl; + std::cout << get_time() << "\t Removed id " << e.getSourceID() << std::endl; addMS(nextLeg,3000); nextLeg=static_cast((nextLeg+1)%4); } @@ -72,7 +72,7 @@ ms->setOutputCmd(index,outputRanges[index][MaxRange]); MotionManager::MC_ID id=motman->addPrunableMotion(ms); curMotions.push(id); - cout << get_time() << "\tAdded id " << id << endl; + std::cout << get_time() << "\tAdded id " << id << std::endl; } static std::string getClassDescription() { return "uses a separate MotionCommand for each of several joints to test for region leaks"; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/PaceTargetsMachine.cc ./Behaviors/Demos/PaceTargetsMachine.cc --- ../Tekkotsu_3.0/Behaviors/Demos/PaceTargetsMachine.cc 2006-09-18 14:07:57.000000000 -0400 +++ ./Behaviors/Demos/PaceTargetsMachine.cc 2007-07-16 14:31:39.000000000 -0400 @@ -1,3 +1,6 @@ +#include "Shared/RobotInfo.h" +#ifdef TGT_HAS_IR_DISTANCE + #include "PaceTargetsMachine.h" #include "Behaviors/Transition.h" #include "Behaviors/Nodes/WalkToTargetNode.h" @@ -88,9 +91,10 @@ * @author ejt (Creator) * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.20 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.22 $ * $State: Exp $ - * $Date: 2006/09/18 18:07:57 $ + * $Date: 2007/07/16 18:31:39 $ */ +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/PaceTargetsMachine.h ./Behaviors/Demos/PaceTargetsMachine.h --- ../Tekkotsu_3.0/Behaviors/Demos/PaceTargetsMachine.h 2005-01-24 17:23:46.000000000 -0500 +++ ./Behaviors/Demos/PaceTargetsMachine.h 2007-07-16 14:31:39.000000000 -0400 @@ -2,6 +2,11 @@ #ifndef INCLUDED_PaceTargetsMachine_h_ #define INCLUDED_PaceTargetsMachine_h_ +#include "Shared/RobotInfo.h" +#ifndef TGT_HAS_IR_DISTANCE +#error PaceTargetsMachine requires a distance rangefinder via IRDistOffset +#endif + #include "Behaviors/StateNode.h" #include "Shared/ProjectInterface.h" diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/RelaxBehavior.h ./Behaviors/Demos/RelaxBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/RelaxBehavior.h 2005-06-01 01:47:45.000000000 -0400 +++ ./Behaviors/Demos/RelaxBehavior.h 2007-11-11 18:57:18.000000000 -0500 @@ -8,8 +8,6 @@ #include "IPC/SharedObject.h" #include "Motion/MotionManager.h" -using namespace std; - //! A behavior that sets all the pids to zero for the tail and legs servos. /*! This should hopefully make the robot quieter and consume less power. */ class RelaxBehavior : public BehaviorBase { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/SimpleChaseBallBehavior.h ./Behaviors/Demos/SimpleChaseBallBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/SimpleChaseBallBehavior.h 2005-05-03 12:30:29.000000000 -0400 +++ ./Behaviors/Demos/SimpleChaseBallBehavior.h 2007-11-15 00:19:22.000000000 -0500 @@ -10,6 +10,7 @@ #include "Events/VisionObjectEvent.h" #include "Shared/WorldState.h" #include "Motion/WalkMC.h" +#include "Shared/ERS7Info.h" //! A simple behavior to chase after any objects seen by the vision system /*! Similar to ChaseBallBehavior, but this one doesn't try to move the head, so @@ -41,10 +42,14 @@ //! sets the head to point at the object and sets the body to move where the head points virtual void processEvent(const EventBase& event) { if(event.getGeneratorID()==EventBase::visObjEGID && event.getTypeID()==EventBase::statusETID) { + // see if the camera is on a pan joint, we're using the ERS-7's pan joint as a prototype of what to look for... + const unsigned int panIdx = capabilities.findOutputOffset(ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset]); + float panAngle = (panIdx!=-1U) ? state->outputs[panIdx] : 0; // get its angle, or assume 0 if not found + //x and y are the direction to walk; positive x is forward and positive y is left //so these calculations walk the direction the head is pointing (at 120 mm/sec) - float x=120.0f*cos(state->outputs[HeadOffset+PanOffset]); - float y=120.0f*sin(state->outputs[HeadOffset+PanOffset]); + float x=120.0f*cos(panAngle); + float y=120.0f*sin(panAngle); //z is the amount to turn in radians; conveniently enough, we can use the //x parameter from the vision event as the speed to turn -- you could diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/SoundTestBehavior.h ./Behaviors/Demos/SoundTestBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/SoundTestBehavior.h 2006-09-18 14:07:57.000000000 -0400 +++ ./Behaviors/Demos/SoundTestBehavior.h 2007-06-28 00:36:20.000000000 -0400 @@ -14,7 +14,7 @@ * up and then played successively once the chin button is released. * * Notice that this doesn't preload all needed sounds:\n - * - @c barkmed.wav is listed in ms/config/tekkotsu.cfg as a preloaded system sound + * - @c barkmed.wav is listed in ms/config/tekkotsu.xml as a preloaded system sound * - @c growl.wav will be loaded before being played automatically - notice the * hiccup this can cause. */ @@ -27,15 +27,11 @@ RFr(EventBase::buttonEGID,RFrPawOffset,EventBase::activateETID), LBk(EventBase::buttonEGID,LBkPawOffset,EventBase::activateETID), RBk(EventBase::buttonEGID,RBkPawOffset,EventBase::activateETID), - Back(EventBase::buttonEGID,0,EventBase::activateETID) + Back(EventBase::buttonEGID,NumButtons-1,EventBase::activateETID) { - //different models vary widely in their back buttons - if(state->robotDesign & WorldState::ERS210Mask) - Back.setSourceID(ERS210Info::BackButOffset); - else if(state->robotDesign & WorldState::ERS220Mask) - Back.setSourceID(ERS220Info::BackButOffset); - else if(state->robotDesign & WorldState::ERS7Mask) - Back.setSourceID(ERS7Info::FrontBackButOffset); + if(capabilities.getButtonOffset("BackBut")!=-1U) + Back.setSourceID(capabilities.getButtonOffset("BackBut")); + // otherwise unknown model, just use last button (NumButtons-1, as set in constructor) } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/StareAtBallBehavior.cc ./Behaviors/Demos/StareAtBallBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Demos/StareAtBallBehavior.cc 2006-09-26 17:47:00.000000000 -0400 +++ ./Behaviors/Demos/StareAtBallBehavior.cc 2007-11-15 16:29:17.000000000 -0500 @@ -5,6 +5,7 @@ #include "Motion/HeadPointerMC.h" #include "Motion/MMAccessor.h" #include "Shared/ProjectInterface.h" +#include "Shared/ERS7Info.h" //! Converts degrees to radians inline double DtoR(double deg) { return (deg/180.0*M_PI); } @@ -30,22 +31,37 @@ vert=objev.getCenterY(); } + // for portability, look to see if the host hardware has a head pan & tilt joints + const unsigned int panIdx = capabilities.findOutputOffset(ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset]); + const unsigned int tiltIdx = capabilities.findOutputOffset(ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::TiltOffset]); + if(panIdx==-1U || tiltIdx==-1U) + return; // guess not... + //cout << horiz << ' ' << vert << endl; // Very simple visual servoing control -- move the head a small distance in the direction of the target // This is "proportional" control, because we move the head proportionally further when the error (horiz and vert) is larger - double tilt=state->outputs[HeadOffset+TiltOffset]-vert*M_PI/7; - double pan=state->outputs[HeadOffset+PanOffset]-horiz*M_PI/6; + double tilt=state->outputs[tiltIdx]-vert*CameraFOV/7; + double pan=state->outputs[panIdx]-horiz*CameraFOV/6; // now request access to the headpointer we added in DoStart and set the joint angles MMAccessor headpointer(headpointer_id); - if(state->robotDesign & WorldState::ERS7Mask) { +#ifdef TGT_IS_AIBO + if(RobotName == ERS7Info::TargetName) { //on an ers-7, we want to set the nod joint to look up (maximum value), since tilt can only look down headpointer->setJoints(tilt,pan,outputRanges[HeadOffset+NodOffset][MaxRange]); } else { //on other models (we'll just assume ers-2xx), center the roll joint headpointer->setJoints(tilt,pan,0); } +#else + /* really should do a kinematic solution with lookInDirection, but that assumes + * user has done a .kin file for this robot. Let's just keep it simple and try to + * set the joints directly */ + if(NumHeadJoints>2) + tilt/=2; // we're going to replicate the tilt parameter in the next call, so divide by 2 + headpointer->setJoints(tilt,pan,tilt); +#endif } /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/StareAtPawBehavior2.cc ./Behaviors/Demos/StareAtPawBehavior2.cc --- ../Tekkotsu_3.0/Behaviors/Demos/StareAtPawBehavior2.cc 2005-08-04 17:09:26.000000000 -0400 +++ ./Behaviors/Demos/StareAtPawBehavior2.cc 2007-06-28 00:36:20.000000000 -0400 @@ -1,3 +1,6 @@ +#include "Shared/RobotInfo.h" +#if defined(TGT_HAS_LEGS) + #include "StareAtPawBehavior2.h" #include "Events/EventRouter.h" @@ -10,6 +13,7 @@ #include "Motion/roboop/robot.h" #include "Shared/Config.h" #include "Motion/Kinematics.h" +#include "Shared/ERS7Info.h" // these are for drawing into the camera frame #include "Shared/ProjectInterface.h" @@ -33,7 +37,7 @@ //visRawCameraEGID to draw a dot on the camera image where we think the toe is erouter->addListener(this,EventBase::visRawCameraEGID,ProjectInterface::visRawCameraSID,EventBase::statusETID); - if(state->robotDesign == WorldState::ERS7Mask) + if(RobotName == ERS7Info::TargetName) sout->printf("NOTICE: The ERS-7 has a rather \"sticky\" nod joint\n" "(the upper tilt joint). This can cause it to hesitate\n" "or altogether fail to precisely center the target position\n" @@ -125,6 +129,8 @@ } } +#endif // has legs + /*! @file * @brief Implements StareAtPawBehavior2, which uses new-style ROBOOP kinematics to track the paw which last received a button press with the camera * @author ejt (Creator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/TestBehaviors.h ./Behaviors/Demos/TestBehaviors.h --- ../Tekkotsu_3.0/Behaviors/Demos/TestBehaviors.h 2006-09-05 15:40:07.000000000 -0400 +++ ./Behaviors/Demos/TestBehaviors.h 2007-11-11 18:57:18.000000000 -0500 @@ -51,7 +51,7 @@ class SuicidalBehavior : public BehaviorBase { public: SuicidalBehavior() : BehaviorBase("SuicidalBehavior") {} //!< constructor - ~SuicidalBehavior() { std::cout << getName() << " destructed" << endl; } //!< destructor + ~SuicidalBehavior() { std::cout << getName() << " destructed" << std::endl; } //!< destructor virtual void DoStart() { BehaviorBase::DoStart(); erouter->addTimer(this,0,1000); std::cout << "One second to live!" << std::endl; } virtual void processEvent(const EventBase& /*event*/) { std::cout << "I'm stopping -- refresh controller to see if it worked!" << std::endl; DoStop(); } static std::string getClassDescription() { return "Stops itself after a second via timer event"; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/ToggleHeadLightBehavior.h ./Behaviors/Demos/ToggleHeadLightBehavior.h --- ../Tekkotsu_3.0/Behaviors/Demos/ToggleHeadLightBehavior.h 2005-06-01 01:47:45.000000000 -0400 +++ ./Behaviors/Demos/ToggleHeadLightBehavior.h 2007-06-26 00:27:43.000000000 -0400 @@ -15,7 +15,7 @@ //! opens the head light virtual void DoStart() { BehaviorBase::DoStart(); - if(state->robotDesign & WorldState::ERS220Mask) { + if(RobotName == ERS220Info::TargetName) { SharedObject pose; pose->setOutputCmd(ERS220Info::RetractableHeadLEDOffset,true); light_id=motman->addPersistentMotion(pose); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/WallTestBehavior.cc ./Behaviors/Demos/WallTestBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Demos/WallTestBehavior.cc 2006-07-13 13:25:50.000000000 -0400 +++ ./Behaviors/Demos/WallTestBehavior.cc 2007-11-12 13:00:38.000000000 -0500 @@ -1,3 +1,6 @@ +#include "Shared/RobotInfo.h" +#ifdef TGT_HAS_IR_DISTANCE + #include "WallTestBehavior.h" #include "Shared/newmat/newmat.h" #include "Shared/newmat/newmatap.h" @@ -10,6 +13,8 @@ #include "Shared/TimeET.h" #include +using namespace std; + void WallTestBehavior::DoStart() { BehaviorBase::DoStart(); // do this first @@ -89,7 +94,7 @@ } else if(e.getSourceID()==0) { // must be a timer event -- SID 0 indicates start of recording // so start subscribing to sensor events - erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID); + erouter->addListener(this,EventBase::sensorEGID,SensorSrcID::UpdatedSID); } else if(e.getSourceID()==1) { // must be a timer event -- SID 1 indicates stop of recording @@ -283,3 +288,5 @@ x0=V(1,V.ncols())/V(3,V.ncols()); x1=V(2,V.ncols())/V(3,V.ncols()); } + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/karmedbandit.h ./Behaviors/Demos/karmedbandit.h --- ../Tekkotsu_3.0/Behaviors/Demos/karmedbandit.h 2003-09-18 18:40:27.000000000 -0400 +++ ./Behaviors/Demos/karmedbandit.h 2007-11-12 13:00:38.000000000 -0500 @@ -24,18 +24,18 @@ unsigned int decide() { std::vector p(w.size()); double wsum=0; - cout << "w ="; + std::cout << "w ="; for(unsigned int i=0; iaddListener(this, EventBase::estopEGID); // Turn on wireless - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 300, 300); + cmdsock=wireless->socket(Socket::SOCK_STREAM, 300, 300); wireless->setDaemon(cmdsock,true); wireless->setReceiver(cmdsock->sock, callback); wireless->listen(cmdsock->sock, config->main.estopControl_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/EStopControllerBehavior.h ./Behaviors/Mon/EStopControllerBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/EStopControllerBehavior.h 2004-12-10 18:18:10.000000000 -0500 +++ ./Behaviors/Mon/EStopControllerBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -41,7 +41,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.estopControl_port); + sprintf(tmp,"%d",*config->main.estopControl_port); return std::string("Listens to estop commands coming in from port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/EchoBehavior.cc ./Behaviors/Mon/EchoBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/EchoBehavior.cc 2005-08-01 19:17:59.000000000 -0400 +++ ./Behaviors/Mon/EchoBehavior.cc 2007-05-21 16:51:20.000000000 -0400 @@ -27,8 +27,8 @@ } void EchoBehavior::setupNetwork() { - sockets[STCP]=wireless->socket(SocketNS::SOCK_STREAM); - sockets[SUDP]=wireless->socket(SocketNS::SOCK_DGRAM); + sockets[STCP]=wireless->socket(Socket::SOCK_STREAM); + sockets[SUDP]=wireless->socket(Socket::SOCK_DGRAM); socks[STCP]=sockets[STCP]->sock; socks[SUDP]=sockets[SUDP]->sock; wireless->setDaemon(sockets[STCP],true); @@ -72,14 +72,14 @@ } if(string_util::makeLower(args[1])=="tcp") { if(sockets[CTCP]==NULL) { - sockets[CTCP]=wireless->socket(SocketNS::SOCK_STREAM); + sockets[CTCP]=wireless->socket(Socket::SOCK_STREAM); socks[CTCP]=sockets[CTCP]->sock; wireless->setReceiver(sockets[CTCP], client_callbackT); } wireless->connect(sockets[CTCP],args[2].c_str(),atoi(args[3].c_str())); } else if(string_util::makeLower(args[1])=="udp") { if(sockets[CUDP]==NULL) { - sockets[CUDP]=wireless->socket(SocketNS::SOCK_DGRAM); + sockets[CUDP]=wireless->socket(Socket::SOCK_DGRAM); socks[CUDP]=sockets[CUDP]->sock; wireless->setReceiver(sockets[CUDP], client_callbackU); } @@ -100,8 +100,8 @@ cout << endl; } } else if(args[0]=="relay" || args[0]=="unlink") { - unsigned char from=-1U; - unsigned char to=-1U; + unsigned char from=(unsigned char)-1U; + unsigned char to=(unsigned char)-1U; bool val = (args[0]=="relay"); unsigned int i=1; for(; i0?MaxRange:MinRange]; @@ -34,8 +37,38 @@ r = fabs(param)*outputRanges[HeadOffset+RollOffset][param>0?MaxRange:MinRange]; break; default: - cout << "MECHA: unknown command " << command[0] << endl; + std::cout << "MECHA: unknown command " << command[0] << std::endl; } +#else + switch(command[0]) { + case CMD_tilt: { + const char* n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::TiltOffset]; + unsigned int i = capabilities.findOutputOffset(n); + if(i!=-1U) + t = fabs(param)*outputRanges[i][param>0?MaxRange:MinRange]; + } break; + case CMD_pan: { + const char* n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset]; + unsigned int i = capabilities.findOutputOffset(n); + if(i!=-1U) + p = fabs(param)*outputRanges[i][param>0?MaxRange:MinRange]; + } break; + case CMD_roll: { + const char* n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::NodOffset]; + unsigned int i = capabilities.findOutputOffset(n); + if(i!=-1U) + r = fabs(param)*outputRanges[i][param>0?MaxRange:MinRange]; + else { + n = ERS210Info::outputNames[ERS210Info::HeadOffset+ERS210Info::RollOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + r = fabs(param)*outputRanges[i][param>0?MaxRange:MinRange]; + } + } break; + default: + std::cout << "MECHA: unknown command " << command[0] << std::endl; + } +#endif // If the command was a new motion command, apply the // new motion parameters: @@ -54,11 +87,13 @@ // Behavior startup BehaviorBase::DoStart(); // Enable head control - head_id = motman->addPersistentMotion(SharedObject()); + SharedObject head; + head->setHold(false); + head_id = motman->addPersistentMotion(head); // Turn on wireless theLastOne=theOne; theOne=this; - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 2048, 2048); + cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 2048); wireless->setReceiver(cmdsock->sock, mechacmd_callback); wireless->setDaemon(cmdsock,true); wireless->listen(cmdsock->sock, config->main.headControl_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/HeadPointControllerBehavior.h ./Behaviors/Mon/HeadPointControllerBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/HeadPointControllerBehavior.h 2005-09-13 18:10:36.000000000 -0400 +++ ./Behaviors/Mon/HeadPointControllerBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -79,7 +79,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.headControl_port); + sprintf(tmp,"%d",*config->main.headControl_port); return std::string("Listens to head control commands coming in from port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/MicrophoneServer.cc ./Behaviors/Mon/MicrophoneServer.cc --- ../Tekkotsu_3.0/Behaviors/Mon/MicrophoneServer.cc 2005-08-07 00:11:03.000000000 -0400 +++ ./Behaviors/Mon/MicrophoneServer.cc 2007-11-21 15:57:13.000000000 -0500 @@ -13,11 +13,11 @@ MicrophoneServer* MicrophoneServer::instance = 0; const char* const MicrophoneServer::MIC_LOCATOR = "PRM:/r1/c1/c2/c3/m1-Mic:M1"; -MicrophoneServer* MicrophoneServer::GetInstance() { +MicrophoneServer& MicrophoneServer::getInstance() { if (instance == 0) { instance = new MicrophoneServer(); } - return instance; + return *instance; } MicrophoneServer::MicrophoneServer() @@ -42,7 +42,7 @@ socket = 0; } - socket = wireless->socket(SocketNS::SOCK_STREAM, 512, SEND_BUFFER_SIZE); + socket = wireless->socket(Socket::SOCK_STREAM, 512, SEND_BUFFER_SIZE); wireless->setDaemon(socket, true); wireless->listen(socket->sock, config->sound.streaming.mic_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/MicrophoneServer.h ./Behaviors/Mon/MicrophoneServer.h --- ../Tekkotsu_3.0/Behaviors/Mon/MicrophoneServer.h 2006-09-16 13:32:38.000000000 -0400 +++ ./Behaviors/Mon/MicrophoneServer.h 2007-11-21 15:57:13.000000000 -0500 @@ -9,7 +9,7 @@ class MicrophoneServer : public BehaviorBase { public: //!enforces singleton status - static MicrophoneServer* GetInstance(); + static MicrophoneServer& getInstance(); virtual ~MicrophoneServer(); //!< destructor virtual void DoStart(); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/RawCamBehavior.cc ./Behaviors/Mon/RawCamBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/RawCamBehavior.cc 2006-09-14 14:57:03.000000000 -0400 +++ ./Behaviors/Mon/RawCamBehavior.cc 2007-06-26 00:27:44.000000000 -0400 @@ -36,8 +36,8 @@ RawCamBehavior::processEvent(const EventBase& e) { if(!wireless->isConnected(visRaw->sock)) return; - if(config->vision.rawcam_transport==0 && visRaw->getTransport()==SocketNS::SOCK_STREAM - || config->vision.rawcam_transport==1 && visRaw->getTransport()==SocketNS::SOCK_DGRAM) { + if(config->vision.rawcam.transport==0 && visRaw->getTransport()==Socket::SOCK_STREAM + || config->vision.rawcam.transport==1 && visRaw->getTransport()==Socket::SOCK_DGRAM) { //reset the socket closeServer(); setupServer(); @@ -49,15 +49,15 @@ CameraStreamBehavior::processEvent(e); return; } - if ((get_time() - lastProcessedTime) < config->vision.rawcam_interval) {// not enough time has gone by + if ((get_time() - lastProcessedTime) < config->vision.rawcam.interval) {// not enough time has gone by return; } /* // turning these off enables individual channel compression - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE && e.getGeneratorID()!=EventBase::visRawCameraEGID) + if(config->vision.rawcam.compression==Config::vision_config::COMPRESS_NONE && e.getGeneratorID()!=EventBase::visRawCameraEGID) return; - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_JPEG && e.getGeneratorID()!=EventBase::visJPEGEGID) + if(config->vision.rawcam.compression==Config::vision_config::COMPRESS_JPEG && e.getGeneratorID()!=EventBase::visJPEGEGID) return; */ - if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_COLOR) { + if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_COLOR) { if(!writeColor(*fbke)) { if(packet) { //packet was opened, need to close it cur=packet; // don't send anything @@ -66,7 +66,7 @@ //error message should already be printed in writeColor //ASSERTRET(false,"serialization failed"); } - } else if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) { + } else if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL) { if(!writeSingleChannel(*fbke)) { if(packet) { //packet was opened, need to close it cur=packet; // don't send anything @@ -76,7 +76,7 @@ //ASSERTRET(false,"serialization failed"); } } else { - serr->printf("%s: Bad rawcam_encoding setting\n",getName().c_str()); + serr->printf("%s: Bad rawcam.encoding setting\n",getName().c_str()); } } catch(...) { if(packet) { //packet was opened, need to close it @@ -91,26 +91,26 @@ } unsigned int RawCamBehavior::getSourceLayer(unsigned int chan, unsigned int numLayers) { - if(config->vision.rawcam_encoding==Config::vision_config::ENCODE_SINGLE_CHANNEL) { - if(config->vision.rawcam_channel!=(int)chan) + if(config->vision.rawcam.encoding==Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL) { + if(config->vision.rawcam.channel!=(int)chan) return -1U; - return numLayers-1-config->vision.rawcam_y_skip; + return numLayers-1-config->vision.rawcam.y_skip; } // must be full-color switch(chan) { case RawCameraGenerator::CHAN_Y: - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_JPEG) { - if(config->vision.rawcam_y_skip-config->vision.rawcam_uv_skip == 1) - return numLayers-1-config->vision.rawcam_uv_skip; + if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_JPEG) { + if(config->vision.rawcam.y_skip-config->vision.rawcam.uv_skip == 1) + return numLayers-1-config->vision.rawcam.uv_skip; } - return numLayers-1-config->vision.rawcam_y_skip; + return numLayers-1-config->vision.rawcam.y_skip; case RawCameraGenerator::CHAN_U: case RawCameraGenerator::CHAN_V: - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_JPEG) { - if(config->vision.rawcam_uv_skip-config->vision.rawcam_y_skip == 1) - return numLayers-1-config->vision.rawcam_y_skip; + if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_JPEG) { + if(config->vision.rawcam.uv_skip-config->vision.rawcam.y_skip == 1) + return numLayers-1-config->vision.rawcam.y_skip; } - return numLayers-1-config->vision.rawcam_uv_skip; + return numLayers-1-config->vision.rawcam.uv_skip; default: // other channels, i.e. Y-derivatives return -1U; } @@ -142,25 +142,25 @@ std::vector args; args.push_back("raw"); char port[50]; - snprintf(port,50,"%d",config->vision.rawcam_port); + snprintf(port,50,"%d",*config->vision.rawcam.port); args.push_back(port); - if(config->vision.rawcam_transport==0) { + if(config->vision.rawcam.transport==0) { max_buf=UDP_WIRELESS_BUFFER_SIZE; - visRaw=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf); + visRaw=wireless->socket(Socket::SOCK_DGRAM, 1024, max_buf); args.push_back("udp"); - } else if(config->vision.rawcam_transport==1) { + } else if(config->vision.rawcam.transport==1) { max_buf=TCP_WIRELESS_BUFFER_SIZE; - visRaw=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf); + visRaw=wireless->socket(Socket::SOCK_STREAM, 1024, max_buf); args.push_back("tcp"); } else { - serr->printf("ERROR: Invalid Config::vision.rawcam_transport: %d\n",config->vision.rawcam_transport); + serr->printf("ERROR: Invalid Config::vision.rawcam.transport: %d\n",*config->vision.rawcam.transport); return; } wireless->setDaemon(visRaw,true); wireless->setReceiver(visRaw,networkCallback); - wireless->listen(visRaw,config->vision.rawcam_port); + wireless->listen(visRaw,config->vision.rawcam.port); - Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RawVisionGUI",config->vision.rawcam_port,args); + Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RawVisionGUI",*config->vision.rawcam.port,args); } bool @@ -172,11 +172,13 @@ ASSERT(cur==NULL,"cur non-NULL"); cur=NULL; char * buf=packet=(char*)visRaw->getWriteBuffer(avail); - ASSERTRETVAL(packet!=NULL,"dropped frame, network bandwidth is saturated (reduce frame rate or size)",false); + ASSERT(packet!=NULL,"dropped frame, network bandwidth is saturated (reduce frame rate or size)"); + if(packet==NULL) + return false; if(!LoadSave::encodeInc("TekkotsuImage",buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; - if(!LoadSave::encodeInc(config->vision.rawcam_encoding,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; - if(!LoadSave::encodeInc(config->vision.rawcam_compression,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; + if(!LoadSave::encodeInc(*config->vision.rawcam.encoding,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; + if(!LoadSave::encodeInc(*config->vision.rawcam.compression,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; if(!LoadSave::encodeInc(fbkgen.getWidth(layer),buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; if(!LoadSave::encodeInc(fbkgen.getHeight(layer),buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; @@ -191,12 +193,12 @@ RawCamBehavior::writeColor(const FilterBankEvent& e) { FilterBankGenerator& fbkgen=*e.getSource(); - unsigned int y_layer=fbkgen.getNumLayers()-1-config->vision.rawcam_y_skip; - unsigned int uv_layer=fbkgen.getNumLayers()-1-config->vision.rawcam_uv_skip; + unsigned int y_layer=fbkgen.getNumLayers()-1-config->vision.rawcam.y_skip; + unsigned int uv_layer=fbkgen.getNumLayers()-1-config->vision.rawcam.uv_skip; - if(config->vision.rawcam_channel==-1) { - if(e.getGeneratorID()==EventBase::visRawCameraEGID && config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE - || e.getGeneratorID()==EventBase::visJPEGEGID && config->vision.rawcam_compression==Config::vision_config::COMPRESS_JPEG) { + if(config->vision.rawcam.channel==-1) { + if(e.getGeneratorID()==EventBase::visRawCameraEGID && config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_NONE + || e.getGeneratorID()==EventBase::visJPEGEGID && config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_JPEG) { if(const JPEGGenerator* jgen=dynamic_cast(&fbkgen)) if(jgen->getCurrentSourceFormat()==JPEGGenerator::SRC_COLOR) return true; @@ -212,10 +214,10 @@ if(!LoadSave::encodeInc("blank",cur,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_U); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_V); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; closePacket(); } @@ -229,7 +231,7 @@ small_layer=y_layer; } if(const JPEGGenerator* jgen=dynamic_cast(&fbkgen)) { - if(config->vision.rawcam_compression!=Config::vision_config::COMPRESS_JPEG) + if(config->vision.rawcam.compression!=Config::vision_config::RawCamConfig::COMPRESS_JPEG) return true; if(jgen->getCurrentSourceFormat()==JPEGGenerator::SRC_COLOR && big_layer-small_layer<2) { openPacket(fbkgen,e.getTimeStamp(),big_layer); @@ -237,7 +239,7 @@ return false; fbkgen.selectSaveImage(big_layer,0); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; closePacket(); } else if(jgen->getCurrentSourceFormat()==JPEGGenerator::SRC_GRAYSCALE && big_layer-small_layer>=2) { @@ -247,12 +249,12 @@ if(big_layer==y_layer) { fbkgen.selectSaveImage(y_layer,RawCameraGenerator::CHAN_Y); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; } else { fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_U); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_V); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; } if(!opened) @@ -261,25 +263,25 @@ } else { bool opened=false; - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE || big_layer-small_layer>=2 && big_layer==uv_layer) { + if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_NONE || big_layer-small_layer>=2 && big_layer==uv_layer) { opened=openPacket(fbkgen,e.getTimeStamp(),big_layer); if(cur==NULL) //error should have been displayed by openPacket return false; fbkgen.selectSaveImage(y_layer,RawCameraGenerator::CHAN_Y); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; } - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE || big_layer-small_layer>=2 && big_layer==y_layer) { + if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_NONE || big_layer-small_layer>=2 && big_layer==y_layer) { opened=openPacket(fbkgen,e.getTimeStamp(),big_layer); if(cur==NULL) //error should have been displayed by openPacket return false; fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_U); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; fbkgen.selectSaveImage(uv_layer,RawCameraGenerator::CHAN_V); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; } - if(config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE || !opened) + if(config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_NONE || !opened) closePacket(); } @@ -289,20 +291,20 @@ bool RawCamBehavior::writeSingleChannel(const FilterBankEvent& e) { FilterBankGenerator& fbkgen=*e.getSource(); - if( config->vision.rawcam_compression==Config::vision_config::COMPRESS_NONE && e.getGeneratorID()==EventBase::visRawCameraEGID - || config->vision.rawcam_compression==Config::vision_config::COMPRESS_JPEG && e.getGeneratorID()==EventBase::visJPEGEGID ) + if( config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_NONE && e.getGeneratorID()==EventBase::visRawCameraEGID + || config->vision.rawcam.compression==Config::vision_config::RawCamConfig::COMPRESS_JPEG && e.getGeneratorID()==EventBase::visJPEGEGID ) { if(const JPEGGenerator * jgen=dynamic_cast(&fbkgen)) if(jgen->getCurrentSourceFormat()!=JPEGGenerator::SRC_GRAYSCALE) return true; - unsigned int layer=fbkgen.getNumLayers()-1-config->vision.rawcam_y_skip; + unsigned int layer=fbkgen.getNumLayers()-1-config->vision.rawcam.y_skip; openPacket(fbkgen,e.getTimeStamp(),layer); if(cur==NULL) //error should have been displayed by openPacket return false; - fbkgen.selectSaveImage(layer,config->vision.rawcam_channel); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam_transport to TCP and reopen raw cam")) return false; + fbkgen.selectSaveImage(layer,config->vision.rawcam.channel); + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.rawcam.transport to TCP and reopen raw cam")) return false; closePacket(); } @@ -317,7 +319,7 @@ return; visRaw->write(cur-packet); /* cout << "used=" << (cur-packet) << "\tavail==" << avail; - if(state->robotDesign & WorldState::ERS7Mask) + if(RobotName == ERS7Info::TargetName) cout << "\tmax bandwidth=" << (cur-packet)/1024.f*30 << "KB/sec" << endl; else cout << "\tmax bandwidth=" << (cur-packet)/1024.f*24 << "KB/sec" << endl; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/RawCamBehavior.h ./Behaviors/Mon/RawCamBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/RawCamBehavior.h 2006-09-16 13:32:38.000000000 -0400 +++ ./Behaviors/Mon/RawCamBehavior.h 2007-06-07 14:24:42.000000000 -0400 @@ -20,8 +20,8 @@ * * I emphasize: beginning of each Vision packet, before the FilterBankGenerator header. * - <@c string:"TekkotsuImage"> - * - <Config::vision_config::encoding_t: rawcam_encoding> (expect single or multiple channels, 0 means color (3 channels), 1 means intensity (1 channel)) - * - <Config::vision_config::compression_t: rawcam_compression> (0==none, 1==jpeg, 2==rle) + * - <Config::vision_config::encoding_t: rawcam.encoding> (expect single or multiple channels, 0 means color (3 channels), 1 means intensity (1 channel)) + * - <Config::vision_config::compression_t: rawcam.compression> (0==none, 1==jpeg, 2==rle) * - <@c unsigned @c int: width> (this is the width of the largest channel - note different channels can be sent at different resolutions! Provides cheap "compression" of chromaticity channels) * - <@c unsigned @c int: height> (similarly, height of largest channel) * - <@c unsigned @c int: timestamp> (time image was taken, milliseconds since boot) @@ -46,7 +46,11 @@ //! destructor ~RawCamBehavior() { theOne=NULL; } +#ifdef PLATFORM_APERIOS static const unsigned int TCP_WIRELESS_BUFFER_SIZE=200000; //!< 200000 bytes for use up to 416x320 + 2*208x160 (double res Y, full res UV on ERS-7) +#else + static const unsigned int TCP_WIRELESS_BUFFER_SIZE=901*1024; //!< 900KB for max of full-color 640x480 + 1KB for header +#endif static const unsigned int UDP_WIRELESS_BUFFER_SIZE=64*1024; //!< 64KB is the max udp packet size virtual void DoStart(); @@ -57,7 +61,7 @@ static std::string getClassDescription() { char tmp[20]; - snprintf(tmp,20,"%d",config->vision.rawcam_port); tmp[19]='\0'; + snprintf(tmp,20,"%d",*config->vision.rawcam.port); tmp[19]='\0'; return std::string("Forwards images from camera over port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/RegionCamBehavior.cc ./Behaviors/Mon/RegionCamBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/RegionCamBehavior.cc 2006-09-09 00:32:29.000000000 -0400 +++ ./Behaviors/Mon/RegionCamBehavior.cc 2007-05-21 16:51:20.000000000 -0400 @@ -30,8 +30,8 @@ RegionCamBehavior::processEvent(const EventBase& e) { if(!wireless->isConnected(visRegion->sock)) return; - if(config->vision.region_transport==0 && visRegion->getTransport()==SocketNS::SOCK_STREAM - || config->vision.region_transport==1 && visRegion->getTransport()==SocketNS::SOCK_DGRAM) { + if(config->vision.regioncam.transport==0 && visRegion->getTransport()==Socket::SOCK_STREAM + || config->vision.regioncam.transport==1 && visRegion->getTransport()==Socket::SOCK_DGRAM) { closeServer(); setupServer(); return; @@ -61,23 +61,23 @@ std::vector args; args.push_back("reg"); char port[50]; - snprintf(port,50,"%d",config->vision.region_port); + snprintf(port,50,"%d",*config->vision.regioncam.port); args.push_back(port); - if(config->vision.region_transport==0) { + if(config->vision.regioncam.transport==0) { max_buf=UDP_WIRELESS_BUFFER_SIZE; - visRegion=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf); + visRegion=wireless->socket(Socket::SOCK_DGRAM, 1024, max_buf); args.push_back("udp"); - } else if(config->vision.region_transport==1) { + } else if(config->vision.regioncam.transport==1) { max_buf=TCP_WIRELESS_BUFFER_SIZE; - visRegion=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf); + visRegion=wireless->socket(Socket::SOCK_STREAM, 1024, max_buf); wireless->setDaemon(visRegion,true); args.push_back("tcp"); } else { - serr->printf("ERROR: Invalid Config::vision.region_transport: %d\n",config->vision.region_transport); + serr->printf("ERROR: Invalid Config::vision.region_transport: %d\n",*config->vision.regioncam.transport); return; } - wireless->listen(visRegion,config->vision.region_port); - Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RegionVisionGUI",config->vision.region_port,args); + wireless->listen(visRegion,config->vision.regioncam.port); + Controller::loadGUI("org.tekkotsu.mon.VisionGUI","RegionVisionGUI",config->vision.regioncam.port,args); } bool @@ -89,11 +89,13 @@ ASSERT(cur==NULL,"cur non-NULL"); cur=NULL; char * buf=packet=(char*)visRegion->getWriteBuffer(avail); - ASSERTRETVAL(packet!=NULL,"could not get buffer",false); + ASSERT(packet!=NULL,"could not get buffer"); + if(packet==NULL) + return false; if(!LoadSave::encodeInc("TekkotsuImage",buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; - if(!LoadSave::encodeInc(Config::vision_config::ENCODE_SINGLE_CHANNEL,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; - if(!LoadSave::encodeInc(Config::vision_config::COMPRESS_RLE,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; + if(!LoadSave::encodeInc(Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; + if(!LoadSave::encodeInc(Config::vision_config::SegCamConfig::COMPRESS_RLE,buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; if(!LoadSave::encodeInc(fbkgen.getWidth(layer),buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; if(!LoadSave::encodeInc(fbkgen.getHeight(layer),buf,avail,"ran out of space %s:%un",__FILE__,__LINE__)) return false;; @@ -108,14 +110,14 @@ RegionCamBehavior::writeRegions(const FilterBankEvent& e) { FilterBankGenerator& fbkgen=*e.getSource(); - unsigned int layer=fbkgen.getNumLayers()-1-config->vision.regioncam_skip; + unsigned int layer=fbkgen.getNumLayers()-1-config->vision.regioncam.skip; openPacket(fbkgen,e.getTimeStamp(),layer); ASSERTRETVAL(cur!=NULL,"header failed",false); RegionGenerator * regGen = dynamic_cast(&fbkgen); ASSERTRETVAL(regGen!=NULL,"fbkgen isn't an RegionGenerator",false); - regGen->selectSaveImage(layer,config->vision.segcam_channel); + regGen->selectSaveImage(layer,config->vision.segcam.channel); if(!LoadSave::checkInc(regGen->saveBuffer(cur,avail),cur,avail,"save region image failed")) return false; const SegmentedColorGenerator * seg = dynamic_cast((regGen->getSourceGenerator())->getSourceGenerator()); //Get the source of his source (the SegmentedColorGenerator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/RegionCamBehavior.h ./Behaviors/Mon/RegionCamBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/RegionCamBehavior.h 2006-09-16 13:32:38.000000000 -0400 +++ ./Behaviors/Mon/RegionCamBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -27,7 +27,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->vision.segcam_port); + sprintf(tmp,"%d",*config->vision.segcam.port); return std::string("Forwards regions calculated out of images from camera over port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/RoverControllerBehavior.cc ./Behaviors/Mon/RoverControllerBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/RoverControllerBehavior.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Mon/RoverControllerBehavior.cc 2007-11-18 01:47:01.000000000 -0500 @@ -0,0 +1,208 @@ +#include "Shared/RobotInfo.h" +#if ( defined(TGT_HAS_ARMS) || defined(TGT_HAS_LEGS) ) && defined(TGT_HAS_HEAD) + +#include "RoverControllerBehavior.h" + +#include "Motion/MMAccessor.h" +#include + +using namespace std; + +void RoverControllerBehavior::DoStart() { + BehaviorBase::DoStart(); // do this first (required) + // open server socket + cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 2048); + wireless->setReceiver(cmdsock, callback); + wireless->setDaemon(cmdsock,true); + wireless->listen(cmdsock, PORT); + // Open the gui on the desktop + Controller::loadGUI("org.tekkotsu.mon.RoverGUI","RoverGUI",PORT); + // set up motion commands + head = motman->addPersistentMotion(SharedObject()); + arm = motman->addPersistentMotion(SharedObject()); +} + +void RoverControllerBehavior::DoStop() { + // remove motion commands + motman->removeMotion(head); + head=MotionManager::invalid_MC_ID; + motman->removeMotion(arm); + arm=MotionManager::invalid_MC_ID; + // Close the GUI + Controller::closeGUI("RoverGUI"); + // close server socket + wireless->setDaemon(cmdsock,false); + wireless->close(cmdsock); + BehaviorBase::DoStop(); // do this last (required) +} + +void RoverControllerBehavior::initScale() { + PostureEngine e; + unsigned int gripperFrame=-1U, armBaseFrame=-1U; +#ifdef TGT_HAS_ARMS + gripperFrame=ArmOffset+NumArmJoints-1; + armBaseFrame=ArmOffset; +#elif defined(TGT_HAS_LEGS) + gripperFrame=PawFrameOffset; + armBaseFrame=LFrLegOffset; +#else + // RoverControllerBehavior can't find manipulator, won't run + // (user should've seen the compiler warning when including the header...) + return; +#endif + + // find something resembling range of motion + const float BIGNUM=1000000; + e.solveLinkPosition(BIGNUM,0,0, gripperFrame, 0,0,0); + NEWMAT::ColumnVector x = e.jointToBase(gripperFrame).SubMatrix(1,4,4,4); + float max=ceil(x(1)/x(4)); + x = e.jointToBase(armBaseFrame).SubMatrix(1,4,4,4); + tgtXOff=x(1)/x(4); + tgtScale=(max-tgtXOff)/2; + tgtXOff+=tgtScale; + x = e.jointToBase(armBaseFrame+1).SubMatrix(1,4,4,4); + tgtYOff=x(2)/x(4); + std::cout << "Gripper XY reach (-1 to 1): " << tgtXOff-tgtScale << " to " << tgtXOff+tgtScale << std::endl; + std::cout << "Gripper XY center: (" << tgtXOff << ',' << tgtYOff <<')' << std::endl; + +#ifdef TGT_HAS_ARMS + // arm just goes up + e.solveLinkPosition(0,0,BIGNUM, gripperFrame, 0,0,0); + x = e.jointToBase(gripperFrame).SubMatrix(1,4,4,4); + max=ceil(x(3)/x(4)); + x = e.jointToBase(armBaseFrame).SubMatrix(1,4,4,4); + heightOff=x(3)/x(4); + heightScale=max-heightOff; +#elif defined(TGT_HAS_LEGS) + // legs start at bottom + e.solveLinkPosition(0,0,-BIGNUM, gripperFrame, 0,0,0); + x = e.jointToBase(gripperFrame).SubMatrix(1,4,4,4); + heightOff=floor(x(3)/x(4)); + x = e.jointToBase(armBaseFrame).SubMatrix(1,4,4,4); + heightScale=(x(3)/x(4)-heightOff)*2; +#endif + std::cout << "Gripper Z reach (0 to 1):" << heightOff << " to " << heightOff+heightScale << std::endl; + + e.solveLinkPosition(0,0,-BIGNUM, gripperFrame, 0,0,0); + e.solveLinkPosition(0,0,BIGNUM, CameraFrameOffset, 0,0,0); + float ydist=e.jointToJoint(gripperFrame,CameraFrameOffset).SubMatrix(1,3,4,4).NormFrobenius(); + e.solveLinkPosition(BIGNUM,0,0, gripperFrame, 0,0,0); + e.solveLinkPosition(-BIGNUM,0,0, CameraFrameOffset, 0,0,0); + float xdist=e.jointToJoint(gripperFrame,CameraFrameOffset).SubMatrix(1,3,4,4).NormFrobenius(); + distanceScale = ceil(xdist>ydist ? xdist : ydist); + std::cout << "Max camera distance is " << distanceScale << std::endl; +} + +int RoverControllerBehavior::update(char *buf, int bytes) { + stringstream cmd(string(buf,bytes)); + + bool armDirty=false, headDirty=false; + + while(cmd) { + string t; + cmd >> t; + bool gotArm=false, gotHead=false; + if(gotHead=(t=="autoPerspective")) + cmd >> autoPerspective; + else if(gotArm=(t=="autoAngle")) + cmd >> autoGripperAngle; + else if(gotHead=(t=="autoTrack")) + cmd >> autoTrackGripper; + else if(gotHead=(t=="maxDist")) + cmd >> maxDist; + + else if(t=="gripper") { + float v; + cmd >> v; + unsigned int idx=-1U; +#ifdef TGT_HAS_ARMS + idx=ArmOffset+JointsPerArm-1; +#elif defined(TGT_HAS_MOUTH) + if(NumMouthJoints>0) + idx=MouthOffset; +#endif + if(idx!=-1U) { + float range = outputRanges[idx][MaxRange] - outputRanges[idx][MinRange]; + v = v*range + outputRanges[idx][MinRange]; + MMAccessor(arm)->setOutputCmd(idx,v); + } + } + else if(gotArm=(t=="gripperAngle")) + cmd >> gripperAngle; + else if(gotHead=(t=="perspective")) + cmd >> perspective; + else if(gotArm=(t=="gripperHeight")) { + cmd >> tgtZ; + tgtZ*=heightScale; + tgtZ+=heightOff; + } + else if(gotHead=(t=="cameraDistance")) { + cmd >> lookD; + lookD*=distanceScale; + } + + else if(gotArm=(t=="tgt")) { + cmd >> tgtY >> tgtX; + tgtY=-tgtY; + tgtX*=tgtScale; + tgtX+=tgtXOff; + tgtY*=tgtScale; + tgtY+=tgtYOff; + } + else if(gotHead=(t=="look")) { + cmd >> lookY >> lookX; + lookY=-lookY; + lookX*=tgtScale; + lookX+=tgtXOff; + lookY*=tgtScale; + lookY+=tgtYOff; + } + + armDirty = armDirty || gotArm; + headDirty = headDirty || gotHead; + } + if(autoTrackGripper) { + lookX=tgtX; + lookY=tgtY; + headDirty = headDirty || armDirty; + } + + if(armDirty) + updateArm(); + + if(headDirty) + updateHead(); + + return 0; +} + +RoverControllerBehavior * RoverControllerBehavior::theOne=NULL; + +void RoverControllerBehavior::updateArm() { +#ifdef TGT_HAS_ARMS + MMAccessor(arm)->solveLinkPosition(tgtX,tgtY,tgtZ,ArmOffset+NumArmJoints-1,0,0,0); +#elif defined(TGT_HAS_LEGS) + MMAccessor(arm)->solveLinkPosition(tgtX,tgtY,tgtZ,PawFrameOffset,0,0,0); +#endif +} + +void RoverControllerBehavior::updateHead() { + if(maxDist) + MMAccessor(head)->lookAtPoint(lookX,lookY,tgtZ); + else + MMAccessor(head)->lookAtPoint(lookX,lookY,tgtZ,lookD); +} + + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.5 $ + * $State: Exp $ + * $Date: 2007/11/18 06:47:01 $ + */ + +#endif // check for (arms or hands) and legs diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/RoverControllerBehavior.h ./Behaviors/Mon/RoverControllerBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/RoverControllerBehavior.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Mon/RoverControllerBehavior.h 2007-11-13 11:41:14.000000000 -0500 @@ -0,0 +1,116 @@ +//-*-c++-*- +#ifndef INCLUDED_RoverControllerBehavior_h_ +#define INCLUDED_RoverControllerBehavior_h_ + +#include "Shared/RobotInfo.h" +#if !defined(TGT_HAS_ARMS) && !defined(TGT_HAS_LEGS) || !defined(TGT_HAS_HEAD) +// no manipulator, but we can still compile, so it's only a warning +# warning RoverControllerBehavior can't find a manipulator, won't run +#endif + +#include "Behaviors/BehaviorBase.h" +#include "Behaviors/Controller.h" +#include "Events/EventRouter.h" +#include "Motion/PostureMC.h" +#include "Motion/HeadPointerMC.h" + +//! DESCRIPTION +class RoverControllerBehavior : public BehaviorBase { +public: + static const int PORT=10056; //!< port number to open up + + //! returns #theOne, initializing it if necessary + static RoverControllerBehavior& getInstance() { + if(theOne==NULL) + theOne = new RoverControllerBehavior; + return *theOne; + } + + //! destructor + virtual ~RoverControllerBehavior() { + if(isActive()) + DoStop(); + theOne=NULL; + } + + virtual void DoStart(); + virtual void DoStop(); + + static std::string getClassDescription() { return "DESCRIPTION"; } + virtual std::string getDescription() const { return getClassDescription(); } + + +protected: + //! constructor + RoverControllerBehavior() + : BehaviorBase("Rover Remote Control"), + tgtScale(1), tgtXOff(0), tgtYOff(0), heightScale(1), heightOff(0), distanceScale(1), + tgtX(0),tgtY(0),tgtZ(0), lookX(0),lookY(0),lookD(0), + gripperAngle(0),perspective(0), + autoGripperAngle(true),autoPerspective(true),autoTrackGripper(true),maxDist(true), + cmdsock(NULL), head(MotionManager::invalid_MC_ID), arm(MotionManager::invalid_MC_ID) + { + initScale(); + } + + void initScale(); + + //! called by wireless when there's new data, forwards call to theOne->update + static int callback(char *buf, int bytes) { return theOne->update(buf,bytes); } + //! called by wireless (via callback()) when there's new data + int update(char *buf, int bytes); + + void updateArm(); + void updateHead(); + + static RoverControllerBehavior * theOne; + + float tgtScale; + float tgtXOff; + float tgtYOff; + float heightScale; + float heightOff; + float distanceScale; + + float tgtX; + float tgtY; + float tgtZ; + float lookX; + float lookY; + float lookD; + + float gripperAngle; + float perspective; + + bool autoGripperAngle; + bool autoPerspective; + bool autoTrackGripper; + bool maxDist; + + Socket *cmdsock; //!< The input command stream socket + + MotionManager::MC_ID head; + MotionManager::MC_ID arm; + +private: + // Providing declarations for these functions will avoid a compiler warning if + // you have any class members which are pointers. However, as it is, an error + // will result if you inadvertantly cause a call to either (which is probably + // a good thing, unless you really intended to copy/assign a behavior, in + // which case simply provide implementations for the functions) + RoverControllerBehavior(const RoverControllerBehavior&); //!< don't call (copy constructor) + RoverControllerBehavior& operator=(const RoverControllerBehavior&); //!< don't call (assignment operator) +}; + +/*! @file + * @brief Defines RoverControllerBehavior, which DESCRIPTION + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.4 $ + * $State: Exp $ + * $Date: 2007/11/13 16:41:14 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/SegCamBehavior.cc ./Behaviors/Mon/SegCamBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/SegCamBehavior.cc 2006-09-14 14:57:03.000000000 -0400 +++ ./Behaviors/Mon/SegCamBehavior.cc 2007-05-21 16:51:20.000000000 -0400 @@ -35,8 +35,8 @@ SegCamBehavior::processEvent(const EventBase& e) { if(!wireless->isConnected(visRLE->sock)) return; - if(config->vision.segcam_transport==0 && visRLE->getTransport()==SocketNS::SOCK_STREAM - || config->vision.segcam_transport==1 && visRLE->getTransport()==SocketNS::SOCK_DGRAM) { + if(config->vision.segcam.transport==0 && visRLE->getTransport()==Socket::SOCK_STREAM + || config->vision.segcam.transport==1 && visRLE->getTransport()==Socket::SOCK_DGRAM) { closeServer(); setupServer(); return; @@ -47,9 +47,9 @@ CameraStreamBehavior::processEvent(e); return; } - if ((get_time() - lastProcessedTime) < config->vision.segcam_interval) // not enough time has gone by + if ((get_time() - lastProcessedTime) < config->vision.segcam.interval) // not enough time has gone by return; - if(config->vision.segcam_compression==Config::vision_config::COMPRESS_NONE && e.getGeneratorID()==EventBase::visSegmentEGID) { + if(config->vision.segcam.compression==Config::vision_config::SegCamConfig::COMPRESS_NONE && e.getGeneratorID()==EventBase::visSegmentEGID) { if(!writeSeg(*fbke)) { if(packet!=NULL) { cur=packet; @@ -59,7 +59,7 @@ //ASSERTRET(succ,"serialization failed"); } } - if(config->vision.segcam_compression==Config::vision_config::COMPRESS_RLE && e.getGeneratorID()==EventBase::visRLEEGID) { + if(config->vision.segcam.compression==Config::vision_config::SegCamConfig::COMPRESS_RLE && e.getGeneratorID()==EventBase::visRLEEGID) { if(!writeRLE(*fbke)) { if(packet!=NULL) { cur=packet; @@ -98,25 +98,25 @@ std::vector args; args.push_back("rle"); char port[50]; - snprintf(port,50,"%d",config->vision.segcam_port); + snprintf(port,50,"%d",*config->vision.segcam.port); args.push_back(port); - if(config->vision.segcam_transport==0) { + if(config->vision.segcam.transport==0) { max_buf=UDP_WIRELESS_BUFFER_SIZE; - visRLE=wireless->socket(SocketNS::SOCK_DGRAM, 1024, max_buf); + visRLE=wireless->socket(Socket::SOCK_DGRAM, 1024, max_buf); args.push_back("udp"); - } else if(config->vision.segcam_transport==1) { + } else if(config->vision.segcam.transport==1) { max_buf=TCP_WIRELESS_BUFFER_SIZE; - visRLE=wireless->socket(SocketNS::SOCK_STREAM, 1024, max_buf); + visRLE=wireless->socket(Socket::SOCK_STREAM, 1024, max_buf); args.push_back("tcp"); } else { - serr->printf("ERROR: Invalid Config::vision.segcam_transport: %d\n",config->vision.segcam_transport); + serr->printf("ERROR: Invalid Config::vision.segcam.transport: %d\n",*config->vision.segcam.transport); return; } wireless->setDaemon(visRLE,true); wireless->setReceiver(visRLE,networkCallback); - wireless->listen(visRLE,config->vision.segcam_port); + wireless->listen(visRLE,config->vision.segcam.port); - Controller::loadGUI("org.tekkotsu.mon.VisionGUI","SegVisionGUI",config->vision.segcam_port,args); + Controller::loadGUI("org.tekkotsu.mon.VisionGUI","SegVisionGUI",config->vision.segcam.port,args); } bool @@ -128,11 +128,13 @@ ASSERT(cur==NULL,"cur non-NULL"); cur=NULL; char * buf=packet=(char*)visRLE->getWriteBuffer(avail); - ASSERTRETVAL(packet!=NULL,"dropped frame, network bandwidth is saturated (reduce frame rate or size)",false); + ASSERT(packet!=NULL,"dropped frame, network bandwidth is saturated (reduce frame rate or size)"); + if(packet==NULL) + return false; if(!LoadSave::encodeInc("TekkotsuImage",buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; - if(!LoadSave::encodeInc(Config::vision_config::ENCODE_SINGLE_CHANNEL,buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; - if(!LoadSave::encodeInc(Config::vision_config::COMPRESS_RLE,buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; + if(!LoadSave::encodeInc(Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL,buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; + if(!LoadSave::encodeInc(Config::vision_config::SegCamConfig::COMPRESS_RLE,buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; if(!LoadSave::encodeInc(fbkgen.getWidth(layer),buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; if(!LoadSave::encodeInc(fbkgen.getHeight(layer),buf,avail,"ran out of space %s:%u\n",__FILE__,__LINE__)) return false;; @@ -147,7 +149,7 @@ SegCamBehavior::writeRLE(const FilterBankEvent& e) { FilterBankGenerator& fbkgen=*e.getSource(); - unsigned int layer=fbkgen.getNumLayers()-1-config->vision.segcam_skip; + unsigned int layer=fbkgen.getNumLayers()-1-config->vision.segcam.skip; openPacket(fbkgen,e.getTimeStamp(),layer); if(cur==NULL) //error should have been displayed by openPacket return false; @@ -155,8 +157,8 @@ RLEGenerator * rle = dynamic_cast(&fbkgen); ASSERTRETVAL(rle!=NULL,"fbkgen isn't an RLEGenerator",false); - rle->selectSaveImage(layer,config->vision.segcam_channel); - if(!LoadSave::checkInc(rle->saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.segcam_transport to TCP and reopen seg cam")) return false; + rle->selectSaveImage(layer,config->vision.segcam.channel); + if(!LoadSave::checkInc(rle->saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.segcam.transport to TCP and reopen seg cam")) return false; // send out the color map ourselves (since RLE compression doesn't have a concept of color) const SegmentedColorGenerator * seg = dynamic_cast(rle->getSourceGenerator()); @@ -172,13 +174,13 @@ SegCamBehavior::writeSeg(const FilterBankEvent& e) { FilterBankGenerator& fbkgen=*e.getSource(); - unsigned int layer=fbkgen.getNumLayers()-1-config->vision.segcam_skip; + unsigned int layer=fbkgen.getNumLayers()-1-config->vision.segcam.skip; openPacket(fbkgen,e.getTimeStamp(),layer); if(cur==NULL) //error should have been displayed by openPacket return false; - fbkgen.selectSaveImage(layer,config->vision.segcam_channel); - if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.segcam_transport to TCP and reopen seg cam")) return false; + fbkgen.selectSaveImage(layer,config->vision.segcam.channel); + if(!LoadSave::checkInc(fbkgen.saveBuffer(cur,avail),cur,avail,"image size too large -- may need to set Config::vision.segcam.transport to TCP and reopen seg cam")) return false; closePacket(); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/SegCamBehavior.h ./Behaviors/Mon/SegCamBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/SegCamBehavior.h 2006-09-16 16:11:50.000000000 -0400 +++ ./Behaviors/Mon/SegCamBehavior.h 2007-05-01 17:21:07.000000000 -0400 @@ -63,7 +63,11 @@ //! destructor ~SegCamBehavior() { theOne=NULL; } +#if defined(TGT_ERS210) || defined(TGT_ERS220) || defined(TGT_ERS2xx) || defined(TGT_ERS7) static const unsigned int TCP_WIRELESS_BUFFER_SIZE=85000; //!< 85000 bytes for use up to 416x320 pixels / 8 min expected runs * 5 bytes per run + some padding +#else + static const unsigned int TCP_WIRELESS_BUFFER_SIZE=301*1024; //!< 300KB for use up to 640x480 pixels / 8 min expected runs * 5 bytes per run + some padding +#endif static const unsigned int UDP_WIRELESS_BUFFER_SIZE=64*1024; //!< 64KB is the max udp packet size virtual void DoStart(); @@ -74,7 +78,7 @@ static std::string getClassDescription() { char tmp[20]; - snprintf(tmp,20,"%d",config->vision.segcam_port); tmp[19]='\0'; + snprintf(tmp,20,"%d",*config->vision.segcam.port); tmp[19]='\0'; return std::string("Forwards segmented images from camera over port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/SpeakerServer.cc ./Behaviors/Mon/SpeakerServer.cc --- ../Tekkotsu_3.0/Behaviors/Mon/SpeakerServer.cc 2006-09-18 14:08:07.000000000 -0400 +++ ./Behaviors/Mon/SpeakerServer.cc 2007-11-21 15:57:13.000000000 -0500 @@ -7,11 +7,11 @@ SpeakerServer* SpeakerServer::instance = 0; -SpeakerServer* SpeakerServer::GetInstance() { +SpeakerServer& SpeakerServer::getInstance() { if (instance == 0) { instance = new SpeakerServer(); } - return instance; + return *instance; } SpeakerServer::SpeakerServer() @@ -45,7 +45,7 @@ channel = SoundManager::invalid_Play_ID; socket = - wireless->socket(SocketNS::SOCK_STREAM, RECEIVE_BUFFER_SIZE + 8, 512); + wireless->socket(Socket::SOCK_STREAM, RECEIVE_BUFFER_SIZE + 8, 512); wireless->setReceiver(socket->sock, socket_callback); wireless->setDaemon(socket, true); wireless->listen(socket->sock, config->sound.streaming.speaker_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/SpeakerServer.h ./Behaviors/Mon/SpeakerServer.h --- ../Tekkotsu_3.0/Behaviors/Mon/SpeakerServer.h 2006-09-16 16:11:50.000000000 -0400 +++ ./Behaviors/Mon/SpeakerServer.h 2007-11-21 15:57:13.000000000 -0500 @@ -8,7 +8,7 @@ //! Plays streamed audio via the speaker class SpeakerServer : public BehaviorBase { public: - static SpeakerServer* GetInstance(); //!< returns global #instance + static SpeakerServer& getInstance(); //!< returns global #instance virtual ~SpeakerServer(); //!< destructor virtual void DoStart(); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/SpiderMachineBehavior.cc ./Behaviors/Mon/SpiderMachineBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/SpiderMachineBehavior.cc 2006-02-21 00:27:13.000000000 -0500 +++ ./Behaviors/Mon/SpiderMachineBehavior.cc 1969-12-31 19:00:00.000000000 -0500 @@ -1,239 +0,0 @@ -#include "SpiderMachineBehavior.h" -#include "Events/EventRouter.h" -#include "Behaviors/StateNode.h" -#include "Wireless/Wireless.h" - -SpiderMachineBehavior * SpiderMachineBehavior::theOne=NULL; -unsigned int SpiderMachineBehavior::port=10081; - -void SpiderMachineBehavior::DoStart() { - BehaviorBase::DoStart(); // do this first - theOne=this; - // Turn on wireless - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 1024, 1024*10); - wireless->setDaemon(cmdsock,true); - wireless->setReceiver(cmdsock->sock, callback); - wireless->listen(cmdsock->sock, port); - erouter->addListener(this,EventBase::stateMachineEGID); - erouter->addListener(this,EventBase::stateTransitionEGID); -} - -void SpiderMachineBehavior::DoStop() { - erouter->removeListener(this); - expected.clear(); - while(!queuedEvents.empty()) - queuedEvents.pop(); - // Close socket; turn wireless off - wireless->setDaemon(cmdsock,false); - wireless->close(cmdsock); - if(theOne==this) - theOne=NULL; - BehaviorBase::DoStop(); // do this last -} - -void SpiderMachineBehavior::processEvent(const EventBase& e) { - if(!wireless->isConnected(cmdsock->sock) || listen.size()==0) - return; - - if(e.getGeneratorID()==EventBase::stateTransitionEGID) { - bool care=false; - const Transition * trans = reinterpret_cast(e.getSourceID()); - const std::vector& incoming=trans->getSources(); - const std::vector& outgoing=trans->getDestinations(); - for(std::vector::const_iterator it=incoming.begin(); it!=incoming.end() && !care; it++) - care=isListening(*it); - for(std::vector::const_iterator it=outgoing.begin(); it!=outgoing.end() && !care; it++) - care=isListening(*it); - if(!care) - return; - - if(expected.size()!=0) { - queuedEvents.push(e); - } else { - cmdsock->printf("\n"); - indent(1); - cmdsock->printf("\n",trans->getName().c_str(),e.getTimeStamp()); - expected.insert(incoming.begin(),incoming.end()); - expected.insert(outgoing.begin(),outgoing.end()); - while(queuedEvents.size()>0) { - EventBase qe=queuedEvents.front(); - queuedEvents.pop(); - processEvent(qe); - } - } - - } else if(e.getGeneratorID()==EventBase::stateMachineEGID) { - if(e.getTypeID()==EventBase::statusETID) - return; - const StateNode * beh=reinterpret_cast(e.getSourceID()); - expected_t::iterator it=expected.find(beh); - char * format; - if(isListening(beh)) { - if(it==expected.end()) { //if not found - if(queuedEvents.size()==0) - format="\n"; // unexpected - else { - queuedEvents.push(e); - return; - } - } else - format=" \n"; // expected as part of transition - if(e.getTypeID()==EventBase::activateETID) - cmdsock->printf(format,"start",beh->getName().c_str(),e.getTimeStamp()); - else if(e.getTypeID()==EventBase::deactivateETID) - cmdsock->printf(format,"stop",beh->getName().c_str(),e.getTimeStamp()); - else - serr->printf("WARNING: Unrecognized TypeID %d\n",e.getTypeID()); - } - if(it!=expected.end()) { //was found - expected.erase(it); - if(expected.size()==0) { - cmdsock->printf("\n"); - while(queuedEvents.size()>0) { - EventBase qe=queuedEvents.front(); - queuedEvents.pop(); - processEvent(qe); - } - } - } - - } else { - serr->printf("WARNING: Unknown event %s (%s)\n",e.getName().c_str(),e.getDescription().c_str()); - } -} - -void SpiderMachineBehavior::spider(const StateNode* n, unsigned int depth/*=0*/) { - if(n==NULL) - return; - - const std::vector& subnodes=n->getNodes(); - if(subnodes.size()==0) { - // it's a leaf node, no subnodes or transitions between them - indent(depth); - cmdsock->printf("\n", n->getClassName().c_str(), n->getName().c_str()); - } else { - - // first output current node's info - indent(depth); - cmdsock->printf("\n", n->getClassName().c_str(), n->getName().c_str()); - - std::set transitions; - // now recurse on sub-nodes, extracting all of the subnodes transitions - for(unsigned int i=0; i& curt=subnodes[i]->getTransitions(); - transitions.insert(curt.begin(),curt.end()); - } - - // now output transitions between subnodes we collected in previous step - for(std::set::const_iterator it=transitions.begin(); it!=transitions.end(); it++) { - indent(depth+1); - cmdsock->printf("\n", (*it)->getClassName().c_str(), (*it)->getName().c_str()); - const std::vector& incoming=(*it)->getSources(); - for(unsigned int i=0; iprintf("%s\n",incoming[i]->getName().c_str()); - } - const std::vector& outgoing=(*it)->getDestinations(); - for(unsigned int i=0; iprintf("%s\n",outgoing[i]->getName().c_str()); - } - indent(depth+1); - cmdsock->printf("\n"); - } - - indent(depth); - cmdsock->printf("\n"); - } -} - -bool SpiderMachineBehavior::isListening(const StateNode* n) { - while(n!=NULL) { - if(listen.find(n->getName())!=listen.end()) - return true; - n=n->getParent(); - } - return false; -} - -void SpiderMachineBehavior::indent(unsigned int level) { - for(unsigned int i=0; iprintf(" "); -} - -const StateNode * SpiderMachineBehavior::find(const std::string& name) { - for(registry_t::const_iterator it=getRegistry().begin(); it!=getRegistry().end(); it++) { - const StateNode * cur=dynamic_cast(*it); - if(cur!=NULL && cur->getName()==name) - return cur; - } - //serr->printf("WARNING: SpiderMachineBehavior Could not find StateNode named `%s'\n",name.c_str()); - return NULL; -} - -void SpiderMachineBehavior::runCommand(const std::string& s) { - if(s==std::string("list")) { - unsigned int numstate=0; - for(registry_t::const_iterator it=getRegistry().begin(); it!=getRegistry().end(); it++) { - const StateNode * cur=dynamic_cast(*it); - if(cur!=NULL) - numstate++; - } - cmdsock->printf("%d\n",numstate); - for(registry_t::const_iterator it=getRegistry().begin(); it!=getRegistry().end(); it++) { - const StateNode * cur=dynamic_cast(*it); - if(cur!=NULL) - cmdsock->printf("%s\n",cur->getName().c_str()); - } - - } else if(s.find("spider ")==0) { - const StateNode * n=find(s.substr(7)); - if(n==NULL) { - serr->printf("WARNING: SpiderMachineBehavior could not find \"%s\" for spidering\n",s.substr(7).c_str()); - cmdsock->printf("\n"); - } else { - cmdsock->printf("\n"); - spider(n); - cmdsock->printf("\n"); - } - - } else if(s.find("listen ")==0) { - listen.insert(s.substr(7)); - - } else if(s.find("ignore ")==0) { - listen.erase(s.substr(7)); - - } else if(s=="clear") { - listen.clear(); - - } else { - serr->printf("SpiderMachineBehavior::runCommand() - bad message: '%s'\n",s.c_str()); - } -} - -// The command packet reassembly mechanism -int SpiderMachineBehavior::callback(char *buf, int bytes) { - if(SpiderMachineBehavior::theOne==NULL) - return 0; - static std::string cmd; - for(int i=0; irunCommand(cmd); - cmd.clear(); - } else if(buf[i]!='\r') - cmd+=buf[i]; - } - return 0; -} - -/*! @file - * @brief Implements SpiderMachineBehavior, which when active, active and connected over network socket, outputs structure of requested state machine(s) - * @author ejt (Creator) - * - * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.5 $ - * $State: Exp $ - * $Date: 2006/02/21 05:27:13 $ - */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/SpiderMachineBehavior.h ./Behaviors/Mon/SpiderMachineBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/SpiderMachineBehavior.h 2005-08-07 00:11:03.000000000 -0400 +++ ./Behaviors/Mon/SpiderMachineBehavior.h 1969-12-31 19:00:00.000000000 -0500 @@ -1,136 +0,0 @@ -//-*-c++-*- -#ifndef INCLUDED_SpiderMachineBehavior_h_ -#define INCLUDED_SpiderMachineBehavior_h_ - -#include "Behaviors/BehaviorBase.h" -#include - -class StateNode; - -//! When active and connected over network socket, outputs structure of requested state machine(s) -/*! The protocol is: - * - 'list' - send list of all instantiated StateNodes - * - 'spider name' - spider the current structure of StateNode named name - * - 'listen name' - send updates regarding the activation status of name and its subnodes; you can specify a state which is not yet running - * - 'ignore name' - cancels a previous listen command - * - 'clear' - cancels all previous listen commands; should be called at the beginning or end of each connection, preferably both - * - * Each of those commands should be terminated with a newline - - * i.e. one command per line - * - * After a list command, the first line will be the number - * of StateNodes, followed by that number of lines, one StateNode - * name per line. - * - * After a spider command, an XML description of the model - * will be sent. If no matching StateNode is found, an warning will - * be displayed on #serr, and an empty model - * ("") returned over the network - * connection. - * - * All other commands give no direct response - listen can be - * executed before the specified StateNode is yet running, and ignore - * doesn't care whether or not the specified StateNode was actually - * being listened for. - * - * The format of the model is: - @verbatim - - - - - - - - - - - ]>@endverbatim - * - * The format of status updates following a listen command is: - @verbatim - - - - - - - - - - - - ]>@endverbatim -*/ -class SpiderMachineBehavior : public BehaviorBase { -public: - //! Points to the one SpiderMachineBehavior object that the input command stream is talking to. - /*! A kludge. Dunno how you're gonna make sure you're not using this uninitialized. */ - static SpiderMachineBehavior * theOne; - static unsigned int port; //!< the port to listen on (10081 by default) - static int callback(char *buf, int bytes); //!< called by wireless when there's new data - -public: - //! constructor - SpiderMachineBehavior() : BehaviorBase("SpiderMachineBehavior"), cmdsock(NULL), expected(), listen(), queuedEvents() {} - - virtual void DoStart(); - virtual void DoStop(); - virtual void processEvent(const EventBase& e); - - //! dumps all of the transitions and subnodes of a given statenode - void spider(const StateNode* n, unsigned int depth=0); - - //! returns true iff @a n or one of its parents is found in #listen - bool isListening(const StateNode* n); - - static std::string getClassDescription() { - char tmp[20]; - sprintf(tmp,"%d",port); - return std::string("When active and connected over network socket on port ")+tmp - +std::string(", outputs structure of requested state machine(s)"); - } - virtual std::string getDescription() const { return getClassDescription(); } - - //! parses commands sent from callback() - void runCommand(const std::string& s); - -protected: - //!just to prettify the data sent out - probably should make this a null-op to save bandwidth after debugging is done - void indent(unsigned int level); - - //!searches currently instantiated StateNodes to find the one named @a name - const StateNode * find(const std::string& name); - - class Socket *cmdsock; //!< the socket for communication - - typedef std::set registry_t; //!< the type of the behavior registry (BehaviorBase::registry) - typedef std::multiset expected_t; //!< the type of #expected - typedef std::set listen_t; //!< the type of #listen - typedef std::queue queuedEvents_t; //!< the type of #queuedEvents - - expected_t expected; //!< a set of behaviors which are involved with an impending transition - their next stateMachineEGID event should be ignored - - listen_t listen; //!< a set of state machine names which should have their subnodes monitored - - queuedEvents_t queuedEvents; //!< used if a transition causes other transitions, those transitions need to be remembered - -private: - SpiderMachineBehavior(const SpiderMachineBehavior&); //!< don't call - SpiderMachineBehavior operator=(const SpiderMachineBehavior&); //!< don't call -}; - -/*! @file - * @brief Defines SpiderMachineBehavior, which active and connected over network socket, outputs structure of requested state machine(s) - * @author ejt (Creator) - * - * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.9 $ - * $State: Exp $ - * $Date: 2005/08/07 04:11:03 $ - */ - -#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/StewartPlatformBehavior.cc ./Behaviors/Mon/StewartPlatformBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/StewartPlatformBehavior.cc 2005-06-01 01:47:45.000000000 -0400 +++ ./Behaviors/Mon/StewartPlatformBehavior.cc 2007-05-21 16:51:20.000000000 -0400 @@ -13,7 +13,7 @@ // Behavior startup BehaviorBase::DoStart(); // Turn on wireless - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 300, 300); + cmdsock=wireless->socket(Socket::SOCK_STREAM, 300, 300); sock=cmdsock->sock; wireless->setDaemon(cmdsock,true); wireless->setReceiver(cmdsock->sock, callback); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/StewartPlatformBehavior.h ./Behaviors/Mon/StewartPlatformBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/StewartPlatformBehavior.h 2005-08-07 00:11:03.000000000 -0400 +++ ./Behaviors/Mon/StewartPlatformBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -41,7 +41,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.stewart_port); + sprintf(tmp,"%d",*config->main.stewart_port); return std::string("moves the legs in synchrony to emulate the capabilities of a stewart platform, base on commands from port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/UPennWalkControllerBehavior.cc ./Behaviors/Mon/UPennWalkControllerBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/UPennWalkControllerBehavior.cc 2006-09-18 14:08:07.000000000 -0400 +++ ./Behaviors/Mon/UPennWalkControllerBehavior.cc 2007-05-21 16:51:20.000000000 -0400 @@ -94,7 +94,7 @@ // Turn on wireless theLastOne=theOne; theOne=this; - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 2048, 2048); + cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 2048); wireless->setReceiver(cmdsock->sock, mechacmd_callback); wireless->setDaemon(cmdsock,true); wireless->listen(cmdsock->sock, config->main.walkControl_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/UPennWalkControllerBehavior.h ./Behaviors/Mon/UPennWalkControllerBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/UPennWalkControllerBehavior.h 2005-04-23 14:33:26.000000000 -0400 +++ ./Behaviors/Mon/UPennWalkControllerBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -90,7 +90,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.walkControl_port); + sprintf(tmp,"%d",*config->main.walkControl_port); return std::string("Listens to walk control commands coming in from port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/ViewWMVarsBehavior.h ./Behaviors/Mon/ViewWMVarsBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/ViewWMVarsBehavior.h 2004-11-10 20:45:36.000000000 -0500 +++ ./Behaviors/Mon/ViewWMVarsBehavior.h 2007-01-30 17:56:19.000000000 -0500 @@ -27,7 +27,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.wmmonitor_port); + sprintf(tmp,"%d",*config->main.wmmonitor_port); return std::string("Brings up the WatchableMemory GUI on port ")+tmp+std::string(" (connects to WMMonitorBehavior, this just launches the GUI)"); } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/WMMonitorBehavior.h ./Behaviors/Mon/WMMonitorBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/WMMonitorBehavior.h 2004-11-10 20:45:36.000000000 -0500 +++ ./Behaviors/Mon/WMMonitorBehavior.h 2007-05-21 16:51:20.000000000 -0400 @@ -65,7 +65,7 @@ // Behavior startup BehaviorBase::DoStart(); // Turn on wireless - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 2048, 8192); + cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 8192); wireless->setReceiver(cmdsock->sock, wmmonitorcmd_callback); wireless->setDaemon(cmdsock,true); wireless->listen(cmdsock->sock, config->main.wmmonitor_port); @@ -100,7 +100,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.wmmonitor_port); + sprintf(tmp,"%d",*config->main.wmmonitor_port); return std::string("Bidirectional control communication with WMMonitor on port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/WalkControllerBehavior.cc ./Behaviors/Mon/WalkControllerBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/WalkControllerBehavior.cc 2006-09-18 14:08:07.000000000 -0400 +++ ./Behaviors/Mon/WalkControllerBehavior.cc 2007-05-21 16:51:20.000000000 -0400 @@ -101,7 +101,7 @@ // Turn on wireless theLastOne=theOne; theOne=this; - cmdsock=wireless->socket(SocketNS::SOCK_STREAM, 2048, 2048); + cmdsock=wireless->socket(Socket::SOCK_STREAM, 2048, 2048); wireless->setReceiver(cmdsock->sock, mechacmd_callback); wireless->setDaemon(cmdsock,true); wireless->listen(cmdsock->sock, config->main.walkControl_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/WalkControllerBehavior.h ./Behaviors/Mon/WalkControllerBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/WalkControllerBehavior.h 2005-09-13 18:10:36.000000000 -0400 +++ ./Behaviors/Mon/WalkControllerBehavior.h 2007-08-28 14:31:15.000000000 -0400 @@ -2,8 +2,6 @@ #ifndef INCLUDED_WalkControllerBehavior_h_ #define INCLUDED_WalkControllerBehavior_h_ -#include -#include "Wireless/Wireless.h" #include "Behaviors/BehaviorBase.h" #include "Motion/MotionManager.h" #include "Motion/WalkMC.h" @@ -11,6 +9,9 @@ #include "Events/EventRouter.h" #include "Events/EventBase.h" #include "Shared/Config.h" +#include "Wireless/Wireless.h" + +#include //! Listens to control commands coming in from the command port for remotely controlling the walk /*! The communication protocol is a very simple binary format, shared @@ -102,7 +103,7 @@ static std::string getClassDescription() { char tmp[20]; - sprintf(tmp,"%d",config->main.walkControl_port); + sprintf(tmp,"%d",*config->main.walkControl_port); return std::string("Listens to walk control commands coming in from port ")+tmp; } virtual std::string getDescription() const { return getClassDescription(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/WorldStateSerializerBehavior.cc ./Behaviors/Mon/WorldStateSerializerBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Mon/WorldStateSerializerBehavior.cc 2006-09-19 18:51:38.000000000 -0400 +++ ./Behaviors/Mon/WorldStateSerializerBehavior.cc 2007-06-26 00:27:44.000000000 -0400 @@ -6,6 +6,9 @@ #include "Events/EventRouter.h" #include "Shared/LoadSave.h" +//! a little trick to get RobotName length under aperios, which has to use a string class instead of char* +inline size_t strlen(const std::string& st) { return st.size(); } + WorldStateSerializerBehavior::WorldStateSerializerBehavior() : BehaviorBase("WorldStateSerializerBehavior"), wsJoints(NULL), wsPIDs(NULL), lastProcessedTime(0) { @@ -15,13 +18,13 @@ BehaviorBase::DoStart(); // do this first const unsigned int transmitPIDSize=(NumPIDJoints*3)*LoadSave::getSerializedSize()+2*LoadSave::getSerializedSize(); - wsPIDs=wireless->socket(SocketNS::SOCK_STREAM, 1024, transmitPIDSize*4); // enough for 4 packets queued up + wsPIDs=wireless->socket(Socket::SOCK_STREAM, 1024, transmitPIDSize*4); // enough for 4 packets queued up wireless->setDaemon(wsPIDs); wireless->listen(wsPIDs, config->main.wspids_port); const size_t robotNameLen=strlen(RobotName)+1; //note the +1 to include '\0' at the end const size_t transmitJointsSize=(NumOutputs+NumSensors+NumButtons+NumPIDJoints)*LoadSave::getSerializedSize()+6*LoadSave::getSerializedSize()+robotNameLen; - wsJoints=wireless->socket(SocketNS::SOCK_STREAM, 1024, transmitJointsSize*4); // enough for 4 packets queued up + wsJoints=wireless->socket(Socket::SOCK_STREAM, 1024, transmitJointsSize*4); // enough for 4 packets queued up wireless->setDaemon(wsJoints); wireless->listen(wsJoints, config->main.wsjoints_port); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/WorldStateSerializerBehavior.h ./Behaviors/Mon/WorldStateSerializerBehavior.h --- ../Tekkotsu_3.0/Behaviors/Mon/WorldStateSerializerBehavior.h 2006-09-09 19:28:59.000000000 -0400 +++ ./Behaviors/Mon/WorldStateSerializerBehavior.h 2007-06-26 00:27:44.000000000 -0400 @@ -4,6 +4,7 @@ #include "Behaviors/BehaviorBase.h" #include "Shared/Config.h" +#include class Socket; @@ -38,7 +39,7 @@ virtual void processEvent(const EventBase& e); //!< core functionality - performs serialization, sends to sockets static std::string getClassDescription() { char tmp[80]; - sprintf(tmp,"Sends sensor information to port %d and current pid values to port %d",config->main.wsjoints_port,config->main.wspids_port); + sprintf(tmp,"Sends sensor information to port %d and current pid values to port %d",*config->main.wsjoints_port,*config->main.wspids_port); return tmp; } virtual std::string getDescription() const { return getClassDescription(); } @@ -60,10 +61,16 @@ //! writes @a num copies of T from @a src to @a dst and advances @a dst by @a num * sizeof(T) /*! doesn't do any byte swapping, so this is only used if LoadSave indicates no byte swapping is needed */ template - inline static void copy(char **dst, const T * src, int num) { + inline static void copy(char **dst, const T * src, size_t num) { memcpy(*dst, src, num*sizeof(T)); (*dst) += num*sizeof(T); } + + //! writes @a num characters from @a src to @a dst and advances @a dst by @a num * sizeof(T) + inline static void copy(char **dst, const std::string& src, size_t num) { + memcpy(*dst, src.c_str(), num*sizeof(std::string::value_type)); + (*dst) += num*sizeof(std::string::value_type); + } Socket *wsJoints; //!< socket for sending current joint data Socket *wsPIDs; //!< socket for sending current PID info diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Nodes/MCNode.cc ./Behaviors/Nodes/MCNode.cc --- ../Tekkotsu_3.0/Behaviors/Nodes/MCNode.cc 2006-09-27 16:10:27.000000000 -0400 +++ ./Behaviors/Nodes/MCNode.cc 2007-03-13 04:31:26.000000000 -0400 @@ -8,18 +8,26 @@ // defined here instead of corresponding .cc files to avoid file bloat // (there would be nothing else in their .cc files) -//! name for TailWagNode to pass as template argument -extern const char defTailWagNodeName[]="TailWagNode"; -//! description for TailWagNode to pass as template argument -extern const char defTailWagNodeDesc[]="Wags the tail for as long as the state is active"; //! name for HeadPointerNode to pass as template argument extern const char defHeadPointerNodeName[]="HeadPointerNode"; //! description for HeadPointerNode to pass as template argument extern const char defHeadPointerNodeDesc[]="Manages a HeadPointerMC to look in a given direction each time the node is activated"; +//! name for TailWagNode to pass as template argument +extern const char defTailWagNodeName[]="TailWagNode"; +//! description for TailWagNode to pass as template argument +extern const char defTailWagNodeDesc[]="Wags the tail for as long as the state is active"; +//! name for PostureNode to pass as template argument +extern const char defPostureNodeName[]="PostureNode"; +//! description for PostureNode to pass as template argument +extern const char defPostureNodeDesc[]="Moves the body to the specified posture"; //! name for WalkNode to pass as template argument extern const char defWalkNodeName[]="WalkNode"; //! description for WalkNode to pass as template argument extern const char defWalkNodeDesc[]="Manages a WalkMC node to walk in a direction each time the node is activated."; +//! name for WaypointWalkNode to pass as template argument +extern const char defWaypointWalkNodeName[]="WaypointWalkNode"; +//! description for WaypointWalkNode to pass as template argument +extern const char defWaypointWalkNodeDesc[]="Manages a WaypointWalkMC to perform a waypoint walk each time the node is activated."; void MCNodeBase::DoStart() { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Nodes/MotionSequenceNode.h ./Behaviors/Nodes/MotionSequenceNode.h --- ../Tekkotsu_3.0/Behaviors/Nodes/MotionSequenceNode.h 2006-09-09 00:32:33.000000000 -0400 +++ ./Behaviors/Nodes/MotionSequenceNode.h 2007-04-06 22:03:43.000000000 -0400 @@ -6,6 +6,7 @@ #include "Motion/MotionManager.h" #include "Motion/MotionSequenceMC.h" #include "Motion/MMAccessor.h" +#include "Shared/debuget.h" //! A StateNode for playing a MotionSequence (and looping it if desired) /*! Eventually, i'd like to just build the looping functionality into diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Nodes/PostureNode.h ./Behaviors/Nodes/PostureNode.h --- ../Tekkotsu_3.0/Behaviors/Nodes/PostureNode.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Nodes/PostureNode.h 2007-11-11 18:57:19.000000000 -0500 @@ -0,0 +1,68 @@ +//-*-c++-*- +#ifndef INCLUDED_TailWagNode_h_ +#define INCLUDED_TailWagNode_h_ + +#include "MCNode.h" +#include "Events/EventRouter.h" +#include "Motion/PostureMC.h" + +//!default name for PostureNode's (have to instantiate a variable in order to use as a template argument) +/*! instantiation will be placed in MCNode.cc to avoid file bloat */ +extern const char defPostureNodeName[]; +//!default description for PostureNode's (have to instantiate a variable in order to use as a template argument) +/*! instantiation will be placed in MCNode.cc to avoid file bloat */ +extern const char defPostureNodeDesc[]; + +//! A simple StateNode that executes a PostureMC motion command +/*! Caches the posture file in a private PostureEngine because the + * motion command might be shared with other functions that are + * using it for other purposes */ +class PostureNode : public MCNode { +public: + + //! Constructor: takes optional instance name and filename. + /*! Caches the posture file in a private PostureEngine because the + motion command might be shared with other functions that are + using it for other purposes */ + PostureNode(const std::string &nodename=defPostureNodeName, const std::string &filename=std::string()) + : MCNode(nodename), posture() + { + if ( filename.size() > 0 ) + posture.loadFile(filename.c_str()); + } + + virtual void DoStart() { + getMC()->setAverage(posture,1); // copy cached posture into the motion command + MCNode::DoStart(); + } + + //! loads the specified file into #posture, note this @em doesn't affect the current PostureMC, just the cached one which will be loaded into it on next activation. See getPosture(), getMC_ID() + virtual void loadFile(const std::string &filename) { + posture.loadFile(filename.c_str()); + getMC()->setAverage(posture,1); + } + + //! accessor for #posture, note this @em doesn't affect the current PostureMC, just the cached one which will be loaded into it on next activation. See getMC_ID() + virtual PostureEngine& getPosture() { return posture; } + //! accessor for #posture, note this @em doesn't return the current PostureMC, just the cached one which will be loaded into it on next activation. See getMC_ID() + virtual const PostureEngine& getPosture() const { return posture; } + +protected: + //! The internal cache of joint positions, copied to the motion command when activated. + /*! This allows the motion command to be shared by other nodes/behaviors, which might modify + * the posture on an ongoing basis. */ + PostureEngine posture; +}; + +/*! @file + * @brief Defines PostureNode, a simple StateNode that runs a PostureMC motion command + * @author dst + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.5 $ + * $State: Exp $ + * $Date: 2007/11/11 23:57:19 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Nodes/WalkToTargetNode.cc ./Behaviors/Nodes/WalkToTargetNode.cc --- ../Tekkotsu_3.0/Behaviors/Nodes/WalkToTargetNode.cc 2004-12-04 23:47:53.000000000 -0500 +++ ./Behaviors/Nodes/WalkToTargetNode.cc 2007-08-28 14:05:19.000000000 -0400 @@ -5,7 +5,11 @@ #include "Events/VisionObjectEvent.h" #include "Shared/WorldState.h" #include "Behaviors/Transitions/TimeOutTrans.h" -#include "Behaviors/Transitions/VisualTargetCloseTrans.h" +#include "Shared/RobotInfo.h" +#include "Shared/ERS7Info.h" +#ifdef TGT_HAS_IR_DISTANCE +# include "Behaviors/Transitions/VisualTargetCloseTrans.h" +#endif void WalkToTargetNode::DoStart() { StateNode::DoStart(); @@ -37,19 +41,25 @@ } else return; + // for portability, look to see if the host hardware has a head pan & tilt joints + const unsigned int panIdx = capabilities.findOutputOffset(ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset]); + const unsigned int tiltIdx = capabilities.findOutputOffset(ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::TiltOffset]); + if(panIdx==-1U || tiltIdx==-1U) + return; // guess not... + //cout << "Pos: " << horiz << ' ' << vert << endl; - double tilt=state->outputs[HeadOffset+TiltOffset]-vert*M_PI/6; - double pan=state->outputs[HeadOffset+PanOffset]-horiz*M_PI/7.5; - if(tilt>outputRanges[HeadOffset+TiltOffset][MaxRange]) - tilt=outputRanges[HeadOffset+TiltOffset][MaxRange]; - if(tiltoutputRanges[HeadOffset+PanOffset][MaxRange]*2/3) - pan=outputRanges[HeadOffset+PanOffset][MaxRange]*2/3; - if(pan(headpointer_id)->setJoints(tilt,pan,0);} //note use of {}'s to limit scope + double tilt=state->outputs[tiltIdx]-vert*M_PI/6; + double pan=state->outputs[panIdx]-horiz*M_PI/7.5; + if(tilt>outputRanges[tiltIdx][MaxRange]) + tilt=outputRanges[tiltIdx][MaxRange]; + if(tiltoutputRanges[panIdx][MaxRange]*2/3) + pan=outputRanges[panIdx][MaxRange]*2/3; + if(pan(headpointer_id)->setJoints(tilt,pan,0); // note no variable name, one-line scope { MMAccessor walker(walker_id); @@ -65,7 +75,12 @@ } Transition* WalkToTargetNode::newDefaultCloseTrans(StateNode* dest) { +#ifdef TGT_HAS_IR_DISTANCE return new VisualTargetCloseTrans(dest,tracking); +#else + (void)dest; + return NULL; +#endif } @@ -74,9 +89,8 @@ * @author ejt (Creator) * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.1 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.4 $ * $State: Exp $ - * $Date: 2004/12/05 04:47:53 $ + * $Date: 2007/08/28 18:05:19 $ */ - diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Nodes/WaypointWalkNode.h ./Behaviors/Nodes/WaypointWalkNode.h --- ../Tekkotsu_3.0/Behaviors/Nodes/WaypointWalkNode.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Nodes/WaypointWalkNode.h 2007-02-26 03:42:51.000000000 -0500 @@ -0,0 +1,64 @@ +//-*-c++-*- +#ifndef INCLUDED_WaypointWalkNode_h_ +#define INCLUDED_WaypointWalkNode_h_ + +#include "MCNode.h" +#include "Motion/MotionManager.h" +#include "Motion/WaypointWalkMC.h" +#include "Events/EventRouter.h" +#include "Events/LocomotionEvent.h" + +//!default name for WaypointEngineNode's (have to instantiate a variable in order to use as a template argument) +/*! instantiation will be placed in MCNode.cc to avoid file bloat */ +extern const char defWaypointWalkNodeName[]; +//!default description for WaypointWalkNode's (have to instantiate a variable in order to use as a template argument) +/*! instantiation will be placed in MCNode.cc to avoid file bloat */ +extern const char defWaypointWalkNodeDesc[]; + +//! A StateNode for doing a waypoint walk, use the template parameter to specify a custom walk MC, or use the ::WaypointWalkNode typedef to accept the "default" walk +template +class WaypointEngineNode : public MCNode { +public: + + //! constructor + WaypointEngineNode() : MCNode() {} + + //! constructor + WaypointEngineNode(const std::string& name) : MCNode(name) {} + + //!destructor + ~WaypointEngineNode() {} + + virtual void DoStart() { + MCNode::DoStart(); + erouter->addListener(this,EventBase::locomotionEGID,MCNode::getMC_ID(),EventBase::statusETID); + } + +protected: + + //! constructor + WaypointEngineNode(const std::string& className, const std::string& instanceName) : + MCNode(className,instanceName) {} + + void processEvent(const EventBase &event) { + if ( static_cast(event).isStop() ) + MCNode::postCompletionEvent(); + } + +}; + +//! the prototypical WaypointWalkNode, using a WaypointWalkMC +typedef WaypointEngineNode WaypointWalkNode; + +/*! @file + * @brief Describes WaypointEngineNode, a StateNode for doing a waypoint walk; use the template parameter to specify a custom waypoint walk MC, or use the WaypointWalkNode typedef to accept the "default" walk + * @author dst (Creator) + * + * $Author: dst $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.1 $ + * $State: Exp $ + * $Date: 2007/02/26 08:42:51 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Services/AutoGetupBehavior.h ./Behaviors/Services/AutoGetupBehavior.h --- ../Tekkotsu_3.0/Behaviors/Services/AutoGetupBehavior.h 2006-09-18 14:07:56.000000000 -0400 +++ ./Behaviors/Services/AutoGetupBehavior.h 2007-11-12 13:00:40.000000000 -0500 @@ -19,10 +19,10 @@ //! destructor virtual ~AutoGetupBehavior() {} - //! Listens for the SensorSourceID::UpdatedSID + //! Listens for the SensorSrcID::UpdatedSID virtual void DoStart() { BehaviorBase::DoStart(); - erouter->addListener(this,EventBase::sensorEGID,SensorSourceID::UpdatedSID); + erouter->addListener(this,EventBase::sensorEGID,SensorSrcID::UpdatedSID); } //! Stops listening for events virtual void DoStop() { @@ -33,7 +33,7 @@ virtual void processEvent(const EventBase &event) { if(event.getGeneratorID()==EventBase::motmanEGID) { //previous attempt at getting up has completed - cout << "Getup complete" << endl; + std::cout << "Getup complete" << std::endl; erouter->removeListener(this,EventBase::motmanEGID); waiting=false; return; @@ -42,7 +42,7 @@ side=side*gamma+(1-gamma)*state->sensors[LAccelOffset]; if(!waiting && back*back+side*side>sensitivity*WorldState::g*WorldState::g) { //fallen down - cout << "I've fallen!" << endl; + std::cout << "I've fallen!" << std::endl; sndman->playFile("yipper.wav"); std::string gu; //config->motion.makePath will return a path relative to config->motion.root (from config file read at boot) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Services/BatteryMonitorBehavior.h ./Behaviors/Services/BatteryMonitorBehavior.h --- ../Tekkotsu_3.0/Behaviors/Services/BatteryMonitorBehavior.h 2006-09-14 15:14:03.000000000 -0400 +++ ./Behaviors/Services/BatteryMonitorBehavior.h 2007-06-28 00:36:20.000000000 -0400 @@ -29,16 +29,16 @@ //! destructor virtual ~BatteryMonitorBehavior() {} - //! Listens for the PowerSourceID::LowPowerWarnSID + //! Listens for the PowerSrcID::LowPowerWarnSID virtual void DoStart() { BehaviorBase::DoStart(); - erouter->addListener(this,EventBase::powerEGID,PowerSourceID::LowPowerWarnSID); - erouter->addListener(this,EventBase::powerEGID,PowerSourceID::ExternalPowerSID); - erouter->addListener(this,EventBase::powerEGID,PowerSourceID::BatteryConnectSID); - erouter->addListener(this,EventBase::powerEGID,PowerSourceID::UpdatedSID); + erouter->addListener(this,EventBase::powerEGID,PowerSrcID::LowPowerWarnSID); + erouter->addListener(this,EventBase::powerEGID,PowerSrcID::ExternalPowerSID); + erouter->addListener(this,EventBase::powerEGID,PowerSrcID::BatteryConnectSID); + erouter->addListener(this,EventBase::powerEGID,PowerSrcID::UpdatedSID); //if the low power warning is *already* on, better forge an event and send it to myself if(shouldWarn()) - processEvent(EventBase(EventBase::powerEGID,PowerSourceID::UpdatedSID,EventBase::statusETID)); + processEvent(EventBase(EventBase::powerEGID,PowerSrcID::UpdatedSID,EventBase::statusETID)); } //! Stops listening for events virtual void DoStop() { @@ -98,7 +98,7 @@ virtual std::string getDescription() const { return getClassDescription(); } //! returns true if the warning should be active (power remaining less than high_power_p, no external power, but also checks that a power update has been received) - static bool shouldWarn() { return state!=NULL && state->powerFlags[PowerSourceID::BatteryConnectSID] && (state->sensors[PowerRemainOffset]*100<=high_power_p || state->powerFlags[PowerSourceID::LowPowerWarnSID]) && !state->powerFlags[PowerSourceID::ExternalPowerSID]; } + static bool shouldWarn() { return state!=NULL && state->powerFlags[PowerSrcID::BatteryConnectSID] && (state->sensors[PowerRemainOffset]*100<=high_power_p || state->powerFlags[PowerSrcID::LowPowerWarnSID]) && !state->powerFlags[PowerSrcID::ExternalPowerSID]; } protected: //! adds a pose and a timer to get the ears flipping @@ -131,16 +131,20 @@ return 0; return (unsigned int)(max_t*(cur_power-no_power)/(high_power-no_power)); } - //!sets the ears on a 210 or the headlight on a 220 - true toggles current, false clears + //!sets the ears on a 210 & 7 or the headlight on a 220 - true toggles current, false clears void setFlipper(bool set) { - if(state->robotDesign & WorldState::ERS210Mask) - for(unsigned int i=ERS210Info::EarOffset; isetOutputCmd(i,set?!state->outputs[i]:OutputCmd()); - if(state->robotDesign & WorldState::ERS220Mask) - pose->setOutputCmd(ERS220Info::RetractableHeadLEDOffset,set?(state->outputs[ERS220Info::RetractableHeadLEDOffset]>.5?0:1):OutputCmd()); - if(state->robotDesign & WorldState::ERS7Mask) - for(unsigned int i=ERS7Info::EarOffset; isetOutputCmd(light,set?(state->outputs[light]>.5?0:1):OutputCmd()); + } else if(RobotName == ERS7Info::TargetName) { + int ear=capabilities.getOutputOffset(ERS7Info::outputNames[ERS7Info::EarOffset]); + for(unsigned int i=ear; isetOutputCmd(i,set?!state->outputs[i]:OutputCmd()); + } } PostureMC* pose; //!< if we are currently warning of low battery, holds a pose, NULL otherwise MotionManager::MC_ID pose_id; //!< id of pose if we are currently warning, MotionManager::invalid_MC_ID otherwise diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Services/DeadReckoningBehavior.h ./Behaviors/Services/DeadReckoningBehavior.h --- ../Tekkotsu_3.0/Behaviors/Services/DeadReckoningBehavior.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Behaviors/Services/DeadReckoningBehavior.h 2007-11-11 18:57:20.000000000 -0500 @@ -0,0 +1,64 @@ +//-*-c++-*- +#ifndef INCLUDED_DeadReckoningBehavior_h_ +#define INCLUDED_DeadReckoningBehavior_h_ + +#include "Behaviors/BehaviorBase.h" +#include "Events/EventRouter.h" +#include "Events/LocomotionEvent.h" +#include "Motion/HolonomicMotionModel.h" +#include "Shared/WorldState.h" + +//! Subscribes to LocomotionEvents and attempts to track robot movement over time using a fairly generic HolonomicMotionModel +/*! Can be used as a ParticleFilter::MotionModel, or as a component of other behaviors. + * + * If you want a regular report on position, the behavior will output current position on timer events */ +template +class DeadReckoningBehavior : public BehaviorBase, public HolonomicMotionModel { +public: + //! constructor + explicit DeadReckoningBehavior(const std::string& name="DeadReckoningBehavior") : BehaviorBase(name), HolonomicMotionModel() {} + + //! constructor + DeadReckoningBehavior(float xVariance, float yVariance, float aVariance) + : BehaviorBase("DeadReckoningBehavior"), HolonomicMotionModel(xVariance,yVariance,aVariance) {} + + virtual void DoStart() { + BehaviorBase::DoStart(); // do this first (required) + HolonomicMotionModel::setVelocity(state->vel_x, state->vel_y, state->vel_a); + erouter->addListener(this, EventBase::locomotionEGID ); + //erouter->addTimer(this, 0, 500); + } + + virtual void processEvent(const EventBase& event) { + if (event.getGeneratorID() == EventBase::locomotionEGID) { + const LocomotionEvent &locoevt = dynamic_cast(event); + HolonomicMotionModel::setVelocity(locoevt.x,locoevt.y,locoevt.a,locoevt.getTimeStamp()); + } else if (event.getGeneratorID() == EventBase::timerEGID) { + float tempx; + float tempy; + float tempa; + HolonomicMotionModel::getPosition(tempx, tempy, tempa); + std::cout << "DEADPOS " << tempx << " " << tempy << " " << tempa << std::endl; + } + } + + static std::string getClassDescription() { return "Subscribes to LocomotionEvents and attempts to track robot movement over time"; } + virtual std::string getDescription() const { return getClassDescription(); } + +protected: + //! constructor, accepts separate classname and instance name parameters from subclass + DeadReckoningBehavior(const std::string& classname, const std::string& instancename) : BehaviorBase(classname, instancename), HolonomicMotionModel() {} +}; + +/*! @file +* @brief Defines DeadReckoningBehavior, which subscribes to LocomotionEvents and attempts to track robot movement over time using a fairly generic HolonomicMotionModel +* @author Ethan Tira-Thompson (ejt) (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.2 $ +* $State: Exp $ +* $Date: 2007/11/11 23:57:20 $ +*/ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Services/FlashIPAddrBehavior.cc ./Behaviors/Services/FlashIPAddrBehavior.cc --- ../Tekkotsu_3.0/Behaviors/Services/FlashIPAddrBehavior.cc 2006-09-18 14:07:56.000000000 -0400 +++ ./Behaviors/Services/FlashIPAddrBehavior.cc 2007-08-05 12:16:04.000000000 -0400 @@ -1,5 +1,11 @@ -#include "FlashIPAddrBehavior.h" +#include "Shared/RobotInfo.h" +#ifdef TGT_HAS_LEDS + +#include "Shared/ERS210Info.h" +#include "Shared/ERS220Info.h" +#include "Shared/ERS7Info.h" +#include "FlashIPAddrBehavior.h" #include "Events/EventRouter.h" #include "Motion/MMAccessor.h" #include "Motion/LedEngine.h" @@ -16,8 +22,10 @@ ms_id = motman->addPrunableMotion(ms,MotionManager::kEmergencyPriority+1); erouter->addListener(this,EventBase::motmanEGID,ms_id,EventBase::deactivateETID); } +#ifdef TGT_HAS_BUTTONS erouter->addListener(this,EventBase::buttonEGID,button1); erouter->addListener(this,EventBase::buttonEGID,button2); +#endif } void FlashIPAddrBehavior::DoStop() { @@ -55,6 +63,7 @@ } +#ifdef TGT_HAS_BUTTONS } else if(e.getGeneratorID()==EventBase::buttonEGID) { //if it's an activate, start a timer to expire in a few seconds //if it's a deactivate, cancel that timer @@ -63,6 +72,7 @@ erouter->addTimer(this,ACTIVATE_TIMER,2000,false); } else if(e.getTypeID()==EventBase::deactivateETID) erouter->removeTimer(this,ACTIVATE_TIMER); +#endif } else if(e.getGeneratorID()==EventBase::motmanEGID) { // display has completed, mark it as such @@ -143,14 +153,16 @@ } //cout << endl; if(i!=0) { - LEDBitMask_t dot=1<robotDesign&WorldState::ERS210Mask) { - dot=LedEngine::ERS210numMasks[10]; - } else if(state->robotDesign&WorldState::ERS220Mask) { + LEDBitMask_t dot=LedEngine::defaultCountNumMasks[10]; //default in case we don't recognize model +#ifdef TGT_HAS_LED_PANEL + if(RobotName == ERS210Info::TargetName) { + dot=LedEngine::defaultMimicNumMasks[10]; + } else if(RobotName == ERS220Info::TargetName) { dot=LedEngine::ERS220numMasks[10]; - } else if(state->robotDesign&WorldState::ERS7Mask) { + } else if(RobotName == ERS7Info::TargetName) { dot=LedEngine::ERS7numMasks[10]; } +#endif erouter->addTimer(this,sounds.size(),ms->getTime()+delay,false); sounds.push_back("numbers/dot.wav"); for(unsigned int j=0; jplay(); } +#endif /*! @file * @brief Implements FlashIPAddrBehavior, which displays IP address by flashing a series of numbers on the LED face panel diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Services/FlashIPAddrBehavior.h ./Behaviors/Services/FlashIPAddrBehavior.h --- ../Tekkotsu_3.0/Behaviors/Services/FlashIPAddrBehavior.h 2006-09-14 15:14:04.000000000 -0400 +++ ./Behaviors/Services/FlashIPAddrBehavior.h 2007-08-05 12:16:04.000000000 -0400 @@ -2,6 +2,10 @@ #ifndef INCLUDED_FlashIPAddrBehavior_h_ #define INCLUDED_FlashIPAddrBehavior_h_ +#ifndef TGT_HAS_LEDS +# error FlashIPAddrBehavior requires a target with LEDs +#endif + #include "Behaviors/BehaviorBase.h" #include "Motion/MotionManager.h" #include "Motion/MotionSequenceMC.h" @@ -26,11 +30,16 @@ virtual void processEvent(const EventBase& e); static std::string getClassDescription() { - std::string pre="Displays IP address by flashing a series of numbers on the LED face panel; Hold down "; + std::string pre="Displays IP address by flashing a series of numbers on the LED face panel;"; +#ifdef TGT_HAS_BUTTONS + pre+=" Hold down "; pre+=buttonNames[button1]; pre+=" and "; pre+=buttonNames[button2]; pre+=" to trigger any time while running"; +#else + pre+=" Set configuration file to enable display on boot."; +#endif return pre; } virtual std::string getDescription() const { return getClassDescription(); } @@ -42,8 +51,10 @@ void releaseSounds(); //!< releases the numeric sounds void setupSequence(); //!< construct the motion sequence for flashing leds, request timers to play corresponding sound file +#ifdef TGT_HAS_BUTTONS static const unsigned int button1=ChinButOffset; //!< one of two buttons which must be pressed together to trigger the report without using the Controller static const unsigned int button2=HeadFrButOffset; //!< one of two buttons which must be pressed together to trigger the report without using the Controller +#endif static const unsigned int ACTIVATE_TIMER=-1U; //!< timer id to specify both trigger buttons have been down long enough std::vector sounds; //!< sound to play, corresponding to timers to coincide with corresponding digit on the LEDs (could be done with chained sounds, but this is cooler) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/StateNode.h ./Behaviors/StateNode.h --- ../Tekkotsu_3.0/Behaviors/StateNode.h 2006-10-03 18:11:44.000000000 -0400 +++ ./Behaviors/StateNode.h 2007-08-14 14:23:27.000000000 -0400 @@ -9,14 +9,16 @@ //! Recursive data structure - both a state machine controller as well as a node within a state machine itself /*! - * Override DoStart() / DoStop() as you would a normal BehaviorBase subclass to - * have this node add some functionality of its own. - * * Override setup() to build your own Transition and StateNode network if you want * this node to contain a state machine. * + * Override DoStart() / DoStop() as you would a normal BehaviorBase subclass to + * have this node add some functionality of its own. + * * You can override setup to create a sub-network, as well as overriding DoStart and DoStop, in the same class. * + * See also the tutorial page on State Machines. + * * There are two StateNode templates in project/templates/: * - statenode.h * is intended for leaf nodes, which directly implement the execution of a task. diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transition.cc ./Behaviors/Transition.cc --- ../Tekkotsu_3.0/Behaviors/Transition.cc 2006-09-18 14:08:05.000000000 -0400 +++ ./Behaviors/Transition.cc 2007-03-02 12:20:51.000000000 -0500 @@ -12,7 +12,7 @@ if(sound.size()!=0) sndman->playFile(sound); - erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast(this),EventBase::statusETID,0,getName(),1); + erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast(this),EventBase::activateETID,0,getName(),1); for(unsigned int i=0; iisActive()) //It's usually a bad idea to call DoStop/DoStart when it's already stopped/started... @@ -21,6 +21,8 @@ if(!dsts[i]->isActive()) dsts[i]->DoStart(); + erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast(this),EventBase::deactivateETID,0,getName(),0); + //serr->printf("%s fire() - leave %d\n",getName().c_str(),get_time()); RemoveReference(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transitions/CompareTrans.h ./Behaviors/Transitions/CompareTrans.h --- ../Tekkotsu_3.0/Behaviors/Transitions/CompareTrans.h 2005-04-15 17:31:15.000000000 -0400 +++ ./Behaviors/Transitions/CompareTrans.h 2007-06-05 14:04:30.000000000 -0400 @@ -12,7 +12,7 @@ * * For example, if you want to transition when the IR sensor goes below, say 200, * pass &state->sensors[IRDistOffset], CompareTrans::LT, 200, and - * EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID) + * EventBase(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID) * as the polling event. Or a timer event to just check at a certain interval. * * If you pass a class as the templated type, only requires that < operator is diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transitions/CompletionTrans.h ./Behaviors/Transitions/CompletionTrans.h --- ../Tekkotsu_3.0/Behaviors/Transitions/CompletionTrans.h 2004-12-22 20:47:07.000000000 -0500 +++ ./Behaviors/Transitions/CompletionTrans.h 2007-11-12 23:16:01.000000000 -0500 @@ -30,7 +30,7 @@ completions[i] = false; erouter->addListener(this, EventBase::stateMachineEGID, - (unsigned int)getSources()[i], + reinterpret_cast(getSources()[i]), EventBase::statusETID); }; } @@ -47,7 +47,7 @@ virtual void processEvent(const EventBase &event) { int numcomplete = 0; for ( unsigned int i=0; i(getSources()[i]) ) completions[i] = true; if ( completions[i] ) ++numcomplete; }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transitions/EventTrans.h ./Behaviors/Transitions/EventTrans.h --- ../Tekkotsu_3.0/Behaviors/Transitions/EventTrans.h 2004-12-22 20:47:07.000000000 -0500 +++ ./Behaviors/Transitions/EventTrans.h 2007-11-13 00:13:31.000000000 -0500 @@ -11,44 +11,63 @@ private: int argcount; //!< the number of arguments which were supplied to the constructor (granularity of filtering) EventBase::EventGeneratorID_t egid; //!< the requested generator - unsigned int esid; //!< the requested source + size_t esid; //!< the requested source + unsigned int *esidAddr; EventBase::EventTypeID_t etid; //!< the requested type public: //!@name Constructors //! follows general pattern of EventRouter::addListener() EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid) - : Transition("EventTrans",destination), argcount(1), egid(gid), esid(0), etid(EventBase::statusETID) + : Transition("EventTrans",destination), argcount(1), egid(gid), esid(0), esidAddr(NULL), etid(EventBase::statusETID) {} - EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int sid) - : Transition("EventTrans",destination), argcount(2), egid(gid), esid(sid), etid(EventBase::statusETID) + EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid, size_t sid) + : Transition("EventTrans",destination), argcount(2), egid(gid), esid(sid), esidAddr(NULL), etid(EventBase::statusETID) {} - EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int sid, EventBase::EventTypeID_t tid) - : Transition("EventTrans",destination), argcount(3), egid(gid), esid(sid), etid(tid) + EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int *sidAddr) + : Transition("EventTrans",destination), argcount(2), egid(gid), esid(0), esidAddr(sidAddr), etid(EventBase::statusETID) + {} + + EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid, size_t sid, EventBase::EventTypeID_t tid) + : Transition("EventTrans",destination), argcount(3), egid(gid), esid(sid), esidAddr(NULL), etid(tid) + {} + + EventTrans(StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int* sidAddr, EventBase::EventTypeID_t tid) + : Transition("EventTrans",destination), argcount(3), egid(gid), esid(0), esidAddr(sidAddr), etid(tid) {} EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid) - : Transition("EventTrans",name,destination), argcount(1), egid(gid), esid(0), etid(EventBase::statusETID) + : Transition("EventTrans",name,destination), argcount(1), egid(gid), esid(0), esidAddr(NULL), etid(EventBase::statusETID) {} - EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int sid) - : Transition("EventTrans",name,destination), argcount(2), egid(gid), esid(sid), etid(EventBase::statusETID) + EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid, size_t sid) + : Transition("EventTrans",name,destination), argcount(2), egid(gid), esid(sid), esidAddr(NULL), etid(EventBase::statusETID) {} - EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int sid, EventBase::EventTypeID_t tid) - : Transition("EventTrans",name,destination), argcount(3), egid(gid), esid(sid), etid(tid) + EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int *sidAddr) + : Transition("EventTrans",name,destination), argcount(2), egid(gid), esid(0), esidAddr(sidAddr), etid(EventBase::statusETID) + {} + + EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid, size_t sid, EventBase::EventTypeID_t tid) + : Transition("EventTrans",name,destination), argcount(3), egid(gid), esid(sid), esidAddr(NULL), etid(tid) + {} + EventTrans(const std::string& name, StateNode* destination, EventBase::EventGeneratorID_t gid, unsigned int *sidAddr, EventBase::EventTypeID_t tid) + : Transition("EventTrans",name,destination), argcount(3), egid(gid), esid(0), esidAddr(sidAddr), etid(tid) {} //@} //! starts listening virtual void DoStart() { Transition::DoStart(); - switch (argcount) { - case 1: erouter->addListener(this,egid); break; - case 2: erouter->addListener(this,egid,esid); break; - case 3: erouter->addListener(this,egid,esid,etid); + if ( esidAddr != 0 ) + erouter->addListener(this,egid); // must check sid dynamically as events come in + else + switch (argcount) { + case 1: erouter->addListener(this,egid); break; + case 2: erouter->addListener(this,egid,esid); break; + case 3: erouter->addListener(this,egid,esid,etid); }; } @@ -59,7 +78,17 @@ } //! fire the transition if an event is seen - virtual void processEvent(const EventBase&) { fire(); } + virtual void processEvent(const EventBase &event) { + if ( esidAddr == 0 ) + fire(); + else if ( event.getSourceID() == *esidAddr ) + if ( argcount == 2 || event.getTypeID() == etid ) + fire(); + } + +private: + EventTrans(const EventTrans&); //!< do not call + EventTrans& operator=(const EventTrans&); //!< do not call }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transitions/RandomTrans.cc ./Behaviors/Transitions/RandomTrans.cc --- ../Tekkotsu_3.0/Behaviors/Transitions/RandomTrans.cc 2006-09-18 14:08:04.000000000 -0400 +++ ./Behaviors/Transitions/RandomTrans.cc 2007-03-02 12:20:53.000000000 -0500 @@ -33,6 +33,9 @@ void RandomTrans::fire() { AddReference(); // for safety + + erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast(this),EventBase::activateETID,0,getName(),1); + if ( sound.size()!=0 ) sndman->playFile(sound); @@ -56,6 +59,8 @@ }; } + erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast(this),EventBase::deactivateETID,0,getName(),0); + RemoveReference(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transitions/RandomTrans.h ./Behaviors/Transitions/RandomTrans.h --- ../Tekkotsu_3.0/Behaviors/Transitions/RandomTrans.h 2005-01-04 14:51:41.000000000 -0500 +++ ./Behaviors/Transitions/RandomTrans.h 2006-11-13 09:44:06.000000000 -0500 @@ -22,7 +22,7 @@ RandomTrans(const std::string& name, StateNode* destination, float weight=1); //! Add a destination node with weight==1 (see addDestination(StateNode* dest, float weight) to specify a different weight) - virtual void RandomTrans::addDestination(StateNode* destination) { + virtual void addDestination(StateNode* destination) { addDestination(destination,1); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Transitions/VisualTargetCloseTrans.h ./Behaviors/Transitions/VisualTargetCloseTrans.h --- ../Tekkotsu_3.0/Behaviors/Transitions/VisualTargetCloseTrans.h 2005-06-13 17:22:41.000000000 -0400 +++ ./Behaviors/Transitions/VisualTargetCloseTrans.h 2007-06-26 00:27:45.000000000 -0400 @@ -33,15 +33,11 @@ ASSERTRET(ve!=NULL,"Casting error"); float x=ve->getCenterX(); float y=ve->getCenterY(); - unsigned int IRDistOffset=-1U; + unsigned int IRDistOffset=::IRDistOffset; //The ERS-7 adds more IR distance sensors, so we have to - //break it down by model so we can specify which one - if(state->robotDesign & WorldState::ERS210Mask) - IRDistOffset=ERS210Info::IRDistOffset; - else if(state->robotDesign & WorldState::ERS220Mask) - IRDistOffset=ERS220Info::IRDistOffset; - else if(state->robotDesign & WorldState::ERS7Mask) - IRDistOffset=ERS7Info::NearIRDistOffset; + //break it down so we can specify which one + if(RobotName == ERS7Info::TargetName) + IRDistOffset=(distanceThreshold<350) ? ERS7Info::NearIRDistOffset : ERS7Info::FarIRDistOffset; if(x*x+y*y<0.02f && IRDistOffset!=-1U && state->sensors[IRDistOffset] class Sketch; +//! Representation of the robot on the world map class AgentData : public BaseData { private: Point center_pt; @@ -49,15 +50,14 @@ const NEWMAT::ColumnVector& groundplane); //! Transformations. (Virtual in BaseData.) - virtual void applyTransform(const NEWMAT::Matrix& Tmat); - + virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); virtual unsigned short getDimension() const { return 3; } AngTwoPi getOrientation() const { return orientation; } protected: - //! Updates orientation according to @param orientation_pt + //! Updates orientation according to #orientation_pt void updateOrientation(); private: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BaseData.cc ./DualCoding/BaseData.cc --- ../Tekkotsu_3.0/DualCoding/BaseData.cc 2006-08-10 23:20:22.000000000 -0400 +++ ./DualCoding/BaseData.cc 2007-11-11 18:57:20.000000000 -0500 @@ -1,5 +1,5 @@ #include "Macrodefs.h" -#include "Measures.h" +#include "Shared/Measures.h" #include "Sketch.h" // this must precede references to Sketch #include "BaseData.h" @@ -8,11 +8,13 @@ #include "SketchDataRoot.h" #include "ShapeSpace.h" +using namespace std; + namespace DualCoding { BoundingBox::BoundingBox(const BoundingBox &b1, const BoundingBox &b2) : - xmin(min(b1.xmin,b2.xmin)), ymin(min(b1.ymin,b2.ymin)), - xmax(max(b1.xmax,b2.xmax)), ymax(max(b1.ymax,b2.ymax)) {} + xmin(std::min(b1.xmin,b2.xmin)), ymin(std::min(b1.ymin,b2.ymin)), + xmax(std::max(b1.xmax,b2.xmax)), ymax(std::max(b1.ymax,b2.ymax)) {} BoundingBox::BoundingBox(const std::vector &vec) : xmin(0), ymin(0), xmax(0), ymax(0) { @@ -142,18 +144,22 @@ bool BaseData::isSameColorAs(const ShapeRoot& other) const { return getColor() == other->getColor(); } -void BaseData::setColor(string const &color_name) { +void BaseData::setColor(const std::string &color_name) { setColor(ProjectInterface::getColorRGB(color_name)); } -void BaseData::setColor(rgb new_color) { +void BaseData::setColor(const rgb &new_color) { color_rgb = new_color; if ( rendering_sketch != NULL ) (*rendering_sketch)->setColor(new_color); } +void BaseData::setColor(const unsigned int color_index) { + setColor(ProjectInterface::getColorRGB(color_index)); +} + -bool BaseData::isMobile() const { return mobile; } +bool BaseData::getMobile() const { return mobile; } void BaseData::setMobile(bool _mobile) { mobile = _mobile; } @@ -176,7 +182,7 @@ void BaseData::increaseConfidence(int n, int maxConfidence) { confidence += n; if ( maxConfidence > 0 ) - confidence = min(confidence, maxConfidence); + confidence = std::min(confidence, maxConfidence); } void BaseData::increaseConfidence(const BaseData& other, int maxConfidence) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BaseData.h ./DualCoding/BaseData.h --- ../Tekkotsu_3.0/DualCoding/BaseData.h 2006-08-10 23:20:22.000000000 -0400 +++ ./DualCoding/BaseData.h 2007-04-06 22:18:33.000000000 -0400 @@ -8,7 +8,7 @@ #include "Wireless/Socket.h" // needed for sout #include "Macrodefs.h" -#include "Measures.h" +#include "Shared/Measures.h" #include "Point.h" #include "Shared/newmat/newmat.h" #include "Motion/Kinematics.h" @@ -22,9 +22,11 @@ class SketchSpace; template class Sketch; class ShapeRoot; +class ShapeSpace; class SketchDataRoot; template class Shape; +//! Bounding box of a shape; used for coordinate calculations class BoundingBox { public: coordinate_t xmin, ymin, xmax, ymax; @@ -45,6 +47,7 @@ std::ostream& operator<< (std::ostream& out, const BoundingBox &b); +//! Base class that all shape data classes inherit from, e.g., @a LineData, @a BlobData, etc. class BaseData { public: friend class ShapeRoot; @@ -145,8 +148,9 @@ //! Set shape and rendering sketch color. //@{ - void setColor(std::string const &color_name); - void setColor(rgb new_color); + void setColor(const std::string &color_name); + void setColor(const rgb &new_color); + void setColor(const unsigned int color_index); //@} //! Test if shape colors are the same. @@ -173,7 +177,7 @@ //! Mobility //@{ - bool isMobile() const; + bool getMobile() const; void setMobile(bool mobility); //@} @@ -188,7 +192,7 @@ virtual void printParams() const=0; //! Apply a transformation matrix to the shape. - virtual void applyTransform(const NEWMAT::Matrix& Tmat)=0; + virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified)=0; //! Project to ground plane using given matrix virtual void projectToGround(const NEWMAT::Matrix& camToBase, @@ -203,10 +207,12 @@ //! If no such rendering exists, it is created. Sketch& getRendering(); +private: //! Render into a sketch space. virtual Sketch* render() const=0; //@} +public: //! Copy operator. Assumes "&other =? this" check is done by the sub class calling this operator BaseData& operator=(const BaseData& other); }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BlobData.cc ./DualCoding/BlobData.cc --- ../Tekkotsu_3.0/DualCoding/BlobData.cc 2006-08-02 17:27:14.000000000 -0400 +++ ./DualCoding/BlobData.cc 2007-11-11 18:57:20.000000000 -0500 @@ -19,17 +19,21 @@ #include "BrickOps.h" +using namespace std; + namespace DualCoding { BlobData::BlobData(ShapeSpace& _space, const Point &_topLeft, const Point &_topRight, const Point &_bottomLeft, const Point &_bottomRight, const float _area, const std::vector &_runvec, - const BlobOrientation_t _orientation, rgb _rgbvalue) : + const BlobOrientation_t _orientation, coordinate_t _assumedHeight, + rgb _rgbvalue) : BaseData(_space, getStaticType()), + orientation(_orientation), assumedHeight(_assumedHeight), topLeft(_topLeft), topRight(_topRight), bottomLeft(_bottomLeft), bottomRight(_bottomRight), - area(_area), runvec(_runvec), orientation(_orientation) + area(_area), runvec(_runvec) { setColor(_rgbvalue); } @@ -43,12 +47,13 @@ } void BlobData::printParams() const { - cout << "Blob" - << " tl=" << topLeft.coords - << " tr=" << topRight.coords - << " bl=" << bottomLeft.coords - << " br=" << bottomRight.coords - << " area=" << area + cout << "Type = " << getTypeName() << " ID=" << getId() << " ParentID=" << getParentId() << endl; + printf(" color = %d %d %d\n",getColor().red,getColor().green,getColor().blue); + cout << " tl=" << NEWMAT::printmat(topLeft.coords) << endl + << " tr=" << NEWMAT::printmat(topRight.coords) << endl + << " bl=" << NEWMAT::printmat(bottomLeft.coords) << endl + << " br=" << NEWMAT::printmat(bottomRight.coords) << endl + << " area=" << area << ", assumedHeight=" << assumedHeight << endl; } @@ -77,39 +82,24 @@ } break; case pillar: - case pinata: - cout << "BlobData::render() : Can't yet render blobs in pillar/pinata orientations" << endl; + case poster: + cout << "BlobData::render() : Can't yet render blobs in pillar/poster orientations" << endl; break; } return result; } //! Transformations. (Virtual in BaseData.) -void BlobData::applyTransform(const NEWMAT::Matrix& Tmat) { - switch ( orientation ) { - - case groundplane: - topLeft.applyTransform(Tmat); - topRight.applyTransform(Tmat); - bottomLeft.applyTransform(Tmat); - bottomRight.applyTransform(Tmat); - break; - - case pillar: - case pinata: - // *** HACK: THIS IS NOT THE RIGHT WAY TO CALCULATE HEIGHT - Point height_incr((topLeft-bottomLeft + topRight-bottomRight) / 2); - height_incr.coords << 0 << 0; - bottomLeft.applyTransform(Tmat); - bottomRight.applyTransform(Tmat); - topLeft = bottomLeft + height_incr; - topRight = bottomRight + height_incr; - break; - }; +void BlobData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + topLeft.applyTransform(Tmat,newref); + topRight.applyTransform(Tmat,newref); + bottomLeft.applyTransform(Tmat,newref); + bottomRight.applyTransform(Tmat,newref); } void BlobData::projectToGround(const NEWMAT::Matrix& camToBase, const NEWMAT::ColumnVector& gndplane) { + float const camblob_area = area; switch ( orientation ) { case groundplane: topLeft.projectToGround(camToBase,gndplane); @@ -118,53 +108,42 @@ bottomRight.projectToGround(camToBase,gndplane); break; case pillar: - case pinata: bottomLeft.projectToGround(camToBase,gndplane); bottomRight.projectToGround(camToBase,gndplane); - // DST HACK -- hard coded pillar height 100 mm topLeft = bottomLeft; topRight = bottomRight; - topLeft.coords(3) += 100; - topRight.coords(3) += 100; - } - update_derived_properties(); -} - - /* -void BlobData::projectToGround(int xres, int yres, const NEWMAT::ColumnVector& gndplane) { - switch ( orientation ) { - case groundplane: - topLeft.projectToGround(xres,yres,gndplane); - topRight.projectToGround(xres,yres,gndplane); - bottomLeft.projectToGround(xres,yres,gndplane); - bottomRight.projectToGround(xres,yres,gndplane); + topLeft.coords(3) += assumedHeight; + topRight.coords(3) += assumedHeight; + break; + case poster: + // create an elevated plane by shifting the ground plane by assumedHeight + NEWMAT::ColumnVector elevatedPlane = gndplane; + float displacement = assumedHeight * sqrt(elevatedPlane(1) * elevatedPlane(1) + elevatedPlane(2) * elevatedPlane(2) + elevatedPlane(3) * elevatedPlane(3)); + elevatedPlane(4) += elevatedPlane(3) >= 0 ? displacement : -displacement; + + // Project the centroid onto the elevated plane and set all 4 points to the new centroid + Point centroid = getCentroid(); + centroid.projectToGround(camToBase, elevatedPlane); + bottomLeft = centroid; + bottomRight = centroid; + topLeft = centroid; + topRight = centroid; break; - case pillar: - case pinata: - bottomLeft.projectToGround(xres,yres,gndplane); - bottomRight.projectToGround(xres,yres,gndplane); - // DST HACK -- hard coded pillar height 100 mm - topLeft = bottomLeft; - topRight = bottomRight; - topLeft.coords(3) += 100; - topRight.coords(3) += 100; } update_derived_properties(); + area = camblob_area; // stick with cam area for now } - */ void BlobData::update_derived_properties() { switch ( orientation ) { case groundplane: - // DST HACK -- should use the formula for area of a quadrilaterl - area = (topRight+bottomRight-topLeft-bottomLeft).coords(1) * - (bottomLeft+bottomRight-topLeft-topRight).coords(2) / 4; - break; - case pillar: - case pinata: - // fill this in later + case poster: + // DST HACK -- should project each run to ground and integrate, + // or use the formula for area of a quadrilateral + area = fabs((topRight+bottomRight-topLeft-bottomLeft).coords(1)) * + fabs((bottomLeft+bottomRight-topLeft-topRight).coords(2)) / 4; break; } } @@ -194,42 +173,69 @@ topRight = (topRight*confidence + other_blob->topRight*other_conf) / sumconf; bottomLeft = (bottomLeft*confidence + other_blob->bottomLeft*other_conf) / sumconf; bottomRight = (bottomRight*confidence + other_blob->bottomRight*other_conf) / sumconf; + float const newArea = (area*confidence + other_blob->area*other_conf) / sumconf; update_derived_properties(); + area = newArea; // fixup because update_derived_properties currently messes up on pillar and poster areas return true; } +//================================================================ +// Blob extraction + std::vector > BlobData::extractBlobs(const Sketch &sketch, - const set& colors, int minarea, - BlobData::BlobOrientation_t orient, + int minarea, + BlobOrientation_t orient, + coordinate_t height, int maxblobs) { // We could multiply sketch*color_index to convert to uchar and // spare ourselves the for loop that follows for setting blob // colors, but this way is actually much faster because we skip all // the pixel-wise multiplications. Casting Sketch to // Sketch is done with a simple reinterpret_cast; no copying. - std::vector > result(extractBlobs((Sketch&)sketch,colors,minarea,orient,maxblobs)); - rgb rgbvalue(sketch->getColor()); + set dummyColors; + dummyColors.insert(1); // converting bool to uchar always yields color index 1 + map minareas; + minareas[1] = minarea; + map orients; + orients[1] = orient; + map heights; + heights[1] = height; + std::vector > result(extractBlobs((Sketch&)sketch,dummyColors,minareas,orients,heights,maxblobs)); + rgb sketchColor(sketch->getColor()); for ( std::vector >::iterator it = result.begin(); it != result.end(); it++ ) - (*it)->setColor(rgbvalue); + (*it)->setColor(sketchColor); return result; } std::vector > -BlobData::extractBlobs(const Sketch &sketch, int minarea, - BlobData::BlobOrientation_t orient, int maxblobs) { +BlobData::extractBlobs(const Sketch &sketch, + int minarea, + BlobOrientation_t orient, + coordinate_t height, + int maxblobs) { const int numColors = ProjectInterface::getNumColors(); - set colors; - for (int i = 1; i < numColors; i++) colors.insert(i); - return extractBlobs(sketch, colors, minarea, orient, maxblobs); + set colors; + map minareas; + map orients; + map heights; + for (int i = 1; i < numColors; i++) { + colors.insert(i); + minareas[i] = minarea; + orients[i] = orient; + heights[i] = height; + } + return extractBlobs(sketch, colors, minareas, orients, heights, maxblobs); } - std::vector > BlobData::extractBlobs(const Sketch &sketch, - const set& colors, int minarea, - BlobData::BlobOrientation_t orient, int maxblobs) { + const std::set& colors, + const std::map& minareas, + const std::map& orients, + const std::map& heights, + int maxblobs) { int parent = sketch->getId(); uchar *pixels = &((*sketch.pixels)[0]); @@ -254,16 +260,19 @@ result.clear(); ShapeSpace &ShS = sketch->getSpace().getDualSpace(); // for ( size_t color=1; color < numColors; color++ ) { - for (set::const_iterator it = colors.begin(); + for (set::const_iterator it = colors.begin(); it != colors.end(); it++) { - // const CMVision::region* list_head = ccs[color].list; - const CMVision::region* list_head = ccs[*it].list; + int const color = *it; + const CMVision::region* list_head = ccs[color].list; if ( list_head != NULL ) { - // const rgb rgbvalue = ProjectInterface::getColorRGB(color); - const rgb rgbvalue = ProjectInterface::getColorRGB(*it); + const rgb rgbvalue = ProjectInterface::getColorRGB(color); + int const minarea = (minareas.find(color)==minareas.end()) ? 50 : const_cast&>(minareas)[color]; + BlobOrientation_t const orient = (orients.find(color)==orients.end()) ? + groundplane : const_cast&>(orients)[color]; + coordinate_t const height = (heights.find(color)==heights.end()) ? 0 : const_cast&>(heights)[color]; for (int i=0; list_head!=NULL && iarea >= minarea; list_head = list_head->next, i++) { - BlobData* blobdat = new_blob(ShS,*list_head, rle_buffer, orient, rgbvalue); + BlobData* blobdat = new_blob(ShS,*list_head, rle_buffer, orient, height, rgbvalue); blobdat->setParentId(parent); result.push_back(Shape(blobdat)); } @@ -275,20 +284,11 @@ return result; } -std::vector > -BlobData::extractBlobs(const Sketch &sketch, int minarea, - BlobData::BlobOrientation_t orient, int maxblobs) { - const int numColors = ProjectInterface::getNumColors(); - set colors; - for (int i = 1; i < numColors; i++) colors.insert(i); - return extractBlobs(sketch, colors, minarea, orient, maxblobs); -} - - BlobData* BlobData::new_blob(ShapeSpace& space, const CMVision::region ®, - const CMVision::run *rle_buff, - const BlobData::BlobOrientation_t orient, + const CMVision::run *rle_buff, + const BlobOrientation_t orient, + const coordinate_t height, const rgb rgbvalue) { int const x1 = reg.x1; int const y1 = reg.y1; @@ -312,34 +312,34 @@ return new BlobData(space, Point(x1,y1),Point(x2,y1), Point(x1,y2),Point(x2,y2), - reg.area, runvec, orient, rgbvalue); + reg.area, runvec, orient, height, rgbvalue); else return new BlobData(space, Point(x2,y2),Point(x1,y2), Point(x2,y1),Point(x1,y1), - reg.area, runvec, orient, rgbvalue); + reg.area, runvec, orient, height, rgbvalue); } +//================================================================ +// Corner extraction: General call to find the corners of a blob. +// Used in brick / pyramid extraction +// +// +// Requires the number of corners you expect to find. +// Currently just uses shape fitting to find the corners +// Originally used either the derivative or diagonal approaches to finding corners +// +// Shape fitting works very well, but is very slow. +// (no attempt was made to optimize it though) +// +// The old diagonal/derivative approach is at the bottom +// It is much faster, but less robust. + std::vector BlobData::findCorners(unsigned int nExpected, + std::vector& candidates, + float &bestValue) { - - - // General call to find the corners of a blob. - // Used in brick / pyramid extraction - // - // - // Requires the number of corners you expect to find. - // Currently just uses shape fitting to find the corners - // Originally used either the derivative or diagonal approaches to finding corners - // - // Shape fitting works very well, but is very slow. - // (no attempt was made to optimize it though) - // - // The old diagonal/derivative approach is at the bottom - // It is much faster, but less robust. - std::vector BlobData::findCorners(unsigned int nExpected, std::vector& candidates, float &bestValue) - { std::vector fitCorners = findCornersShapeFit(nExpected, candidates, bestValue); // debug output @@ -454,8 +454,6 @@ return fitCorners; - - // Old method, used the diagonal and derivative approaches and took the better results // Was generally much faster, but broke down in some special cases /* @@ -905,7 +903,7 @@ // Comparison predicates -bool BlobData::areaLessThan::operator() (const Shape &b1, const Shape &b2) const { +bool BlobData::AreaLessThan::operator() (const Shape &b1, const Shape &b2) const { return b1->getArea() < b2->getArea(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BlobData.h ./DualCoding/BlobData.h --- ../Tekkotsu_3.0/DualCoding/BlobData.h 2006-07-21 13:57:44.000000000 -0400 +++ ./DualCoding/BlobData.h 2007-03-28 05:19:17.000000000 -0400 @@ -4,6 +4,7 @@ #include #include +#include #include #include @@ -11,8 +12,9 @@ #include "Vision/cmv_types.h" #include "BaseData.h" // superclass -#include "Point.h" // Point data member -#include "ShapeTypes.h" // blobDataType +#include "Point.h" // Point data member +#include "SketchTypes.h" // uchar +#include "ShapeTypes.h" // blobDataType #include "ShapeFuns.h" namespace DualCoding { @@ -25,10 +27,12 @@ class BlobData : public BaseData { public: - // Bounding quadrilateral; may not be square when projected to world space. - Point topLeft, topRight, bottomLeft, bottomRight; - - float area; + //! Assumed orientation of the blob in 3D space. + enum BlobOrientation_t { + groundplane, //!< 2D shape lying flat on the ground + pillar, //!< 3D shape standing on the ground + poster //!< 3D shape hanging vertically in space + }; struct run { public: @@ -38,24 +42,24 @@ x(_x), y(_y), width(_width) {} }; - const std::vector runvec; - - //! Assumed orientation of the blob in 3D space. - enum BlobOrientation_t { - groundplane, //!< 2D shape lying flat on the ground - pillar, //!< 3D shape standing on the ground - pinata //!< 3D shape hanging vertically in space - } orientation; + // Data members + BlobOrientation_t orientation; //!< Orientation of the blob + coordinate_t assumedHeight; //!< Assumed height above ground of blob centroid (for poster) or top (for pillar) + //! Bounding quadrilateral: may not be square when projected to ground space. + Point topLeft, topRight, bottomLeft, bottomRight; + float area; //!< Area of the blob; may not be integer when projected to ground space + const std::vector runvec; //!< Runs (for rendering in camera space) public: //! Constructor BlobData(ShapeSpace& _space, const Point &_topLeft, const Point &_topRight, const Point &_bottomLeft, const Point &_bottomRight, - const float _area, - const std::vector &_runvec, - const BlobOrientation_t _orientation, - const rgb rgbvalue); + const float _area=0, + const std::vector &_runvec=std::vector(), + const BlobOrientation_t _orientation=groundplane, + const coordinate_t assumedHeight=0, + const rgb rgbvalue=rgb()); static ShapeType_t getStaticType() { return blobDataType; } @@ -73,7 +77,7 @@ virtual void printParams() const; //! Transformations. (Virtual in BaseData.) - virtual void applyTransform(const NEWMAT::Matrix& Tmat); + virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); //! Project to ground // virtual void projectToGround(int xres, int yres, const NEWMAT::ColumnVector& groundplane); @@ -93,45 +97,48 @@ //! Import blobs from Sketch as a vector of Shape static std::vector > - extractBlobs(const Sketch &sketch, - const set& colors, int minarea=0, - BlobData::BlobOrientation_t orient=BlobData::groundplane, - int maxblobs=50); - static std::vector > - extractBlobs(const Sketch &sketch, int minarea=0, - BlobData::BlobOrientation_t orient=BlobData::groundplane, + extractBlobs(const Sketch &sketch, + int minarea=25, + BlobOrientation_t orient=BlobData::groundplane, + coordinate_t height=0, int maxblobs=50); - //! Import blobs from Sketch as a vector of Shape + //! Import blobs of all colors from Sketch as a vector of Shape static std::vector > - extractBlobs(const Sketch &sketch, - const set& colors, int minarea=0, - BlobData::BlobOrientation_t orient=BlobData::groundplane, + extractBlobs(const Sketch &sketch, + int minarea=25, + BlobOrientation_t orient=BlobData::groundplane, + const coordinate_t height=0, int maxblobs=50); + + //! Import blobs of specified colors from Sketch as a vector of Shape static std::vector > - extractBlobs(const Sketch &sketch, int minarea=0, - BlobData::BlobOrientation_t orient=BlobData::groundplane, - int maxblobs=50); + extractBlobs(const Sketch &sketch, + const std::set& colors, + const std::map& minareas, + const std::map& orients, + const std::map& heights, + int maxblobs); - static BlobData* - new_blob(ShapeSpace& space, + //! Utility function for making a new blob instance from CMVision's region data structures + static BlobData* new_blob(ShapeSpace& space, const CMVision::region ®, const CMVision::run *rle_buff, - const BlobData::BlobOrientation_t orient, + const BlobOrientation_t orient, + const coordinate_t height, const rgb rgbvalue); + //!@name Corner extraction for rectangular blobs + //@{ std::vector findCorners(unsigned int nExpected, std::vector& candidates, float &bestValue); - std::vector findCornersDerivative(); - std::vector findCornersDiagonal(); - std::vector findCornersShapeFit(unsigned int ncorners, std::vector& candidates, float &bestValue); - + //@} // comparison predicates - class areaLessThan : public BinaryShapePred { + class AreaLessThan : public BinaryShapePred { public: bool operator() (const Shape &b1, const Shape &b2) const; }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BrickData.cc ./DualCoding/BrickData.cc --- ../Tekkotsu_3.0/DualCoding/BrickData.cc 2006-09-23 23:45:20.000000000 -0400 +++ ./DualCoding/BrickData.cc 2007-11-11 18:57:20.000000000 -0500 @@ -19,6 +19,7 @@ #include "ShapePoint.h" #include "Region.h" +using namespace std; namespace DualCoding { @@ -96,15 +97,15 @@ //! Transformations. (Virtual in BaseData.) -void BrickData::applyTransform(const NEWMAT::Matrix& Tmat) { - GFL.applyTransform(Tmat); - GFR.applyTransform(Tmat); - GBL.applyTransform(Tmat); - GBR.applyTransform(Tmat); - TFL.applyTransform(Tmat); - TFR.applyTransform(Tmat); - TBL.applyTransform(Tmat); - TBR.applyTransform(Tmat); +void BrickData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + GFL.applyTransform(Tmat,newref); + GFR.applyTransform(Tmat,newref); + GBL.applyTransform(Tmat,newref); + GBR.applyTransform(Tmat,newref); + TFL.applyTransform(Tmat,newref); + TFR.applyTransform(Tmat,newref); + TBL.applyTransform(Tmat,newref); + TBR.applyTransform(Tmat,newref); } void BrickData::projectToGround(const NEWMAT::Matrix& camToBase, @@ -129,7 +130,8 @@ TBR.setCoords(GBR.coordX(), GBR.coordY(), GBR.coordZ() + BRHeight); centroid = (GFL + GFR + GBL + GBR)/4; centroid.setCoords(centroid.coordX(), centroid.coordY(), brickHeight/2); - std::cout<<"New centroid: ("< #include -#include #include "Shared/newmat/newmat.h" @@ -74,7 +73,7 @@ virtual void printParams() const; //! Transformations. (Virtual in BaseData.) - void applyTransform(const NEWMAT::Matrix& Tmat); + void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); //! Project to ground virtual void projectToGround(const NEWMAT::Matrix& camToBase, @@ -90,9 +89,9 @@ std::vector > blobs2, std::vector > blobs3); - static Shape extractBrick(ShapeSpace& space, vector > &blobs); + static Shape extractBrick(ShapeSpace& space, std::vector > &blobs); - static vector findOrthogonalBoundingBox(ShapeSpace& space, Shape blob, Point centroid, Shape parallel); + static std::vector findOrthogonalBoundingBox(ShapeSpace& space, Shape blob, Point centroid, Shape parallel); private: //! Render into a sketch space and return reference. (Private.) Sketch* render() const; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BrickOps.cc ./DualCoding/BrickOps.cc --- ../Tekkotsu_3.0/DualCoding/BrickOps.cc 2006-08-10 23:19:53.000000000 -0400 +++ ./DualCoding/BrickOps.cc 2007-11-11 18:57:20.000000000 -0500 @@ -1,6 +1,8 @@ #include "BrickOps.h" #include "visops.h" +using namespace std; + namespace DualCoding { /* Begin functionality for distance-from-center methods of finding the corners of a blob*/ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BrickOps.h ./DualCoding/BrickOps.h --- ../Tekkotsu_3.0/DualCoding/BrickOps.h 2006-08-10 23:19:53.000000000 -0400 +++ ./DualCoding/BrickOps.h 2007-11-11 18:57:20.000000000 -0500 @@ -25,19 +25,19 @@ void applyGaussian(float x[], float gx[], int len); - float getBoundingQuadrilateralScore(BlobData &blob, vector& corners, Sketch edgeImage, + float getBoundingQuadrilateralScore(BlobData &blob, std::vector& corners, Sketch edgeImage, int& borderCount, ShapeSpace &space); float getBoundingQuadrilateralInteriorPointRatio(BlobData &blob, - vector& corners, + std::vector& corners, ShapeSpace &space); - float getQuadrilateralArea(vector& corners); + float getQuadrilateralArea(std::vector& corners); - int countBorderPixelFit(BlobData &blob, const vector &corners, + int countBorderPixelFit(BlobData &blob, const std::vector &corners, Sketch edges, ShapeSpace &space); - int pickMove(vector scores, float weight); + int pickMove(std::vector scores, float weight); } #endif /* _BRICK_OPS_H_ */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/DualCoding.h ./DualCoding/DualCoding.h --- ../Tekkotsu_3.0/DualCoding/DualCoding.h 2006-07-21 13:57:47.000000000 -0400 +++ ./DualCoding/DualCoding.h 2007-11-09 14:01:16.000000000 -0500 @@ -5,9 +5,9 @@ #define LOADED_DualCoding_h_ //! Dual coding vision representations (Sketches and Shapes) +/*! For tutorial, see http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/vr-intro.shtml */ namespace DualCoding {} -#include "Measures.h" #include "ShapeTypes.h" #include "SketchTypes.h" @@ -15,61 +15,30 @@ #include "ShapeSpace.h" #include "ShapeFuns.h" -#include "SketchDataRoot.h" -#include "SketchData.h" -#include "SketchPoolRoot.h" -#include "SketchPool.h" #include "Sketch.h" #include "SketchIndices.h" #include "Region.h" #include "visops.h" -#include "Point.h" -#include "EndPoint.h" - -#include "BaseData.h" #include "ShapeRoot.h" - -#include "LineData.h" #include "ShapeLine.h" - -#include "EllipseData.h" #include "ShapeEllipse.h" - -#include "PointData.h" #include "ShapePoint.h" - -#include "AgentData.h" #include "ShapeAgent.h" - -#include "SphereData.h" #include "ShapeSphere.h" - -#include "BlobData.h" #include "ShapeBlob.h" - -#include "PolygonData.h" #include "ShapePolygon.h" - -#include "BrickData.h" #include "ShapeBrick.h" - -#include "PyramidData.h" #include "ShapePyramid.h" +#include "ShapeLocalizationParticle.h" -#include "ViewerConnection.h" #include "VisualRoutinesStateNode.h" -#include "VisualRoutinesBehavior.h" // this must preceed mapbuilders, pilot and lookout -#include "VRmixin.h" +#include "VisualRoutinesBehavior.h" // this must precede mapbuilders, pilot and lookout -#include "LookoutRequests.h" #include "Lookout.h" -#include "MapBuilderRequests.h" #include "MapBuilder.h" #include "Pilot.h" -#include "Particle.h" -#include "ParticleShapes.h" -#include "ParticleFilter.h" +#include "PFShapeSLAM.h" #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/EllipseData.cc ./DualCoding/EllipseData.cc --- ../Tekkotsu_3.0/DualCoding/EllipseData.cc 2006-08-02 17:27:13.000000000 -0400 +++ ./DualCoding/EllipseData.cc 2007-11-11 18:57:20.000000000 -0500 @@ -6,7 +6,7 @@ #include "BaseData.h" // superclass #include "Point.h" // Point data member -#include "Measures.h" // coordinate_t; AngPi data member +#include "Shared/Measures.h" // coordinate_t; AngPi data member #include "ShapeTypes.h" // ellipseDataType #include "SketchSpace.h" @@ -20,13 +20,16 @@ #include "EllipseData.h" #include "ShapeEllipse.h" +using namespace std; + namespace DualCoding { inline int round(float x) { return (int) ceil((double)x-0.5f); } -EllipseData::EllipseData(ShapeSpace& _space, const Point &c) + EllipseData::EllipseData(ShapeSpace& _space, const Point &c, + const float _semimajor, const float _semiminor, const float _orientation) : BaseData(_space, getStaticType()), - center_pt(c), semimajor(0), semiminor(0), orientation(0) + center_pt(c), semimajor(_semimajor), semiminor(_semiminor), orientation(_orientation) { center_pt.setRefFrameType(getRefFrameType()); mobile = ELLIPSE_DATA_MOBILE; } @@ -65,22 +68,14 @@ } //! Print information about this shape. (Virtual in BaseData.) -void -EllipseData::printParams() const { - cout << "Type = " << getTypeName(); - cout << "Shape ID = " << getId() << endl; - cout << "Parent ID = " << getParentId() << endl; - - // Print critical points. - cout << endl; - cout << "center{" << centerPt().coordX() << ", " << centerPt().coordY() << "}" << endl; - - cout << "semimajor = " << getSemimajor() << endl; - cout << "semiminor = " << getSemiminor() << endl; - cout << "orientation = " << getOrientation() << endl; - printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue); - cout << "mobile = " << isMobile() << endl; - cout << "viewable = " << isViewable() << endl; +void EllipseData::printParams() const { + cout << "Type = " << getTypeName() << " ID=" << getId() << " ParentID=" << getParentId() << endl; + printf(" color = %d %d %d\n",getColor().red,getColor().green,getColor().blue); + cout << " center = " << centerPt() << endl; + cout << " semimajor = " << getSemimajor() + << ", semiminor = " << getSemiminor() + << ", orientation = " << getOrientation() << endl; + cout << " mobile = " << getMobile() << ", viewable = " << isViewable() << endl; } pair EllipseData::findFeaturePoints() const { @@ -101,12 +96,12 @@ } //! Transformations. (Virtual in BaseData.) -void EllipseData::applyTransform(const NEWMAT::Matrix& Tmat) { +void EllipseData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { pair featurePts = findFeaturePoints(); - center_pt.applyTransform(Tmat); + center_pt.applyTransform(Tmat,newref); // orientation = orientation - (AngTwoPi)atan2(Tmat(1,2),Tmat(1,1)); - featurePts.first.applyTransform(Tmat); - featurePts.second.applyTransform(Tmat); + featurePts.first.applyTransform(Tmat,newref); + featurePts.second.applyTransform(Tmat,newref); updateProperties(featurePts.first, featurePts.second); } @@ -155,7 +150,7 @@ { const float AREA_TOLERANCE = 0.5; const int REGION_THRESH = 25; - NEW_SKETCH_N(labels,usint,visops::oldlabelcc(sketch,visops::EightWayConnect)); + NEW_SKETCH_N(labels,uint,visops::oldlabelcc(sketch,visops::EightWayConnect)); list regionlist = Region::extractRegions(labels,REGION_THRESH); std::vector > ellipses; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/EllipseData.h ./DualCoding/EllipseData.h --- ../Tekkotsu_3.0/DualCoding/EllipseData.h 2006-05-09 18:37:55.000000000 -0400 +++ ./DualCoding/EllipseData.h 2007-11-11 18:57:20.000000000 -0500 @@ -9,7 +9,7 @@ #include "BaseData.h" // superclass #include "Point.h" // Point data member -#include "Measures.h" // coordinate_t; AngPi data member +#include "Shared/Measures.h" // coordinate_t; AngPi data member namespace DualCoding { @@ -29,7 +29,7 @@ public: //! Constructor - EllipseData(ShapeSpace& _space, const Point &c); + EllipseData(ShapeSpace& _space, const Point &c, const float _semimajor=25, const float _semiminor=15, const float _orientation=0); static ShapeType_t getStaticType() { return ellipseDataType; } @@ -40,7 +40,7 @@ void setCentroidPt(const Point& other) { center_pt.setCoords(other); } //! finds points where semiminor or semimajor axis touchs the circumference of ellipse - pair findFeaturePoints() const; + std::pair findFeaturePoints() const; //! updates major/minor axis and orientation from feature points void updateProperties(const Point& minorPt, const Point& majorPt); @@ -60,7 +60,7 @@ virtual void printParams() const; //! Transformations. (Virtual in BaseData.) - void applyTransform(const NEWMAT::Matrix& Tmat); + void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); //! Project to ground virtual void projectToGround(const NEWMAT::Matrix& camToBase, diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/EndPoint.h ./DualCoding/EndPoint.h --- ../Tekkotsu_3.0/DualCoding/EndPoint.h 2006-02-12 00:32:01.000000000 -0500 +++ ./DualCoding/EndPoint.h 2007-01-25 14:07:30.000000000 -0500 @@ -2,7 +2,7 @@ #ifndef _ENDPOINT_H_ #define _ENDPOINT_H_ -#include "Measures.h" +#include "Shared/Measures.h" #include "Point.h" namespace DualCoding { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/LineData.cc ./DualCoding/LineData.cc --- ../Tekkotsu_3.0/DualCoding/LineData.cc 2006-10-03 19:24:05.000000000 -0400 +++ ./DualCoding/LineData.cc 2007-11-11 18:57:20.000000000 -0500 @@ -18,6 +18,8 @@ #include "LineData.h" #include "ShapeLine.h" +using namespace std; + namespace DualCoding { DATASTUFF_CC(LineData); @@ -181,25 +183,26 @@ //! Print information about this shape. (Virtual in BaseData.) void LineData::printParams() const { cout << "Type = " << getTypeName() << " ID=" << getId() << " ParentID=" << getParentId() << endl; - cout << "end1{" << end1Pt().coordX() << ", " << end1Pt().coordY() << "}"; - cout << " active=" << end1Pt().isActive(); - cout << " valid=" << end1Pt().isValid() << endl; + cout << " end1{" << end1Pt().coordX() << ", " << end1Pt().coordY() << "}" + << " active=" << end1Pt().isActive() + << " valid=" << end1Pt().isValid() << endl; - cout << "end2{" << end2Pt().coordX() << ", " << end2Pt().coordY() << "}"; - cout << " active=" << end2Pt().isActive(); - cout << " valid=" << end2Pt().isValid() << std::endl; + cout << " end2{" << end2Pt().coordX() << ", " << end2Pt().coordY() << "}" + << " active=" << end2Pt().isActive() + << " valid=" << end2Pt().isValid() << std::endl; - cout << "rho_norm=" << rho_norm << " theta_norm=" << theta_norm; - cout << " orientation=" << getOrientation() - << " length=" << getLength() << endl; + cout << " rho_norm=" << rho_norm + << ", theta_norm=" << theta_norm + << ", orientation=" << getOrientation() + << ", length=" << getLength() << endl; - printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue); + printf(" color = %d %d %d\n",getColor().red,getColor().green,getColor().blue); - cout << " mobile=" << isMobile() << endl; - cout << " viewable=" << isViewable() << endl; + cout << " mobile=" << getMobile() + << ", viewable=" << isViewable() << endl; vector abc = lineEquation_abc(); - printf("equ = %f %f %f\n",abc[0],abc[1],abc[2]); + printf(" equ = %f %f %f\n",abc[0],abc[1],abc[2]); } void LineData::printEnds() const { @@ -212,12 +215,12 @@ -//! Transformations. -//@{ +// *** Transformations. *** // + //! Apply a transformation to this shape. -void LineData::applyTransform(const NEWMAT::Matrix& Tmat) { - end1Pt().applyTransform(Tmat); - end2Pt().applyTransform(Tmat); +void LineData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + end1Pt().applyTransform(Tmat,newref); + end2Pt().applyTransform(Tmat,newref); update_derived_properties(); } @@ -228,8 +231,8 @@ update_derived_properties(); } -//! Logical endpoints -//@{ + +// *** Logical endpoints *** // EndPoint& LineData::leftPt() { return end1Pt().isLeftOf(end2Pt()) ? end1_pt : end2_pt; } EndPoint& LineData::rightPt() { return end1Pt().isLeftOf(end2Pt()) ? end2_pt : end1_pt; } @@ -312,6 +315,22 @@ else return otherline->end2Pt(); } +Shape LineData::firstPtShape() { + Shape result(new PointData(*space, firstPt())); + result->setName("firstPt"); + result->inheritFrom(*this); + result->setViewable(false); + return result; +} + +Shape LineData::secondPtShape() { + Shape result(new PointData(*space, secondPt())); + result->setName("secondPt"); + result->inheritFrom(*this); + result->setViewable(false); + return result; +} + coordinate_t LineData::firstPtCoord() const { return isNotVertical() ? const_cast(this)->firstPt().coordX() : @@ -336,9 +355,8 @@ secondPt(otherline).coordY(); } -//@} -//! Functions to set endpoints. +// *** Functions to set endpoints. *** // void LineData::setEndPts(const EndPoint& _end1_pt, const EndPoint& _end2_pt) { end1_pt.setCoords(_end1_pt); @@ -355,8 +373,7 @@ } -//! Properties functions. -//@{ +// *** Properties functions. *** // std::pair LineData::lineEquation_mb() const { float m; @@ -408,9 +425,8 @@ return(abc); } -//@} - //! Determine parameters a, b, c satisfying the equation ax + by = c. +//! Determine parameters a, b, c satisfying the equation ax + by = c. std::vector LineData::lineEquation_abc() const { float dx = end2Pt().coordX() - end1Pt().coordX(); float dy = end2Pt().coordY() - end1Pt().coordY(); @@ -446,11 +462,10 @@ return(abc); } -//@} -//! Functions to set values dealing with orientation. -//@{ +// *** Functions to set values dealing with orientation. *** // + void LineData::update_derived_properties() { rho_norm = perpendicularDistanceFrom(origin_pt); const vector abc = lineEquation_abc(); @@ -491,8 +506,8 @@ */ -//! These functions are true based on line length. -//@{ +// *** These functions are true based on line length. *** // + bool LineData::isLongerThan(const Shape& other) const { return length > other->length; } @@ -504,7 +519,6 @@ bool LineData::isShorterThan(float ref_length) const { return length < ref_length; } -//@} bool LineData::isBetween(const Point &p, const LineData &other) const { if (getOrientation() == other.getOrientation()) { // parallel lines @@ -527,8 +541,9 @@ } } -//! Check intersection. -//{ + +// *** Check intersection. *** // + bool LineData::intersectsLine(const Shape& other) const { return intersectsLine(other.getData()); @@ -682,8 +697,8 @@ } } -//! Distance. -//{ + +// *** Distance. *** // float LineData::perpendicularDistanceFrom(const Point& otherPt) const { // NOTE that this formula is rather slow, as it involves the @@ -704,17 +719,12 @@ return(d); } -//} // ================================================== // BEGIN LINE EXTRACTION CODE // ================================================== -//!@name Line Extraction. -//@{ - - #define BEG_DIST_THRESH 2 #define END_DIST_THRESH 2 @@ -731,7 +741,7 @@ ShapeSpace &ShS = SkS.getDualSpace(); // approximate largest skel region with line - NEW_SKETCH_N(labels,usint,visops::oldlabelcc(skeleton,visops::EightWayConnect)); + NEW_SKETCH_N(labels,uint,visops::oldlabelcc(skeleton,visops::EightWayConnect)); list regions = Region::extractRegions(labels,EXTRACT_LINE_MIN_AREA); if ( regions.empty() ) { ShapeRoot invalid; // need to define a named variable to avoid warning on next line @@ -765,7 +775,7 @@ // cout << " x_normpoint=" << x_normpoint << " y_normpoint=" << y_normpoint // << " m=" << m << " b=" << b <scanHorizForEndPts(skelDist,occlusions,m,b); else @@ -802,7 +812,7 @@ PointData most_distant_pt(ShS, skelchunk.mostDistantPtFrom(ln)); // cout << "Point of split: " << most_distant_pt.getCentroid() << endl; const Sketch& point_rendering = most_distant_pt.getRendering(); - usint const clear_dist = 10; + uint const clear_dist = 10; NEW_SKETCH_N(not_too_close, bool, visops::edist(point_rendering) >= clear_dist); skeleton &= not_too_close; return extractLine(skeleton, occlusions); @@ -813,7 +823,7 @@ return ShapeRootType(invalid,LineData); } -void LineData::scanHorizForEndPts(const Sketch& skelDist, +void LineData::scanHorizForEndPts(const Sketch& skelDist, const Sketch& occlusions, float m, float b) { // Scan along the infinite line, looking for segments in the image. @@ -887,7 +897,7 @@ balanceEndPointHoriz(end2_pt,occlusions,m,b); } -void LineData::scanVertForEndPts(const Sketch& skelDist, +void LineData::scanVertForEndPts(const Sketch& skelDist, const Sketch& occlusions, float m, float b) { // Scan along the infinite line, looking for segments in the image. @@ -1021,12 +1031,11 @@ //! Clear out pixels that are on or close to this line. void LineData::clearLine(Sketch& sketch) { const Sketch& line_rendering = getRendering(); - usint const clear_dist = 5; + uint const clear_dist = 5; Sketch not_too_close = (visops::edist(line_rendering) >= clear_dist); sketch &= not_too_close; } -//@} // ================================================== @@ -1356,7 +1365,7 @@ float m = (y1 != 0) ? -(x1/y1) : BIG_SLOPE; float b = y1 - m*x1; - NEW_SKETCH_N(skelDist,usint,visops::edist(skinny)); + NEW_SKETCH_N(skelDist,uint,visops::edist(skinny)); if ( abs(m) <= 1 ) // when |slope| <= 1, scan along x, else scan along y line->scanHorizForEndPts(skelDist,occlusions,m,b); else @@ -1486,9 +1495,14 @@ abs( line1->getRhoNorm() - line2->getRhoNorm() ) <= dist_tol; } -bool LineData::IsHorizontal::operator() (const Shape &line) { +bool LineData::IsHorizontal::operator() (const Shape &line) const { const AngPi orient = line->getOrientation(); return (orient <= threshold) || (orient >= M_PI - threshold); } +bool LineData::IsVertical::operator() (const Shape &line) const { + const AngPi orient = line->getOrientation(); + return (orient >= threshold) && (orient <= M_PI - threshold); + } + } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/LineData.h ./DualCoding/LineData.h --- ../Tekkotsu_3.0/DualCoding/LineData.h 2006-09-23 23:45:20.000000000 -0400 +++ ./DualCoding/LineData.h 2007-11-11 18:57:20.000000000 -0500 @@ -4,14 +4,12 @@ #include #include -#include #include "BaseData.h" // superclass #include "EndPoint.h" // EndPoint data member -#include "Measures.h" // coordinate_t; AngPi data member #include "ShapeFuns.h" #include "ShapePoint.h" -#include "SketchTypes.h" // usint +#include "SketchTypes.h" // uint #include "Shared/mathutils.h" // deg2rad namespace DualCoding { @@ -21,6 +19,7 @@ #define EXTRACT_LINE_MIN_AREA 20 #define DEFAULT_MIN_LENGTH 4.0 +//! A line shape, with two endpoints, a length, orientation, etc. class LineData : public BaseData { private: EndPoint end1_pt; @@ -39,7 +38,7 @@ public: //! Constructor - LineData(ShapeSpace& _space, const Point &p1, const Point &p2) + LineData(ShapeSpace& _space, const EndPoint &p1, const EndPoint &p2) : BaseData(_space,getStaticType()), end1_pt(p1), end2_pt(p2), rho_norm(0), theta_norm(0), orientation(0), length(0) { update_derived_properties(); } @@ -68,10 +67,10 @@ void setInfinite(bool value=true); BoundingBox getBoundingBox() const { - return BoundingBox(min(end1_pt.coordX(),end2_pt.coordX()), - min(end1_pt.coordY(),end2_pt.coordY()), - max(end1_pt.coordX(),end2_pt.coordX()), - max(end1_pt.coordY(),end2_pt.coordY())); + return BoundingBox(std::min(end1_pt.coordX(),end2_pt.coordX()), + std::min(end1_pt.coordY(),end2_pt.coordY()), + std::max(end1_pt.coordX(),end2_pt.coordX()), + std::max(end1_pt.coordY(),end2_pt.coordY())); } //! Match lines based on their parameters. (Virtual in BaseData.) @@ -96,7 +95,7 @@ virtual void printParams() const; //! Transformations. (Virtual in BaseData.) - virtual void applyTransform(const NEWMAT::Matrix& Tmat); + virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); //! Project to ground virtual void projectToGround(const NEWMAT::Matrix& camToBase, @@ -104,7 +103,14 @@ virtual unsigned short getDimension() const { return 1; } - //! Point Access functions. + void printEnds() const; + void setEndPts(const EndPoint& _end1_pt, const EndPoint& _end2_pt); + + //!@name Point access functions. + /*! The first point of a line is the leftmost point if the line is horizontal, + else the topmost point. With an optional Shape argument, uses the current + line's orientation to pick the appropriate point of the other line. + */ //@{ EndPoint& end1Pt() { return end1_pt; } EndPoint& end2Pt() { return end2_pt; } @@ -121,38 +127,33 @@ Shape topPtShape(); Shape bottomPtShape(); - //! The first point of a line is the leftmost point if the line is horizontal, - //! else the topmost point. With an optional Shape argument, uses the current - //! line's orientation to pick the appropriate point of the other line. - //@{ EndPoint& firstPt(); EndPoint& firstPt(const Shape &otherline) const; EndPoint& secondPt(); EndPoint& secondPt(const Shape &otherline) const; + Shape firstPtShape(); + Shape secondPtShape(); + coordinate_t firstPtCoord() const; coordinate_t firstPtCoord(const Shape &otherline) const; coordinate_t secondPtCoord() const; coordinate_t secondPtCoord(const Shape &otherline) const; //@} - - void printEnds() const; - void setEndPts(const EndPoint& _end1_pt, const EndPoint& _end2_pt); - - //! Properties functions. + //!@name Properties functions //@{ float getRhoNorm() const { return rho_norm; } AngTwoPi getThetaNorm() const { return theta_norm; } AngPi getOrientation() const { return orientation; } float getLength() const { return length; } - pair lineEquation_mb() const; - vector lineEquation_abc() const; - vector lineEquation_abc_xz() const; + std::pair lineEquation_mb() const; + std::vector lineEquation_abc() const; + std::vector lineEquation_abc_xz() const; //@} -public: - + //!@name Orientation functions + //@{ bool isNotVertical() const; //!< True if line orientation is far enough from vertical bool isOverlappedWith(const LineData& otherline, int amount=0) const; // bool isRoughlyPerpendicularTo(Shape &other); @@ -160,7 +161,7 @@ //@} - //! Predicates based on line length. + //!@name Predicates based on line length //@{ bool isLongerThan(const Shape& other) const; bool isLongerThan(float ref_length) const; @@ -171,7 +172,7 @@ //! Check if point falls between the two lines bool isBetween(const Point &p, const LineData &other) const; - //! Check intersection. + //!@name Check line intersection //@{ bool intersectsLine(const Shape& other) const; bool intersectsLine(const LineData& other) const; @@ -193,16 +194,14 @@ bool pointOnLine(const Point& p); //! Distance. - //@{ float perpendicularDistanceFrom(const Point& other) const; - //@} // ================================================== // BEGIN SKETCH MANIPULATION AND LINE EXTRACTION CODE // ================================================== - //! Extraction. + //!@name Line extraction //@{ //! Extracts most prominent line from a skeletonized image. @@ -212,6 +211,7 @@ //! It's often useful to use the original sketch as an occluder static Shape extractLine(Sketch& skelsketch, const Sketch& occlusions); + //@} //! Helper functions used by extractLine(). //@{ @@ -221,17 +221,17 @@ //! Clears a line from a sketch. void clearLine(Sketch& sketch); - void scanHorizForEndPts(const Sketch& skelDist, const Sketch& occlusions, + void scanHorizForEndPts(const Sketch& skelDist, const Sketch& occlusions, float m, float b); - void scanVertForEndPts(const Sketch& skelDist, const Sketch& occlusions, + void scanVertForEndPts(const Sketch& skelDist, const Sketch& occlusions, float m, float b); void balanceEndPointHoriz(EndPoint &pt, Sketch const &occluders, float m, float b); void balanceEndPointVert(EndPoint &pt, Sketch const &occluders, float m, float b); - static vector > extractLines(Sketch const& sketch, int const num_lines=10); + static std::vector > extractLines(Sketch const& sketch, int const num_lines=10); - static vector > extractLines(Sketch const& skel, + static std::vector > extractLines(Sketch const& skel, Sketch const& occluders, int const num_lines=10); @@ -245,14 +245,16 @@ //@} - //! Comparison predicates used by shape functions + //!@name Comparison predicates used by shape functions //@{ + //! True if line1 shorter than line2 class LengthLessThan : public BinaryShapePred { public: bool operator() (const Shape &ln1, const Shape &ln2) const; }; + //! True if difference in line orientations is <= tolerance (default 20 deg) class ParallelTest : public BinaryShapePred { public: AngPi tolerance; @@ -261,6 +263,7 @@ }; + //! True if difference in line orientations is 90 deg +/- tolerance (default 20 deg) class PerpendicularTest : public BinaryShapePred { public: AngPi tolerance; @@ -269,6 +272,7 @@ }; + //! True if line orientations are within @a ang_tol (default 20 deg) and normpoints are within @a dist_tol (default 10 units) class ColinearTest : public BinaryShapePred { public: AngPi ang_tol; @@ -278,14 +282,23 @@ bool operator() (const Shape &line1, const Shape &ln2) const; }; + //! Predicate returns true if line orientation is within @a threshold of horizontal class IsHorizontal : public UnaryShapePred { public: IsHorizontal(AngPi thresh=M_PI/6) : UnaryShapePred(), threshold(thresh) {} - bool operator() (const Shape &line); + bool operator() (const Shape &line) const; private: AngPi threshold; }; + //! Predicate returns true if line orientation is within threshold of vertical + class IsVertical : public UnaryShapePred { + public: + IsVertical(AngPi thresh=M_PI/3) : UnaryShapePred(), threshold(thresh) {} + bool operator() (const Shape &line) const; + private: + AngPi threshold; + }; //@} @@ -295,7 +308,7 @@ private: static const int extractorGapTolerance = 8; - //! Rendering. + //!@name Rendering. //@{ //! Render into a sketch space and return reference. diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/LocalizationParticleData.cc ./DualCoding/LocalizationParticleData.cc --- ../Tekkotsu_3.0/DualCoding/LocalizationParticleData.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/LocalizationParticleData.cc 2007-11-11 18:57:20.000000000 -0500 @@ -0,0 +1,80 @@ +//-*-c++-*- + +#include + +#include "Sketch.h" +#include "LocalizationParticleData.h" +#include "ShapeLocalizationParticle.h" + +using namespace std; + +namespace DualCoding { + +LocalizationParticleData::LocalizationParticleData(ShapeSpace& _space, + const Point &_location, + const AngTwoPi _orientation, + const float _weight) : + BaseData(_space, getStaticType()), location(_location), orientation(_orientation), weight(_weight) {} + +LocalizationParticleData::LocalizationParticleData(ShapeSpace &_space, + const PFShapeLocalization::particle_type& particle) : + BaseData(_space, getStaticType()), + location(Point(particle.x,particle.y,0,_space.getRefFrameType())), + orientation(particle.theta), + weight(particle.weight) +{} + +LocalizationParticleData::LocalizationParticleData(const LocalizationParticleData &other) : + BaseData(other), location(other.location), orientation(other.orientation), weight(other.weight) {} + + +DATASTUFF_CC(LocalizationParticleData); + +bool LocalizationParticleData::updateParams(const ShapeRoot&, bool) { return true; } + +void LocalizationParticleData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + location.applyTransform(Tmat,newref); + orientation += atan2(Tmat(1,2),Tmat(1,1)); +} + +void LocalizationParticleData::printParams() const { + cout << "Type = " << getTypeName() << " ID=" << getId() << " ParentID=" << getParentId() << endl; + cout << " location{" << location.coordX() << ", " << location.coordY() << "}" + << ", orientation = " << orientation << endl; +} + +bool LocalizationParticleData::isMatchFor(const ShapeRoot& other) const { + if (!(isSameTypeAs(other) && isSameColorAs(other))) + return false; + const Shape& other_particle = ShapeRootTypeConst(other,LocalizationParticleData); + float dist = location.distanceFrom(other_particle->getCentroid()); + return dist < 20; // *** DST hack +} + +LocalizationParticleData& LocalizationParticleData::operator=(const LocalizationParticleData &other) { + if ( this != &other ) { + BaseData::operator=(other); + location = other.location; + orientation = other.orientation; + weight = other.weight; + } + return *this; +} + +//! Render into a sketch space and return a pointer. (Private.) +Sketch* LocalizationParticleData::render() const { + SketchSpace &SkS = space->getDualSpace(); + NEWMAT::ColumnVector ctr(getCentroid().getCoords()); + SkS.applyTmat(ctr); + int const cx = int(ctr(1)); + int const cy = int(ctr(2)); + Sketch& draw_result = + *new Sketch(SkS, "render("+getName()+")"); + draw_result = false; + draw_result(cx,cy) = true; + return &draw_result; +} + + +} // namespace + diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/LocalizationParticleData.h ./DualCoding/LocalizationParticleData.h --- ../Tekkotsu_3.0/DualCoding/LocalizationParticleData.h 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/LocalizationParticleData.h 2007-03-28 05:19:18.000000000 -0400 @@ -0,0 +1,74 @@ +//-*-c++-*- +#ifndef _LOCALIZATIONPARTICLEDATA_H_ +#define _LOCALIZATIONPARTICLEDATA_H_ + +#include "Shared/Measures.h" // coordinate_t; AngPi data member +#include "Shared/newmat/newmat.h" + +#include "BaseData.h" // superclass +#include "PFShapeLocalization.h" +#include "Point.h" // Point data member +#include "ShapeTypes.h" // localizationParticleDataType + +namespace DualCoding { + +class ShapeRoot; +class SketchSpace; +template class Sketch; + +class LocalizationParticleData : public BaseData { +private: + Point location; + AngTwoPi orientation; + float weight; + +public: + + //! Constructor + LocalizationParticleData(ShapeSpace& _space, const Point &_location, const AngTwoPi _orientation, const float _weight=0); + + LocalizationParticleData(ShapeSpace &space, const PFShapeLocalization::particle_type& particle); + + //! Copy constructor + LocalizationParticleData(const LocalizationParticleData &other); + + static ShapeType_t getStaticType() { return localizationParticleDataType; } + + DATASTUFF_H(LocalizationParticleData); + + //! Centroid. (Virtual in BaseData.) + virtual Point getCentroid() const { return location; } + void setCentroid(const Point& other) { location.setCoords(other); } + + AngTwoPi getOrientation() const { return orientation; } + void setOrientation(const AngTwoPi _orientation) {orientation = _orientation; } + + float getWeight() const { return weight;} + void setWeight(float w) { weight=w; } + + virtual bool isMatchFor(const ShapeRoot& other) const; + + virtual bool updateParams(const ShapeRoot&, bool force=false); + + //! Print information about this shape. (Virtual in BaseData.) + virtual void printParams() const; + + virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); + + virtual void projectToGround(const NEWMAT::Matrix&, + const NEWMAT::ColumnVector&) {} + + virtual unsigned short getDimension() const { return 2; } + + LocalizationParticleData& operator=(const LocalizationParticleData &other); + +private: + //! Render into a sketch space and return pointer. (Private.) + virtual Sketch* render() const; + + +}; + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Lookout.cc ./DualCoding/Lookout.cc --- ../Tekkotsu_3.0/DualCoding/Lookout.cc 2006-10-02 14:49:16.000000000 -0400 +++ ./DualCoding/Lookout.cc 2007-11-18 01:47:01.000000000 -0500 @@ -4,131 +4,494 @@ #include "Events/LocomotionEvent.h" #include "Events/LookoutEvents.h" #include "Events/VisionObjectEvent.h" -#include "Motion/HeadPointerMC.h" -#include "Motion/PostureMC.h" -#include "Motion/MMAccessor.h" -#include "Motion/MotionSequenceMC.h" -#include "Motion/MotionManager.h" #include "Shared/ProjectInterface.h" +#include "Shared/mathutils.h" #include "Shared/WorldState.h" #include "Vision/RegionGenerator.h" #include "VRmixin.h" #include "LookoutRequests.h" #include "Lookout.h" +#include "MapBuilder.h" +#include "ShapeBlob.h" +#include "ShapeLine.h" +#include "ShapePolygon.h" -namespace DualCoding { - -// some stuff for convenience -typedef SegmentedColorGenerator::color_class_state color_class_state; - -inline float getIR() { -#ifdef TGT_ERS7 - return state->sensors[NearIRDistOffset]; -#else - return state->sensors[IRDistOffset]; -#endif -} +using namespace mathutils; +using namespace std; +namespace DualCoding { Lookout::Lookout() : BehaviorBase("Lookout"), - pointer_id(MotionManager::invalid_MC_ID), - sequence_id(MotionManager::invalid_MC_ID), - requests(), curReq(NULL), landmarkInView(true), - idCounter(0) + pixelHistograms(VRmixin::camSkS.getNumPixels()), distanceSamples(), + pointer_id(MotionManager::invalid_MC_ID), + posture_id(MotionManager::invalid_MC_ID), + sequence_id(MotionManager::invalid_MC_ID), + requests(), curReq(NULL), curPAR(NULL), successSave(false), + trackerState(inactive), idCounter(0) {} void Lookout::DoStart() { BehaviorBase::DoStart(); + SharedObject head_mc; + SharedObject posture_mc; + SharedObject mseq_mc; + pointer_id = motman->addPersistentMotion(head_mc,MotionManager::kIgnoredPriority); + posture_id = motman->addPersistentMotion(posture_mc,MotionManager::kIgnoredPriority); + sequence_id = motman->addPersistentMotion(mseq_mc,MotionManager::kIgnoredPriority); + cout << "Lookout starting up: pointer_id=" << pointer_id + << " posture_id=" << posture_id + << " sequence_id=" << sequence_id << endl; + erouter->addListener(this,EventBase::motmanEGID,pointer_id,EventBase::statusETID); + erouter->addListener(this,EventBase::motmanEGID,posture_id,EventBase::statusETID); + erouter->addListener(this,EventBase::motmanEGID,sequence_id,EventBase::statusETID); } void Lookout::DoStop() { - curReq = NULL; - while (!requests.empty()) { - if (requests.front() != NULL) - delete requests.front(); - requests.pop(); - } motman->removeMotion(pointer_id); pointer_id = MotionManager::invalid_MC_ID; + motman->removeMotion(posture_id); + posture_id = MotionManager::invalid_MC_ID; motman->removeMotion(sequence_id); sequence_id = MotionManager::invalid_MC_ID; + curReq = NULL; + curPAR = NULL; + while (!requests.empty()) { + delete requests.front(); + requests.pop(); + } BehaviorBase::DoStop(); } - /* -vector Lookout::getVisionObjectData() { +vector Lookout::groundSearchPoints() { + vector gazePts; + gazePts.push_back(Point( 200, -250, -100, egocentric)); + gazePts.push_back(Point( 800,-1000, -100, egocentric)); + gazePts.push_back(Point(1200, 0, -100, egocentric)); + gazePts.push_back(Point( 800, 1000, -100, egocentric)); + gazePts.push_back(Point( 200, 250, -100, egocentric)); + gazePts.push_back(Point( 200, 0, -100, egocentric)); + gazePts.push_back(Point( 400, 0, -100, egocentric)); + gazePts.push_back(Point( 800, 0, -100, egocentric)); + return gazePts; +} +unsigned int Lookout::executeRequest(const LookoutRequest &req) { + switch (req.getHeadMotionType()) { + case LookoutRequest::noMotion: + case LookoutRequest::pointAt: + pushRequest(req); + break; + case LookoutRequest::scan: + pushRequest(req); + break; + case LookoutRequest::track: + pushRequest(req); + break; + case LookoutRequest::search: + pushRequest(req); + break; + default: + cout << "Lookout::executeRequest: unknown request type " << req.getHeadMotionType() << endl; + }; + const unsigned int reqid = requests.back()->requestID = ++idCounter; + executeRequest(); + return reqid; } -vector Lookout::getIRData() { +void Lookout::executeRequest() { + if ( curReq != NULL || requests.empty() ) + return; + curReq = requests.front(); + cout << "Lookout executing " << LookoutRequest::headMotionTypeNames[curReq->getHeadMotionType()] + << " request, id=" << curReq->requestID << endl; + curPAR = dynamic_cast(curReq); + + // If we're going to be computing pixel or distance modes, clear the bins first + if ( curPAR != NULL && curPAR->numSamples > 1 ) + switch ( curPAR->getResultType() ) { + case LookoutRequest::imageResult: + for ( unsigned int i=0; i 0) distanceSamples.pop(); + break; +#endif + default: + break; + } + // now dispatch on the head motion type + trackerState = inactive; + switch (curReq->getHeadMotionType()) { + case LookoutRequest::noMotion: + erouter->addTimer(this, settle_timer, curPAR->motionSettleTime, false); + break; + case LookoutRequest::pointAt: + moveHeadToPoint(); + break; + case LookoutRequest::scan: + setupScan(); + break; + case LookoutRequest::track: + setupTrack(); + break; + case LookoutRequest::search: + setupSearch(); + break; + default: + cout << "Lookout::executeRequest(): unknown request " << curReq->getHeadMotionType() << endl; + break; + }; } - */ -void Lookout::processScan(const EventBase& event) { +void Lookout::relax() { + motman->setPriority(pointer_id,MotionManager::kIgnoredPriority); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); + motman->setPriority(sequence_id,MotionManager::kIgnoredPriority); +} + +void Lookout::moveHeadToPoint() { + Point pt = curPAR->gazePt; + switch ( pt.getRefFrameType() ) { + case unspecified: + case camcentric: + cout << "Warning: Lookout gaze point " << curPAR->gazePt << " reference frame must be egocentric or allocentric" << endl; + pt.setRefFrameType(egocentric); + case egocentric: + break; + case allocentric: + pt.applyTransform(VRmixin::mapBuilder.worldToLocalTranslateMatrix,egocentric); + pt.applyTransform(VRmixin::mapBuilder.worldToLocalRotateMatrix,egocentric); + } + // point head based on Camera or IR reference frame + switch ( curPAR->getResultType() ) { + case LookoutRequest::noResult: + case LookoutRequest::imageResult: { + successSave = MMAccessor(pointer_id)->lookAtPoint(pt.coordX(),pt.coordY(),pt.coordZ()); + motman->setPriority(pointer_id,MotionManager::kStdPriority); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); + motman->setPriority(sequence_id,MotionManager::kIgnoredPriority); + } + break; +#ifdef TGT_HAS_IR_DISTANCE + case LookoutRequest::distanceResult: { +#ifdef TGT_ERS7 + successSave = MMAccessor(posture_id)->solveLinkVector(pt.coords,NearIRFrameOffset,Kinematics::pack(0,0,1)); +#else + successSave = MMAccessor(posture_id)->solveLinkVector(pt.coords,IRFrameOffset,Kinematics::pack(0,0,1)); +#endif + motman->setPriority(posture_id,MotionManager::kStdPriority); + motman->setPriority(pointer_id,MotionManager::kIgnoredPriority); + motman->setPriority(sequence_id,MotionManager::kIgnoredPriority); + } + break; +#endif + case LookoutRequest::interestPoints: + cout << "Lookout error: this scan type cannot return interest points." << endl; + return; + } +} + +void Lookout::processEvent(const EventBase& event) { + if ( curReq == NULL ) { + if ( event.getGeneratorID() == EventBase::motmanEGID && + event.getTypeID() == EventBase::statusETID ) + return; // harmless motman status event from startup + else { + cout << "Error: Lookout received an event when not executing a request:\n"; + cout << " " << event.getDescription(true,3) << endl; + return; + } + } + + switch (curReq->getHeadMotionType()) { + case LookoutRequest::noMotion: + case LookoutRequest::pointAt: + processPointAtEvent(event); + break; + case LookoutRequest::scan: + processScanEvent(event); + break; + case LookoutRequest::track: + processTrackEvent(event); + break; + case LookoutRequest::search: + processSearchEvent(event); + break; + default: + cout << "Lookout::processEvent: unknown head motion request type: " + << curReq->getHeadMotionType() << ", event: " << event.getDescription() << endl; + break; + }; +} + +void Lookout::processPointAtEvent(const EventBase& event) { + switch (event.getGeneratorID()) { + case EventBase::motmanEGID: + if ( event.getSourceID() == pointer_id || event.getSourceID() == posture_id ) { + // head motion complete, now wait for head to settle + motman->setPriority(event.getSourceID(), MotionManager::kBackgroundPriority); + erouter->addTimer(this, settle_timer, curPAR->motionSettleTime, false); + } + break; + + case EventBase::timerEGID: + if (event.getSourceID() == settle_timer || event.getSourceID() == sample_timer) { + switch (curReq->getResultType()) { + case LookoutRequest::imageResult: + erouter->addListener(this, EventBase::visRegionEGID, + ProjectInterface::visRegionSID,EventBase::statusETID); + break; +#ifdef TGT_HAS_IR_DISTANCE + case LookoutRequest::distanceResult: + erouter->addListener(this, EventBase::sensorEGID, SensorSrcID::UpdatedSID); + break; +#endif + case LookoutRequest::noResult: + default: + requestComplete(successSave); + break; + }; + } + break; + + case EventBase::visRegionEGID: + erouter->removeListener(this, EventBase::visRegionEGID); + VRmixin::camSkS.clear(); + VRmixin::camShS.clear(); + curPAR->image.bind((curPAR->sketchFunc)()); + ++curPAR->sampleCounter; + if ( curPAR->numSamples == 1 || findPixelModes() == true ) { + curPAR->toBaseMatrix = kine->jointToBase(curPAR->joint); + requestComplete(successSave); + } + else + erouter->addTimer(this, sample_timer, curPAR->sampleInterval, false); + break; + + case EventBase::sensorEGID: + erouter->removeListener(this, EventBase::sensorEGID); +#ifdef TGT_HAS_IR_DISTANCE + if ( findDistanceMode() == true ) { + curPAR->toBaseMatrix = kine->jointToBase(curPAR->joint); + requestComplete(successSave); + } else +#endif + erouter->addTimer(this, sample_timer, curPAR->sampleInterval, false); + break; + + default: + cout << "Lookout::processPointAtEvent: unknown event " << event.getDescription() << endl; + break; + }; +} + +bool Lookout::findPixelModes() { + // update our counts using the new sammple + for (size_t i = 0; iimage[i]]++; + if ( curPAR->sampleCounter < curPAR->numSamples ) + return false; + // we have enough samples; compute the mode + for (size_t i = 0; i::const_iterator it = pixelHistograms[i].begin(); + it != pixelHistograms[i].end(); it++) + if (it->second > maxCount) { + maxCount = it->second; + maxChar = it->first; + } + curPAR->image[i] = maxChar; + } + return true; +} + +#ifdef TGT_HAS_IR_DISTANCE +float Lookout::getDistanceModeValue() { + int const npops = distanceSamples.size() / 2; + for ( int i=0; isensors[FarIRDistOffset] > 400 ) // far IR goes 200-1500; near IR goes 50-500 + return state->sensors[FarIRDistOffset]; + else + return state->sensors[NearIRDistOffset]; +#else + return state->sensors[IRDistOffset]; +#endif +} + +bool Lookout::findDistanceMode() { + distanceSamples.push(getIR()); + return (int)distanceSamples.size() < curPAR->numSamples; +} +#endif // TGT_HAS_IR_DISTANCE + +void Lookout::requestComplete(bool success) { + cout << "Lookout request " << curReq->requestID << " complete." << endl; + erouter->removeTimer(this); + erouter->removeListener(this,EventBase::sensorEGID); + erouter->removeListener(this,EventBase::visSegmentEGID); + erouter->removeListener(this,EventBase::visRegionEGID); + erouter->removeListener(this,EventBase::visObjEGID); + LookoutRequest *saveReq = curReq; + curReq = NULL; + curPAR = NULL; + requests.pop(); + switch ( saveReq->getHeadMotionType() ) { + case LookoutRequest::noMotion: + case LookoutRequest::pointAt: + switch ( saveReq->getResultType() ) { + case LookoutRequest::noResult: + erouter->postEvent(LookoutPointAtEvent(success,static_cast(saveReq)->toBaseMatrix, + EventBase::lookoutEGID, saveReq->requestID, EventBase::deactivateETID)); + break; + case LookoutRequest::imageResult: + erouter->postEvent(LookoutSketchEvent(success,static_cast(saveReq)->image, + static_cast(saveReq)->toBaseMatrix, + EventBase::lookoutEGID, saveReq->requestID, EventBase::deactivateETID)); + break; +#ifdef TGT_HAS_IR_DISTANCE + case LookoutRequest::distanceResult: + erouter->postEvent(LookoutIREvent(success,getDistanceModeValue(), static_cast(saveReq)->toBaseMatrix, + EventBase::lookoutEGID, saveReq->requestID, EventBase::deactivateETID)); + break; +#endif + default: + cout << "Lookout::requestComplete(): Unknown type returned by getResultType()\n"; + } + break; + + case LookoutRequest::scan: + erouter->postEvent(LookoutScanEvent(static_cast(saveReq)->tasks, + EventBase::lookoutEGID,saveReq->requestID, EventBase::deactivateETID)); + break; + + case LookoutRequest::track: + erouter->postEvent(EventBase(EventBase::lookoutEGID,saveReq->requestID, EventBase::deactivateETID)); + break; + + case LookoutRequest::search: { + Sketch image(VRmixin::sketchFromSeg()); +#ifdef TGT_HAS_CAMERA + const NEWMAT::Matrix camToBase = kine->jointToBase(CameraFrameOffset); +#else + NEWMAT::Matrix camToBase(4,4); + camToBase << ROBOOP::fourbyfourident; +#endif + erouter->postEvent(LookoutSketchEvent(success, image, camToBase, + EventBase::lookoutEGID, saveReq->requestID, EventBase::deactivateETID)); + break; + } + + default: + cout << "Lookout::requestComplete(): Unknown head motion type\n"; + } + + // The postEvent above may have led to a series of functions + // returning and eventually shutting down the Lookout or starting + // another request, so make sure we're still in the same state + // before proceeding. + delete saveReq; + if ( curReq == NULL && !requests.empty() ) + executeRequest(); +} + +typedef SegmentedColorGenerator::color_class_state color_class_state; + +void Lookout::storeVisionRegionDataTo(vector& data, const set& colors, int minArea) { + const unsigned char *img = + ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0); + const color_class_state *regions = reinterpret_cast (img); + for (set::const_iterator it = colors.begin(); + it != colors.end(); it++) + for (int i = 0; i < regions[*it].num; i++) + if ((regions[*it].list+i)->area > minArea) { + data.push_back(findLocationFor(regions[*it].list)); + cout << regions[*it].name << " at " << data.back() << endl; + } + else break; +} + +#ifdef TGT_HAS_IR_DISTANCE +void Lookout::storeIRDataTo(vector& data) { + NEWMAT::ColumnVector ray = Kinematics::pack(0,0,getIR()); + cout << "dist= " << ray(3) << ", in base frame= "; +#ifdef TGT_ERS7 + NEWMAT::ColumnVector baseCoords = kine->jointToBase(NearIRFrameOffset)*ray; +#else //not ERS7 + NEWMAT::ColumnVector baseCoords = kine->jointToBase(IRFrameOffset)*ray; +#endif + data.push_back(Point(baseCoords(1),baseCoords(2),baseCoords(3))); + cout << data.back() << endl; +} +#endif + + +//================ Scan Request ================ + +void Lookout::processScanEvent(const EventBase& event) { // cout << "Lookout::processScan: " << event.getName() << endl; static bool listeningObjEGID = false; - static ScanRequest* curScanReq = dynamic_cast(curReq); - if (curScanReq != curReq) curScanReq = dynamic_cast(curReq); + const LookoutScanRequest* curScanReq = dynamic_cast(curReq); + switch (event.getGeneratorID()) { case EventBase::motmanEGID: - if (event.getTypeID() != EventBase::deactivateETID) return; // head arrived at the start of motion sequence, add listeners and start scan sequence if (event.getSourceID() == pointer_id) { - pointer_id = MotionManager::invalid_MC_ID; - motman->setPriority(sequence_id,MotionManager::kStdPriority); - MMAccessor(sequence_id)->play(); - for (unsigned int i = 0; i < curScanReq->tasks.size(); i++) { - const ScanRequest::Task* task = curScanReq->tasks[i]; - if (task->getTaskType() == ScanRequest::Task::visObj) { - const ScanRequest::VisionTask& vTask = *dynamic_cast(task); - for(set::const_iterator color_it = vTask.index.begin(); - color_it != vTask.index.end(); color_it++) - erouter->addListener(this,EventBase::visObjEGID, *color_it); - } - erouter->addTimer(this,scan_timer+i,0,false); // for initial measurements - erouter->addTimer(this,scan_timer+i, - (int) ((float) task->interval/(float)curScanReq->scanSpeed),true); - } + erouter->addTimer(this,settle_timer,curScanReq->motionSettleTime,false); } else if (event.getSourceID() == sequence_id) { - sequence_id = MotionManager::invalid_MC_ID; + motman->setPriority(sequence_id,MotionManager::kBackgroundPriority); requestComplete(); } break; + case EventBase::timerEGID: // time to take some measurements - if (event.getSourceID()-scan_timer < curScanReq->tasks.size()) { - ScanRequest::Task* task = curScanReq->tasks[event.getSourceID()-scan_timer]; - if (task->getTaskType() == ScanRequest::Task::visReg) { - ScanRequest::VisionRegionTask* vrt = dynamic_cast(task); + if ( event.getSourceID() == settle_timer ) + triggerScanMotionSequence(); + else if ( event.getSourceID() >= scan_timer && event.getSourceID()-scan_timer < curScanReq->tasks.size() ) { + LookoutRequest::Task* task = curScanReq->tasks[event.getSourceID()-scan_timer]; + if (task->getTaskType() == LookoutRequest::Task::visRegTask) { + LookoutRequest::VisionRegionTask* vrt = dynamic_cast(task); storeVisionRegionDataTo(vrt->data,vrt->index,vrt->minArea); } - else if (task->getTaskType() == ScanRequest::Task::visObj) { + else if (task->getTaskType() == LookoutRequest::Task::visObjTask) { erouter->addListener(this, EventBase::visSegmentEGID, ProjectInterface::visSegmentSID,EventBase::statusETID); listeningObjEGID = true; } - else if (task->getTaskType() == ScanRequest::Task::ir) +#ifdef TGT_HAS_IR_DISTANCE + else if (task->getTaskType() == LookoutRequest::Task::irTask) storeIRDataTo(task->data); +#endif } break; + case EventBase::visSegmentEGID: if (listeningObjEGID) listeningObjEGID = false; else erouter->removeListener(this, EventBase::visSegmentEGID); break; + case EventBase::visObjEGID: if (listeningObjEGID) { - const VisionObjectEvent voe = *static_cast(&event); - for (vector::iterator it = curScanReq->tasks.begin(); + const VisionObjectEvent &voe = static_cast(event); + for (vector::const_iterator it = curScanReq->tasks.begin(); it != curScanReq->tasks.end(); it++) - if ((*it)->getTaskType() == ScanRequest::Task::visObj) { - ScanRequest::VisionTask& vTask = *dynamic_cast(*it); + if ((*it)->getTaskType() == LookoutRequest::Task::visObjTask) { + LookoutRequest::VisionTask& vTask = *dynamic_cast(*it); if (vTask.index.find(event.getSourceID()) != vTask.index.end()) { - vTask.data.push_back(findLocationFor(&voe)); + vTask.data.push_back(findLocationFor(voe)); cout << "VisionObject at " << vTask.data.back() << endl; break; } @@ -141,109 +504,235 @@ }; } -void Lookout::storeVisionRegionDataTo(vector& data, const set& colors, int minArea) { - const unsigned char *img = - ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0); - const color_class_state *regions = reinterpret_cast (img); - for (set::const_iterator it = colors.begin(); - it != colors.end(); it++) - for (int i = 0; i < regions[*it].num; i++) - if ((regions[*it].list+i)->area > minArea) { - data.push_back(findLocationFor(regions[*it].list)); - cout << regions[*it].name << " at " << data.back() << endl; - } - else break; +void Lookout::setupScan() { + const LookoutScanRequest *curScan = dynamic_cast(curReq); + cout << "scan speed: " << curScan->scanSpeed + << " (rad / millisec)\n"; + if ( !curScan->searchArea.isValid() ) { + cout << "Invalid search area in LookoutScanRequest" << endl; + return; + } + switch ( curScan->searchArea->getType() ) { + case lineDataType: { + const Shape &line = ShapeRootTypeConst(curScan->searchArea,LineData); + scanAlongLine(line->firstPt(), line->secondPt()); + break; + } + case polygonDataType:{ + const Shape &poly = ShapeRootTypeConst(curScan->searchArea,PolygonData); + scanAlongPolygon(poly->getVertices()); + break; + } + default: + cout << "Invalid shape type for LookoutRequest searchArea: must be line or polygon" << endl; + } } + +void Lookout::triggerScanMotionSequence() { + const LookoutScanRequest* curScanReq = dynamic_cast(curReq); + for (unsigned int i = 0; i < curScanReq->tasks.size(); i++) { + const LookoutRequest::Task* task = curScanReq->tasks[i]; + if (task->getTaskType() == LookoutRequest::Task::visObjTask) { + const LookoutRequest::VisionTask& vTask = *dynamic_cast(task); + for(set::const_iterator color_it = vTask.index.begin(); + color_it != vTask.index.end(); color_it++) + erouter->addListener(this,EventBase::visObjEGID, *color_it); + } + erouter->addTimer(this,scan_timer+i,0,false); // for initial measurements + int snap_interval = (int)((float)task->dTheta / (float)curScanReq->scanSpeed); + cout << "Lookout scan snap_interval = " << snap_interval << endl; + erouter->addTimer(this, scan_timer+i, snap_interval, true); + } + motman->setPriority(pointer_id,MotionManager::kIgnoredPriority); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); + motman->setPriority(sequence_id,MotionManager::kStdPriority); + MMAccessor(sequence_id)->play(); +} + +void Lookout::scanAlongLine(const Point& startPt, const Point& endPt) { + motman->setPriority(pointer_id,MotionManager::kIgnoredPriority); // just to be safe + MMAccessor pointer_acc(pointer_id); + + // first compute joint angles for final point + pointer_acc->lookAtPoint(endPt.coordX(),endPt.coordY(),endPt.coordZ()); + std::vector anglesA(NumHeadJoints); + for(unsigned int i=0; igetJointValue(i); -void Lookout::storeIRDataTo(vector& data) { - NEWMAT::ColumnVector ray = Kinematics::pack(0,0,getIR()); - cout << "dist= " << ray(3) << ", in base frame= "; -#ifdef TGT_ERS7 - NEWMAT::ColumnVector baseCoords = kine->jointToBase(NearIRFrameOffset)*ray; -#else //not ERS7 - NEWMAT::ColumnVector baseCoords = kine->jointToBase(IRFrameOffset)*ray; + // now compute angles for initial point, so when the motion command is executed we'll start there + pointer_acc->lookAtPoint(startPt.coordX(),startPt.coordY(),startPt.coordZ()); + std::vector anglesB(NumHeadJoints); + for(unsigned int i=0; igetJointValue(i); + + float total_joint_distance=0; + for(unsigned int i=0; i(curReq)->scanSpeed); + + // begin at start point (the HeadPointerMC will have brought us there) and move smoothly to end point + motman->setPriority(sequence_id,MotionManager::kIgnoredPriority); // just to be safe + MMAccessor mseq_acc(sequence_id); + mseq_acc->clear(); + mseq_acc->pause(); +#ifdef TGT_HAS_HEAD + for(unsigned int i=0; isetOutputCmd(HeadOffset+i,anglesA[i]); #endif - data.push_back(Point(baseCoords(1),baseCoords(2),baseCoords(3))); - cout << data.back() << endl; + mseq_acc->advanceTime(movement_time); +#ifdef TGT_HAS_HEAD + for(unsigned int i=0; isetOutputCmd(HeadOffset+i,anglesB[i]); +#endif + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); // just to be safe + motman->setPriority(pointer_id,MotionManager::kStdPriority); // start head moving to where scan begins; completion will trigger the scan } -bool Lookout::findPixelModes(StoreModeImageRequest& modeRequest) { - static size_t npixels = modeRequest.image->getNumPixels(); - static vector > colorCount(npixels); - if (modeRequest.numImages-- == 0) { // finished collecting samples, find modes - for (size_t i = 0; i::const_iterator it = colorCount[i].begin(); - it != colorCount[i].end(); it++) - if (it->second > maxCount) { - maxCount = it->second; - maxChar = it->first; +void Lookout::scanAlongPolygon(vector const &vertices, const bool closed) { + if ( vertices.size() == 0 ) + requestComplete(); + vector vertices_copy(vertices); + const Point startPt = vertices_copy[0]; + if ( closed ) + vertices_copy.push_back(startPt); + motman->setPriority(pointer_id,MotionManager::kBackgroundPriority); // just to be safe + motman->setPriority(sequence_id,MotionManager::kBackgroundPriority); // just to be safe + MMAccessor pointer_acc(pointer_id); + MMAccessor mseq_acc(sequence_id); + mseq_acc->pause(); + mseq_acc->clear(); + float const speed = dynamic_cast(curReq)->scanSpeed; + std::vector anglesA(NumHeadJoints,0), anglesB(NumHeadJoints,0); + for ( vector::const_iterator it = vertices_copy.begin(); it != vertices_copy.end(); ++it ) { + pointer_acc->lookAtPoint((*it).coordX(),(*it).coordY(),(*it).coordZ()); + for(unsigned int i=0; igetJointValue(i); + if ( it != vertices_copy.begin() ) { + float total_joint_distance=0; + for(unsigned int i=0; iadvanceTime(movement_time); + } +#ifdef TGT_HAS_HEAD + for(unsigned int i=0; isetOutputCmd(HeadOffset+i,anglesB[i]); + mseq_acc->advanceTime(200); + for(unsigned int i=0; isetOutputCmd(HeadOffset+i,anglesB[i]); +#endif + anglesA.swap(anglesB); } - modeRequest.image[i] = maxChar; - colorCount[i].clear(); - } - return true; - } - else { - for (size_t i = 0; ilookAtPoint(startPt.coordX(),startPt.coordY(),startPt.coordZ()); + motman->setPriority(pointer_id,MotionManager::kStdPriority); // start head moving to where scan begins; completion will trigger the scan +} + +//================ Track Requests ================ + +void Lookout::setupTrack() { + // point the head at the object, then start tracking it and posting status events + LookoutTrackRequest *curTR = static_cast(curReq); + const ShapeRoot &target = curTR->targetShape; + curTR->cindex = ProjectInterface::getColorIndex(target->getColor()); + Point egoLoc = target->getCentroid(); + if ( target->getRefFrameType() == camcentric ) { +#ifndef TGT_HAS_CAMERA + std::cerr << "Lookout::setupTrack target has camcentric reference frame, but target model doesn't have a camera" << std::endl; +#else + const NEWMAT::Matrix camToBase = kine->jointToBase(CameraFrameOffset); + egoLoc.projectToGround(camToBase,kine->calculateGroundPlane()); // assume head hasn't moved, or we're screwed +#endif } + trackerState = moveToAcquire; + erouter->addListener(this, EventBase::visRegionEGID, ProjectInterface::visRegionSID, EventBase::deactivateETID); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); + motman->setPriority(sequence_id,MotionManager::kIgnoredPriority); + motman->setPriority(pointer_id,MotionManager::kStdPriority); + successSave = MMAccessor(pointer_id)->lookAtPoint(egoLoc.coordX(), egoLoc.coordY(), egoLoc.coordZ()); } - -void Lookout::processPointAt(const EventBase& event) { - // cout << "Lookout::processPointAt: " << event.getName() << endl; - switch (event.getGeneratorID()) { - case EventBase::motmanEGID: // head motion complete, wait for duration - if (event.getSourceID() == pointer_id && event.getTypeID() == EventBase::deactivateETID) { - pointer_id = MotionManager::invalid_MC_ID; - erouter->addTimer(this, dur_timer, dynamic_cast(curReq)->duration, false); + +void Lookout::processTrackEvent(const EventBase &event) { + const LookoutTrackRequest *curTR = static_cast(curReq); + switch ( event.getGeneratorID() ) { + + case EventBase::visRegionEGID: { + if ( trackerState == moveToAcquire ) return; // ignore vision events while slewing head to initial position + const color_class_state *ccs = reinterpret_cast + (ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0)); + const color_class_state &col = ccs[curTR->cindex]; + if ( col.list == NULL || col.list->area <= curTR->minBlobArea ) { + if ( trackerState != lost ) { + trackerState = lost; + erouter->addTimer(this,lost_timer,2000,false); // wait for object to reappear + } + return; } + // test succeeded + erouter->removeTimer(this,lost_timer); + trackerState = tracking; + Point target = findLocationFor(col.list); + MMAccessor(pointer_id)->lookAtPoint(target.coordX(),target.coordY(),target.coordZ()); + } break; - case EventBase::timerEGID: - if (event.getSourceID() == dur_timer) { - PointAtBase* baseReq = dynamic_cast(curReq); - switch (baseReq->getPointAtType()) { - case PointAtBase::storeImage: - erouter->addListener(this, EventBase::visSegmentEGID, - ProjectInterface::visSegmentSID,EventBase::statusETID); - break; - case PointAtBase::measureDist: - erouter->addListener(this, EventBase::sensorEGID, SensorSourceID::UpdatedSID); - break; - default: - requestComplete(); - break; - }; + + + case EventBase::motmanEGID: + switch ( trackerState ) { + case inactive: + break; + case moveToAcquire: + trackerState = tracking; + break; + case tracking: + case searching: + case centering: + case lost: break; } - case EventBase::visSegmentEGID: { - erouter->removeListener(this, EventBase::visSegmentEGID); - PointAtBase* baseReq = dynamic_cast(curReq); - baseReq->toBaseMatrix = kine->jointToBase(baseReq->joint); - VRmixin::camSkS.clear(); - StoreImageRequest& storeImageReq = *dynamic_cast(curReq); - storeImageReq.image = (*storeImageReq.sketchFunc)(); - if (StoreModeImageRequest* modeReq = dynamic_cast(curReq)) - if ( ! findPixelModes(*modeReq) ) { - erouter->addTimer(this, dur_timer, modeReq->interval, false); - return; - } - requestComplete(); - } break; - case EventBase::sensorEGID: { - MeasureDistanceRequest* measureDistReq = dynamic_cast(curReq); - measureDistReq->toBaseMatrix = kine->jointToBase(measureDistReq->joint); - measureDistReq->val = getIR(); - requestComplete(); - } + + case EventBase::timerEGID: + if ( event.getSourceID() == lost_timer ) // object out of sight for too long: give up? Or search? + stopTrack(); break; + default: - cout << "Lookout::processPointAt: unknown event " << event.getName() << endl; break; - }; + } +} + +void Lookout::stopTrack() { + if ( curReq != NULL && curReq->getHeadMotionType() == LookoutRequest::track ) + requestComplete(false); +} + +Point Lookout::findLocationFor(const float normX, const float normY) { + // NEWMAT::ColumnVector ground_plane = kine->calculateGroundPlane(); + NEWMAT::ColumnVector cameraPt(4); + config->vision.computeRay(normX, normY, cameraPt(1),cameraPt(2),cameraPt(3)); +#ifdef TGT_HAS_IR_DISTANCE + cameraPt *= getIR(); +#else + cameraPt *= 400; +#endif + cameraPt(4) = 1; + // groundPt = kine->projectToPlane(CameraFrameOffset, cameraPt, + // BaseFrameOffset, ground_plane, BaseFrameOffset); +#ifndef TGT_HAS_CAMERA + const NEWMAT::ColumnVector groundPt = cameraPt; +#else + const NEWMAT::Matrix camToBase(kine->jointToBase(CameraFrameOffset)); + const NEWMAT::ColumnVector groundPt = camToBase * cameraPt; +#endif + return Point(groundPt(1),groundPt(2),groundPt(3),egocentric); } + /* void Lookout::processTrackVision(float normX, float normY, bool isCurrentlyVisible) { if (!isCurrentlyVisible && landmarkInView) { // landmark just lost @@ -264,7 +753,7 @@ erouter->postEvent(EventBase::lookoutEGID, curReq->getRequestID(), EventBase::statusETID,0); } -void Lookout::processTrack(const EventBase& event) { +void Lookout::processTrackEvent(const EventBase& event) { switch (event.getGeneratorID()) { case EventBase::visObjEGID: if (event.getTypeID()==EventBase::statusETID) { @@ -309,161 +798,8 @@ }; } */ -unsigned int Lookout::executeRequest(const LookoutRequest& req) { - switch (req.getHeadMotionType()) { - case LookoutRequest::none: - switch (dynamic_cast(&req)->getPointAtType()) { - case PointAtBase::storeImage: - if (dynamic_cast(&req)) - pushRequest(req); - else - pushRequest(req); - break; - case PointAtBase::measureDist: - pushRequest(req); break; - default: - cout << "Lookout::executeRequest: unknown PointAtRequest type\n"; - break; - }; - break; - case LookoutRequest::pointAt: - switch (dynamic_cast(&req)->getPointAtType()) { - case PointAtBase::none: - pushRequest(req); break; - case PointAtBase::storeImage: - if (dynamic_cast(&req)) - pushRequest(req); - else - pushRequest(req); - break; - case PointAtBase::measureDist: - pushRequest(req); break; - default: cout << "Lookout::executeRequest: unknown PointAtRequest type\n"; break; - }; - break; - case LookoutRequest::scan: - if (dynamic_cast(&req)->getScanType() == ScanRequest::line) - pushRequest(req); - else - pushRequest(req); - break; - case LookoutRequest::track: - pushRequest(req); break; - default: - cout << "Lookout::executeRequest: unknown request type " << req.getHeadMotionType() << endl; - }; - requests.back()->requestID = idCounter++; - // cout << " request " << requests.back()->requestID << " added to request queue\n"; - if (requests.size() == 1) - executeRequest(); - return requests.back()->requestID; -} -// triggers action to start completing each type of front of request queue -void Lookout::executeRequest() { - curReq = requests.front(); - // cout << "Executing Lookout Request #" << curReq->requestID << endl; - switch (curReq->getHeadMotionType()) { - case LookoutRequest::none: - erouter->addTimer(this,dur_timer,dynamic_cast(curReq)->duration,false); - break; - case LookoutRequest::pointAt: { - const Point& pt = dynamic_cast(curReq)->gazePt; - if (dynamic_cast(curReq)->getPointAtType() == PointAtBase::measureDist) { - SharedObject pstmc; -#ifdef TGT_ERS7 - pstmc->solveLinkVector(pt.coords,NearIRFrameOffset,Kinematics::pack(0,0,1)); -#else - pstmc->solveLinkVector(pt.coords,IRFrameOffset,Kinematics::pack(0,0,1)); -#endif - pointer_id = motman->addPrunableMotion(pstmc); - } - else { - SharedObject hpmc; - hpmc->lookAtPoint(pt.coordX(),pt.coordY(),pt.coordZ()); - pointer_id = motman->addPrunableMotion(hpmc); - } - erouter->addListener(this,EventBase::motmanEGID,pointer_id); - } - break; - case LookoutRequest::scan: - erouter->addListener(this,EventBase::motmanEGID); - scan(); - break; - default: - cout << "Lookout::executeRequest(): unknown request " << curReq->getHeadMotionType() << endl; - break; - }; -} - -void Lookout::requestComplete() { - // remove all timer and listeners for now - erouter->removeListener(this); - erouter->removeTimer(this); - if (curReq->getHeadMotionType() == LookoutRequest::scan) { - erouter->postEvent(LookoutScanEvent - (dynamic_cast(curReq)->tasks, - EventBase::lookoutEGID,curReq->requestID, EventBase::deactivateETID)); - } - else if (curReq->getHeadMotionType() == LookoutRequest::pointAt - || curReq->getHeadMotionType() == LookoutRequest::none) { - const NEWMAT::Matrix& toBase = dynamic_cast(curReq)->toBaseMatrix; - switch (dynamic_cast(curReq)->getPointAtType()) { - case PointAtRequest::none: - erouter->postEvent(LookoutPointAtEvent(toBase,EventBase::lookoutEGID, - curReq->requestID, EventBase::deactivateETID)); - break; - case PointAtRequest::storeImage: - erouter->postEvent(LookoutSketchEvent - (dynamic_cast(curReq)->image, - toBase,EventBase::lookoutEGID, - curReq->requestID, EventBase::deactivateETID)); - break; - case PointAtRequest::measureDist: - erouter->postEvent(LookoutIREvent - (dynamic_cast(curReq)->val, - toBase,EventBase::lookoutEGID, - curReq->requestID, EventBase::deactivateETID)); - break; - default: - cout << "Lookout::requestComplete(): Unknown type returned by getPointAtType()\n"; - }; - } - requests.pop(); - // delete curReq; - curReq = NULL; - if (!requests.empty()) - executeRequest(); -} - - -void Lookout::processEvent(const EventBase& event) { - cout << "Lookout::processEvent got " << event.getDescription() << endl; - if (NULL==curReq) { - cout << "Should not get any event when executing no request\n"; - return; - } - switch (curReq->getHeadMotionType()) { - case LookoutRequest::scan: - processScan(event); - break; - /* - case LookoutRequest::track: - processTrack(event); - break; - case LookoutRequest::localize: - // ?????? - break; - */ - case LookoutRequest::pointAt: - case LookoutRequest::none: - processPointAt(event); break; - default: - cout << "Lookout::processEvent: unknown request type: " << event.getName() << endl; - break; - }; -} /* void Lookout::trackObjectAt(float horiz, float vert) { setPanPrior(false); @@ -495,115 +831,127 @@ } */ -Point Lookout::findLocationFor(float normX, float normY) { - NEWMAT::ColumnVector ground_plane = kine->calculateGroundPlane(); - NEWMAT::ColumnVector cameraPt(4), groundPt(4); - config->vision.computeRay(normX, normY, cameraPt(1),cameraPt(2),cameraPt(3)); - cameraPt(4) = 1; - groundPt = kine->projectToPlane(CameraFrameOffset, cameraPt, - BaseFrameOffset, ground_plane, BaseFrameOffset); - return Point(groundPt(1),groundPt(2),groundPt(3),egocentric); -} +// ================ Search Requests ================ -void Lookout::scan() { - cout << "scan speed: " << dynamic_cast(curReq)->scanSpeed - << " (rad / millisec)\n"; - if (dynamic_cast(curReq)->getScanType()==ScanRequest::line) { - const ScanAlongLineRequest& scanLineReq = *dynamic_cast(curReq); - scanAlongLine(scanLineReq.beginPt, scanLineReq.endPt); - } - else { - const ScanAreaRequest& scanLineReq = *dynamic_cast(curReq); - scanArea(scanLineReq.left, scanLineReq.right, scanLineReq.far, scanLineReq.near); +/* Move head to the target shape. If we encounter the desired color +region along the way, stop moving. Otherwise, upon reaching the +target, begin a spiral search sequence. If the sequence completes +without finding the color region, return failure. Else find the +center of the color region, move the head there, wait for the camera +to settle, take a picture, and return success. */ + +void Lookout::setupSearch() { + // point the head at expected object location, then start a spiral search + LookoutSearchRequest *curSR = static_cast(curReq); + const ShapeRoot &target = curSR->targetShape; + curSR->cindex = ProjectInterface::getColorIndex(target->getColor()); + Point egoLoc = target->getCentroid(); + if ( target->getRefFrameType() == allocentric ) { + egoLoc.applyTransform(VRmixin::mapBuilder.worldToLocalTranslateMatrix,egocentric); + egoLoc.applyTransform(VRmixin::mapBuilder.worldToLocalRotateMatrix,egocentric); } + cout << "Lookout: search target estimated at " << egoLoc << ", color=" << curSR->cindex << endl; + erouter->addListener(this, EventBase::visRegionEGID,ProjectInterface::visRegionSID,EventBase::deactivateETID); + MMAccessor(pointer_id)->lookAtPoint(egoLoc.coordX(), egoLoc.coordY(), egoLoc.coordZ()); + motman->setPriority(pointer_id,MotionManager::kStdPriority); + trackerState = moveToAcquire; } -void Lookout::scanAlongLine(const Point& startPt, const Point& endPt) { - SharedObject hpmc; - - hpmc->lookAtPoint(endPt.coordX(),endPt.coordY(),endPt.coordZ()); - const float pan1 = hpmc->getJointValue(PanOffset); - const float tilt1 = hpmc->getJointValue(TiltOffset); - const float roll1 = hpmc->getJointValue(RollOffset); - - hpmc->lookAtPoint(startPt.coordX(),startPt.coordY(),startPt.coordZ()); - const float pan0 = hpmc->getJointValue(PanOffset); - const float tilt0 = hpmc->getJointValue(TiltOffset); - const float roll0 = hpmc->getJointValue(RollOffset); - - const unsigned int time = (unsigned int) - (sqrt((pan1-pan0)*(pan1-pan0)+(tilt1-tilt0)*(tilt1-tilt0)+(roll1-roll0)*(roll1-roll0)) - / dynamic_cast(curReq)->scanSpeed); - - SharedObject scanmc; - scanmc->pause(); - scanmc->setOutputCmd(HeadOffset+TiltOffset,tilt0); - scanmc->setOutputCmd(HeadOffset+RollOffset,roll0); - scanmc->setOutputCmd(HeadOffset+PanOffset,pan0); - scanmc->advanceTime(time); - scanmc->setOutputCmd(HeadOffset+TiltOffset,tilt1); - scanmc->setOutputCmd(HeadOffset+RollOffset,roll1); - scanmc->setOutputCmd(HeadOffset+PanOffset,pan1); - - pointer_id = motman->addPrunableMotion(hpmc); // moves head to where scan begins; - // actual scan motion sequence (paused), played when pointer_id above is completed - sequence_id = motman->addPrunableMotion(scanmc,MotionManager::kIgnoredPriority); -} +void Lookout::processSearchEvent(const EventBase &event) { + // cout << "Lookout::processSearchEvent: " << event.getDescription() << endl; + const LookoutSearchRequest *curSR = static_cast(curReq); + switch ( event.getGeneratorID() ) { -void Lookout::scanArea(coordinate_t left, coordinate_t right, - coordinate_t far, coordinate_t near) { - const float& scanSpeed = dynamic_cast(curReq)->scanSpeed; - static const float tiltJointValDelta = mathutils::deg2rad(15.0); // - const int tiltTime = (int) (tiltJointValDelta / scanSpeed); - const float z_coord = -150;//1/wmap.ground_plane(3); - unsigned short counter = 1; // or 3 if start from left - - SharedObject hpmc; //! < virtual headpointer, never gets added to motman - near = (near > 100) ? near : 100; - const Point firstPt(near, (counter < 2) ? right : left, z_coord); // start of motion sequence - hpmc->lookAtPoint(firstPt.coordX(),firstPt.coordY(),firstPt.coordZ()); - float tiltJointVal = hpmc->getJointValue(TiltOffset); + case EventBase::motmanEGID: + if ( event.getSourceID() == pointer_id || event.getSourceID() == sequence_id ) + erouter->addTimer(this, settle_timer, 500, false); + else + return; + break; - // define scan waypoints in terms of joint angles instead of base frame coordinates (x,y,z) - // this way you can make sure to cover entire region but not scanning the same region twice - // would be harder to achieve this if I did this in terms of base frame coords + case EventBase::visRegionEGID: { + const color_class_state *ccs = reinterpret_cast + (ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0)); + const color_class_state &col = ccs[curSR->cindex]; + // insert test to see if desired object has been seen: + if ( col.list != NULL && col.list->area >= curSR->minBlobArea ) + erouter->removeListener(this,EventBase::visRegionEGID); + else + return; + // test succeeded + const Point center = findLocationFor(col.list); + cout << "Lookout search: center = " << center << " area = " << col.list->area << " color = " << curSR->cindex << endl; + // MMAccessor(pointer_id)->lookAtPoint(center.coordX(),center.coordY(),center.coordZ()); + // motman->setPriority(pointer_id,MotionManager::kStdPriority); + motman->setPriority(pointer_id,MotionManager::kIgnoredPriority); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); + motman->setPriority(sequence_id,MotionManager::kIgnoredPriority); + trackerState = centering; + erouter->addTimer(this, settle_timer, 500, false); + break; + } - hpmc->lookAtPoint(far,left,z_coord); - const float tiltJointValFar = hpmc->getJointValue(TiltOffset); - const float panJointValLeftFar = hpmc->getJointValue(PanOffset); - hpmc->lookAtPoint(far,right,z_coord); - const float panJointValRiteFar = hpmc->getJointValue(PanOffset); - hpmc->lookAtPoint(near,left,z_coord); - float panJointValLeft = hpmc->getJointValue(PanOffset); - hpmc->lookAtPoint(near,right,z_coord); - float panJointValRite = hpmc->getJointValue(PanOffset); - const int panTime = (int) (fabs(panJointValLeft-panJointValRite)/scanSpeed); + case EventBase::timerEGID: + switch ( trackerState ) { + case moveToAcquire: // camera has settled, so start the search + triggerSearchMotionSequence(); + break; + case searching: + case centering: // camera has settled, so grab a picture and return + requestComplete(); + break; + default: + break; + } - const float panJointLeftDelta = (tiltJointValFar-tiltJointVal < 0.01) ? 0 : - (panJointValLeftFar-panJointValLeft)/(tiltJointValFar-tiltJointVal)*tiltJointValDelta; - const float panJointRiteDelta = (tiltJointValFar-tiltJointVal < 0.01) ? 0 : - (panJointValRiteFar-panJointValRite)/(tiltJointValFar-tiltJointVal)*tiltJointValDelta; + default: + break; + } +} - SharedObject scanmc; - scanmc->pause(); - while (true) { - counter++; - counter = counter % 4; - if (counter%2 == 1) { - tiltJointVal += tiltJointValDelta; - if (tiltJointVal > tiltJointValFar) break; - if (counter == 1) panJointValRite += panJointRiteDelta; - else panJointValLeft += panJointLeftDelta; - } - scanmc->advanceTime((counter%2==1) ? tiltTime : panTime); - scanmc->setOutputCmd(HeadOffset+TiltOffset, tiltJointVal); - scanmc->setOutputCmd(HeadOffset+RollOffset,0); - scanmc->setOutputCmd(HeadOffset+PanOffset, (counter < 2) ? panJointValRite : panJointValLeft); +void Lookout::triggerSearchMotionSequence() { + cout << "Lookout: beginning search motion sequence" << endl; + const LookoutSearchRequest *curSR = static_cast(curReq); + const ShapeRoot &target = curSR->targetShape; + Point egoLoc = target->getCentroid(); + if ( target->getRefFrameType() == allocentric ) { + egoLoc.applyTransform(VRmixin::mapBuilder.worldToLocalTranslateMatrix,egocentric); + egoLoc.applyTransform(VRmixin::mapBuilder.worldToLocalRotateMatrix,egocentric); } - hpmc->lookAtPoint(firstPt.coordX(),firstPt.coordY(),firstPt.coordZ()); - pointer_id = motman->addPrunableMotion(hpmc); // moves head to where scan begins - // actual scan motion sequence (paused), played when pointer_id above is completed - sequence_id = motman->addPrunableMotion(scanmc,MotionManager::kIgnoredPriority); + int const nspirals = 5; + float const xstep=50, ystep=100; + HeadPointerMC hpmc_temp; + std::vector jointvals(0); + jointvals.reserve(nspirals*4*NumHeadJoints); + for (int i=1; i<=nspirals; i++) { + searchAt(hpmc_temp,jointvals,egoLoc+Point(-i*xstep, 0)); + searchAt(hpmc_temp,jointvals,egoLoc+Point( 0, i*ystep)); + searchAt(hpmc_temp,jointvals,egoLoc+Point( i*xstep, 0)); + searchAt(hpmc_temp,jointvals,egoLoc+Point( 0, -i*ystep)); + } + // Calculate all the joint positions first (above), then lock the + // motionsequence command and quickly copy them over. + MMAccessor mseq_acc(sequence_id); + mseq_acc->clear(); +#ifdef TGT_HAS_HEAD + for ( std::vector::const_iterator it = jointvals.begin(); it != jointvals.end(); ) { + mseq_acc->advanceTime(800); + for(unsigned int i=0; isetOutputCmd(HeadOffset+i,*(it++)); + } + mseq_acc->advanceTime(800); +#endif + mseq_acc->play(); + motman->setPriority(sequence_id,MotionManager::kStdPriority); + trackerState = searching; +} + +void Lookout::searchAt(HeadPointerMC &hpmc_temp, + std::vector &jointvals, + const Point &target) { + hpmc_temp.lookAtPoint(target.coordX() ,target.coordY() ,target.coordZ()); + for(unsigned int i=0; i + #include "Behaviors/BehaviorBase.h" +#include "Motion/MMAccessor.h" #include "Motion/MotionManager.h" +#include "Motion/HeadPointerMC.h" #include "Motion/MotionSequenceMC.h" +#include "Motion/PostureMC.h" #include "Events/VisionObjectEvent.h" #include "LookoutRequests.h" namespace DualCoding { -class LookoutRequest; -class StoreModeImageRequest; -class ModeImageRequest; +//! The Lookout accepts LookoutRequests to move the head and collect sensor information. /*! - The Lookout's job is to move the head and collect sensor information. - Head motion can be none (user will point the head himself), pointAt, scan, or track. - The data collected can be an image or distance reading, or for scan operations, it - can be a list of locations where certain VisionObject or VisionRegion streams - reported hits. + HeadMotionType can be none (user will point the head himself), + pointAt, scan, track, or search. The data collected can be an image + or distance reading, or for scan operations, it can be a list of + locations where certain VisionObject or VisionRegion streams reported + hits. */ @@ -28,85 +30,125 @@ public: //! Constructor Lookout(); - //! Destructor - virtual ~Lookout() {} - + virtual void DoStart(); virtual void DoStop(); virtual void processEvent(const EventBase& event); - static std::string getClassDescription() { return "moves head according to request"; } + static std::string getClassDescription() { return "Moves head and collects data according to request"; } virtual std::string getDescription() const { return getClassDescription(); } virtual unsigned int executeRequest(const LookoutRequest&); - // virtual bool removeRequest(unsigned int req_id); - // bool isBusy() const { return !requests.empty(); } + bool busy() { return curReq != NULL; } + void stopTrack(); + + static std::vector groundSearchPoints(); //!< returns a vector of points for searching the ground around the robot + + void moveHeadToPoint(); // bool isLandmarkVisible() const { return landmark_inview; } - // bool isExecuting(LookoutRequest::HeadMotionType_t type) const - // { return !requests.empty() && getCurrentRequest().getHeadMotionType() == type; } - static Point findLocationFor(float, float); - static const unsigned int Invalid_LO_ID=(unsigned int)-1; + void relax(); //!< Inactivates all Lookout motion commands; called when MapBuilder finishes + + static Point findLocationFor(const float normX, const float normY); + static const unsigned int invalid_LO_ID=(unsigned int)-1; protected: virtual void executeRequest(); - virtual void requestComplete(); + virtual void requestComplete(bool result=true); + template void pushRequest(const LookoutRequest& req) { - requests.push(new T(*dynamic_cast(&req))); + requests.push(new T(dynamic_cast(req))); } - //! PointAtReqeust - void processPointAt(const EventBase& event); - bool findPixelModes(StoreModeImageRequest& modeRequest); - void getData(); + //@name PointAtRequest functions + //@{ + void processPointAtEvent(const EventBase& event); + bool findPixelModes(); +#ifdef TGT_HAS_IR_DISTANCE + bool findDistanceMode(); + float getDistanceModeValue(); +#endif + //@} + + //@name ScanRequest functions + //@{ + void setupScan(); + void triggerScanMotionSequence(); + void processScanEvent(const EventBase& event); + void scanAlongLine(const Point& start,const Point& end); + void scanAlongPolygon(const std::vector& vertices, const bool closed=false); + void scanArea(const Point &topLeft, const Point &topRight, + const Point &bottomLeft, const Point &bottomRight); + + static Point findLocationFor(const VisionObjectEvent& visev) { + return findLocationFor(visev.getCenterX(), visev.getCenterY()); + } + + static Point findLocationFor(const CMVision::region* reg) { + return findLocationFor(2.0*reg->cen_x/VRmixin::camSkS.getWidth()-1.0, + 2.0*reg->cen_y/VRmixin::camSkS.getHeight()-1.0); + } + + void storeVisionRegionDataTo(std::vector&, const std::set&, int); +#ifdef TGT_HAS_IR_DISTANCE + void storeIRDataTo(std::vector&); +#endif + //@} + + //@name TrackRequest functions + //@{ + void setupTrack(); + void processTrackEvent(const EventBase& event); /* - //! TrackRequest - void processTrack(const EventBase& event); void processTrackVision(float normX, float normY, bool isCurrentlyVisible); void trackObjectAt(float normX, float normY); //! tracks point at [normX,normY] in cam frame Point findLocationFor(float, float); */ - //! ScanReqeust - void processScan(const EventBase& event); - void scan(); - void scanAlongLine(const Point& start,const Point& end); - void scanArea(coordinate_t left, coordinate_t right, - coordinate_t far, coordinate_t near); - // void storeRegionLocation(const SegmentedColorGenerator::color_class_state*); - // void storeVisionObjectLocation(const VisionObjectEvent*); - Point findLocationFor(const VisionObjectEvent* voe) { - return findLocationFor(voe->getCenterX(), voe->getCenterY()); - } - Point findLocationFor(const CMVision::region* reg) { - return findLocationFor - (2.0*reg->cen_x/VRmixin::camSkS.getWidth()-1.0, - 2.0*reg->cen_y/VRmixin::camSkS.getHeight()-1.0); - } + //@} + + //@name SearchRequest functions + //@{ + void setupSearch(); + void processSearchEvent(const EventBase& event); + void triggerSearchMotionSequence(); + static void searchAt(HeadPointerMC &hpmc_temp, + std::vector &jointvals, + const Point &target); + //@} - void storeVisionRegionDataTo(vector&, const set&, int); - void storeIRDataTo(vector&); - // float scanSpeed() const { return baseRange/base_pan_time; } //(rad/msec) private: Lookout& operator=(const Lookout&); Lookout(const Lookout&); protected: - MotionManager::MC_ID pointer_id; //!< a HeadPointerMC object - MotionManager::MC_ID sequence_id; //!< id for scan/find motion sequence - queue requests; - LookoutRequest *curReq; - bool /*pan_prior, */landmarkInView; + std::vector > pixelHistograms; + std::priority_queue distanceSamples; + + MotionManager::MC_ID pointer_id; //!< id for HeadPointerMC for pointing the camera + MotionManager::MC_ID posture_id; //!< id for PostureMC for pointing the IR sensors + MotionManager::MC_ID sequence_id; //!< id for MotionSequenceMC for scanning + std::queue requests; //!< queue of pending LookoutRequest instances, including the current request + LookoutRequest *curReq; //!< pointer to request currently being executed + LookoutPointRequest *curPAR; //!< current Point-At request (same object as curReq) + bool successSave; + + enum TrackerStates { + inactive, + moveToAcquire, + tracking, + searching, + centering, + lost + } trackerState; unsigned int idCounter; enum LookoutTimerSourceId_t { - start_pan, - pan_complete, - reset_pan, - no_event, - dur_timer, + settle_timer = 1, + sample_timer, + lost_timer, scan_timer, //scan_timer has to be at the end of enum list }; }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/LookoutRequests.cc ./DualCoding/LookoutRequests.cc --- ../Tekkotsu_3.0/DualCoding/LookoutRequests.cc 2006-08-11 18:21:33.000000000 -0400 +++ ./DualCoding/LookoutRequests.cc 2007-11-11 18:57:21.000000000 -0500 @@ -1,5 +1,22 @@ #include "LookoutRequests.h" namespace DualCoding { -const float ScanRequest::defSpd = 0.0015; + +const float LookoutScanRequest::defSpd = 0.0015; + +LookoutScanRequest::~LookoutScanRequest() { + for (std::vector::const_iterator it = tasks.begin(); + it != tasks.end(); it++) + delete *it; } + +const char* const LookoutRequest::headMotionTypeNames[numHeadMotionTypes] = { + "noMotion", + "pointAt", + "scan", + "track", + "search" +}; + + +} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/LookoutRequests.h ./DualCoding/LookoutRequests.h --- ../Tekkotsu_3.0/DualCoding/LookoutRequests.h 2006-08-11 18:21:33.000000000 -0400 +++ ./DualCoding/LookoutRequests.h 2007-11-18 01:47:01.000000000 -0500 @@ -5,312 +5,284 @@ #include "Shared/newmat/newmat.h" #include "Shared/ProjectInterface.h" #include "Shared/WorldState.h" -#include "DualCoding.h" + +#include "Sketch.h" +#include "Point.h" +#include "ShapeRoot.h" #include "VRmixin.h" namespace DualCoding { +//! Base class for requests to the Lookout + class LookoutRequest { public: enum HeadMotionType_t { - none, - pointAt, - scan, - track + noMotion, //!< use current head position + pointAt, //!< move head to specified gaze point + scan, //!< scan head along specified path + track, //!< move head to track object + search, //!< spiral search for a known object + numHeadMotionTypes }; - virtual HeadMotionType_t getHeadMotionType() const = 0; - //! Constructor - LookoutRequest() : requestID((unsigned int) -1) {} - virtual ~LookoutRequest() {} - //! Lookout assigns non-zero value when added to queue - unsigned int requestID; -protected: - //! Copy constructor - LookoutRequest(const LookoutRequest& req) : requestID(req.requestID) {} -private: - LookoutRequest& operator=(const LookoutRequest& req); -}; - -// ---------- pointAt requests ---------- -class PointAtBase : public LookoutRequest { -protected: - //! Constructor - PointAtBase(unsigned int _joint, unsigned int _duration) - : joint(_joint), toBaseMatrix(), duration(_duration) {} - - //! Copy constructor - PointAtBase(const PointAtBase& base) - : LookoutRequest(base), joint(base.joint), - toBaseMatrix(base.toBaseMatrix), duration(base.duration) {} - -public: - enum PointAtRequestType_t { none, storeImage, measureDist }; - virtual PointAtRequestType_t getPointAtType() const = 0;//const { return none; } - virtual HeadMotionType_t getHeadMotionType() const { return LookoutRequest::none; } - unsigned int joint; //!< frame from which base frame transformation matrix is created, e.g., Camera, IR, etc. - NEWMAT::Matrix toBaseMatrix; //!< transformation matrix from joint frame to base frame - //! how much time to wait before taking measurements or throw completion event after head reaches gazePt. - unsigned int duration; -}; - -class PointAtRequest : virtual public PointAtBase { -public: - //! Constructor - PointAtRequest(const Point& pt, unsigned int dur=1000) - : PointAtBase(CameraFrameOffset,dur), gazePt(pt) {}; - //! Copy constructor - PointAtRequest(const PointAtRequest& req) - : PointAtBase(req), gazePt(req.gazePt) {} + static const char* const headMotionTypeNames[numHeadMotionTypes]; - virtual PointAtRequestType_t getPointAtType() const { return none; } - virtual HeadMotionType_t getHeadMotionType() const { return pointAt; } - Point gazePt; //!< point to look at in base frame coordinates -}; + HeadMotionType_t getHeadMotionType() const { return headMotionType; } + void setHeadMotionType(const HeadMotionType_t htype) { headMotionType = htype; } -class StoreImageRequest : virtual public PointAtBase { -public: - //! Constructor - StoreImageRequest(Sketch (&func)()=VRmixin::sketchFromSeg, - unsigned int dur=1000) - : PointAtBase(CameraFrameOffset,dur), image(), sketchFunc(func) {}; - //! Copy constructor - StoreImageRequest(const StoreImageRequest& req) - : PointAtBase(req), image(req.image), sketchFunc(req.sketchFunc) {} + enum LookoutResultType_t { + noResult, //!< don't return anything (just move the head) + imageResult, //!< take a picture +#ifdef TGT_HAS_IR_DISTANCE + distanceResult, //!< measure distance with IR rangefinder +#endif + interestPoints //!< collection of interest points (from scanning) + }; - virtual PointAtRequestType_t getPointAtType() const { return storeImage; } - Sketch image; // (*sketchFunc)(); // (&func)()=VRmixin::sketchFromSeg, - unsigned int dur=1000) - : PointAtBase(CameraFrameOffset,dur), PointAtRequest(pt,dur), StoreImageRequest(func,dur) {} - //! Copy constructor - StoreImageAtRequest(const StoreImageAtRequest& req) - : PointAtBase(req), PointAtRequest(req), StoreImageRequest(req) {} + LookoutRequest(HeadMotionType_t htype=noMotion, LookoutResultType_t rtype=noResult) : + headMotionType(htype), resultType(rtype), requestID(0) {} - virtual PointAtRequestType_t getPointAtType() const { return storeImage; } - virtual HeadMotionType_t getHeadMotionType() const { return pointAt; } -private: - StoreImageAtRequest& operator=(const StoreImageAtRequest&); -}; - -class StoreModeImageRequest : public StoreImageRequest { -public: - //! Constructor - StoreModeImageRequest(unsigned int num, unsigned int _interval=100, - Sketch (&func)()=VRmixin::sketchFromSeg, - unsigned int dur=1000) - : PointAtBase(CameraFrameOffset,dur), StoreImageRequest(func,dur), - numImages(num), interval(_interval) {}; + //! Destructor + virtual ~LookoutRequest() {} //! Copy constructor - StoreModeImageRequest(const StoreModeImageRequest& req) - : PointAtBase(req), StoreImageRequest(req), - numImages(req.numImages), interval(req.interval) {} - - unsigned int numImages; //!< number of image(sketch) over which to take mode - unsigned int interval; //!< interval between storing images -}; + LookoutRequest(const LookoutRequest &req) : + headMotionType(req.headMotionType), + resultType(req.resultType), + requestID(req.requestID) {} -class StoreModeImageAtRequest : public PointAtRequest, public StoreModeImageRequest { -public: - //! Constructor - StoreModeImageAtRequest (const Point& pt, unsigned int num, unsigned int _interval=100, - Sketch (&func)()=VRmixin::sketchFromSeg, unsigned int dur=1000) - : PointAtBase(CameraFrameOffset,dur), PointAtRequest(pt,dur), - StoreModeImageRequest(num,_interval,func) {} - //! Copy constructor - StoreModeImageAtRequest(const StoreModeImageAtRequest& req) - : PointAtBase(req), PointAtRequest(req), StoreModeImageRequest(req) {} + HeadMotionType_t headMotionType; + LookoutResultType_t resultType; + unsigned int requestID; //!< Non-zero value assigned when the request is added to the queue - virtual PointAtRequestType_t getPointAtType() const { return storeImage; } - virtual HeadMotionType_t getHeadMotionType() const { return pointAt; } private: - StoreModeImageAtRequest& operator=(const StoreModeImageAtRequest&); -}; + LookoutRequest& operator=(const LookoutRequest&); -class MeasureDistanceRequest : virtual public PointAtBase { public: - //! Constructor - MeasureDistanceRequest(unsigned int dur=1000) - : PointAtBase( -#ifdef TGT_ERS7 - NearIRFrameOffset -#else - IRFrameOffset -#endif - ,dur), val() {}; - //! Copy Constructor - MeasureDistanceRequest(const MeasureDistanceRequest& req) - : PointAtBase(req), val(req.val) {} - - virtual PointAtRequestType_t getPointAtType() const { return measureDist; } - float val; -}; + // ------------ Tasks that may be implemented during a scan or track request ---------------- + //! Base class for Lookout tasks; cannot instantiate directly + class Task { + public: + enum TaskType_t { noTask, visObjTask, visRegTask, irTask }; -class MeasureDistanceAtRequest : public PointAtRequest, public MeasureDistanceRequest { -public: - //! Constructor - MeasureDistanceAtRequest(const Point& pt, unsigned int dur=1000) - : PointAtBase(0/*overwritten by MeasureDistanceRequest constructor*/,dur), - PointAtRequest(pt,dur), MeasureDistanceRequest(dur) {}; - //! Copy constructor - MeasureDistanceAtRequest(const MeasureDistanceAtRequest& req) - : PointAtBase(req), PointAtRequest(req), MeasureDistanceRequest(req) {} - virtual PointAtRequestType_t getPointAtType() const { return measureDist; } - virtual HeadMotionType_t getHeadMotionType() const { return pointAt; } -}; + virtual TaskType_t getTaskType() const = 0; + virtual Task* clone() const = 0; -//-------------------------------------------- + //! Constructor + Task(AngPi _dTheta) : dTheta(_dTheta), data() {} -// ------------SCAN requests------------------- -class ScanRequest : public LookoutRequest { -public: - class Task; - virtual HeadMotionType_t getHeadMotionType() const { return scan; } - enum ScanType_t { line,area }; - virtual ScanType_t getScanType() const = 0; - vector tasks; - float scanSpeed; // in rad/msec - static const float defSpd; - ScanRequest(const ScanRequest& req) - : LookoutRequest(req), tasks(), scanSpeed(req.scanSpeed) { - for (vector::const_iterator it = req.tasks.begin(); - it != req.tasks.end(); it++) - addTask(**it); - } - ScanRequest(float _speed=defSpd) - : tasks(), scanSpeed(_speed) {} - ScanRequest(const Task& _task, float _speed=defSpd) - : tasks(), scanSpeed(_speed) { addTask(_task); } - void addTask(const Task& t) { - switch (t.getTaskType()) { - case Task::visReg: - tasks.push_back(new VisionRegionTask(*dynamic_cast(&t))); break; - case Task::visObj: - tasks.push_back(new VisionObjectTask(*dynamic_cast(&t))); break; - case Task::ir: - tasks.push_back(new IRTask(*dynamic_cast(&t))); break; - default: return; - }; - } - virtual ~ScanRequest() { - for (vector::const_iterator it = tasks.begin(); - it != tasks.end(); it++) - delete *it; - } + //! Copy constructor + Task(const Task& t) : dTheta(t.dTheta), data(t.data) {} - // ------------Tasks may be implemented during scan ------------------- - class Task { - public: - enum taskType_t { none, visObj, visReg, ir }; - virtual taskType_t getTaskType() const = 0;// { return none; } + //! Destructor virtual ~Task() {} - AngPi interval; //!< interval of measurements - vector data; //!< measured data stored here in base frame coordinates - Task(const Task& t) : interval(t.interval), data(t.data) {} - protected: - Task(AngPi _interval) : interval(_interval), data() {} - private: + + AngPi dTheta; //!< angular step size during scan + std::vector data; //!< measured data stored here in base frame coordinates Task& operator=(const Task&); }; class IRTask : public Task { public: - IRTask(AngPi _interval) : Task(_interval) {} + IRTask(AngPi _dTheta) : Task(_dTheta) {} IRTask(const IRTask& t) : Task(t) {} - virtual taskType_t getTaskType() const { return ir; } - // virtual ~IRTask() { cout << "deleting IRTask " << this << endl; } + virtual TaskType_t getTaskType() const { return irTask; } + virtual Task* clone() const { return new IRTask(*this); } }; - //base class for vision tasks, should not be instantiated + //! Base class for vision tasks, should not be instantiated class VisionTask : public Task { public: - virtual taskType_t getTaskType() const { return none; } - set index; + virtual TaskType_t getTaskType() const { return noTask; } + std::set index; VisionTask(const VisionTask& vt) : Task(vt), index(vt.index) {} - protected: - VisionTask(const set& _index, AngPi _interval) - : Task(_interval), index(_index) {} - VisionTask(int _index, AngPi _interval) - : Task(_interval), index() { index.insert(_index); } + VisionTask(const std::set& _index, AngPi _dTheta) + : Task(_dTheta), index(_index) {} + VisionTask(int _index, AngPi _dTheta) + : Task(_dTheta), index() { index.insert(_index); } + virtual Task* clone() const { return new VisionTask(*this); } }; //! Uses bult-in object detectors (like pink ball detector) via VisionObjectEvent stream class VisionObjectTask : public VisionTask { public: - VisionObjectTask(const set& sid, AngPi _interval) - : VisionTask(sid,_interval) {} + VisionObjectTask(const std::set& sid, AngPi _dTheta=0) + : VisionTask(sid,_dTheta) {} VisionObjectTask(const VisionObjectTask& vot) : VisionTask(vot) {} - virtual taskType_t getTaskType() const { return visObj; } + virtual TaskType_t getTaskType() const { return visObjTask; } + virtual Task* clone() const { return new VisionObjectTask(*this); } }; //! Uses built-in colored region detectors via Region event stream class VisionRegionTask : public VisionTask { public: - VisionRegionTask(const set& colorIndex, AngPi _interval, + VisionRegionTask(const std::set& colorIndex, AngPi _dTheta=0, unsigned int _minArea=200) - : VisionTask(colorIndex,_interval), minArea(_minArea) {} - VisionRegionTask(int colorIndex, AngPi _interval, + : VisionTask(colorIndex,_dTheta), minArea(_minArea) {} + VisionRegionTask(int colorIndex, AngPi _dTheta, unsigned int _minArea=200) - : VisionTask(colorIndex,_interval), minArea(_minArea) {} + : VisionTask(colorIndex,_dTheta), minArea(_minArea) {} VisionRegionTask(const VisionRegionTask& vrt) : VisionTask(vrt), minArea(vrt.minArea) {} - virtual taskType_t getTaskType() const { return visReg; } + virtual TaskType_t getTaskType() const { return visRegTask; } + virtual Task* clone() const { return new VisionRegionTask(*this); } unsigned int minArea; }; + // ---------------- end of Task classes ---------------- + }; -class ScanAlongLineRequest : public ScanRequest { +//================ LookoutPointRequest ================ + +//! Take a picture of or measure a distance to a point in space +class LookoutPointRequest : public LookoutRequest { public: - ScanAlongLineRequest(const Point& bPt, const Point& ePt, float _speed=defSpd) - : ScanRequest(_speed), beginPt(bPt), endPt(ePt) {} - ScanAlongLineRequest(const ScanAlongLineRequest& req) - : ScanRequest(req), beginPt(req.beginPt), endPt(req.endPt) {} - // virtual HeadMotionType_t getHeadMotionType() const { return scanLine; } - virtual ScanType_t getScanType() const { return line; } - Point beginPt, endPt; + //! Constructor + LookoutPointRequest() : + LookoutRequest(noMotion,imageResult), +#ifdef TGT_HAS_CAMERA + joint(CameraFrameOffset), +#else + joint(0), +#endif + toBaseMatrix(), + gazePt(), motionSettleTime(1000), + numSamples(1), sampleCounter(0), sampleInterval(0), + image(), sketchFunc(VRmixin::sketchFromSeg) + {} + + //! Copy constructor + LookoutPointRequest(const LookoutPointRequest &p) + : LookoutRequest(p), joint(p.joint), toBaseMatrix(p.toBaseMatrix), + gazePt(p.gazePt), motionSettleTime(p.motionSettleTime), + numSamples(p.numSamples), sampleCounter(p.sampleCounter), sampleInterval(p.sampleInterval), + image(p.image), sketchFunc(p.sketchFunc) + {} + +public: + void setTarget(const Point &target) { + gazePt = target; + headMotionType = pointAt; + } + + unsigned int joint; //!< joint reference frame from which base frame transformation matrix is created, e.g., Camera, IR, etc. + NEWMAT::Matrix toBaseMatrix; //!< transformation matrix from joint frame to base frame + Point gazePt; //!< point to look at; can be in either egocentric or allocentric reference frame + unsigned int motionSettleTime; //!< Time in msec to wait before taking measurements or throwing completion event after head reaches gazePt. + int numSamples; //!< Number of samples to take; if > 1, return the mode (for pixels) or median (for distance) + int sampleCounter; //!< Number of samples collected so far + int sampleInterval; //!< Interval in msec between successive samples + Sketch image; // (*sketchFunc)(); // tasks; + float scanSpeed; //!< speed in rad/msec + ShapeRoot searchArea; + unsigned int motionSettleTime; + + static const float defSpd; //!< default scan speed + + //! Constructor + LookoutScanRequest(float _speed=defSpd): + LookoutRequest(scan,interestPoints), + tasks(), scanSpeed(_speed), searchArea(), motionSettleTime(1000) {} + + //! Constructor + LookoutScanRequest(const Task& _task, float _speed=defSpd) : + LookoutRequest(scan,interestPoints), tasks(), scanSpeed(_speed), searchArea(), motionSettleTime(1000) + { addTask(_task); } + + //! Copy constructor + LookoutScanRequest(const LookoutScanRequest& req) + : LookoutRequest(req), tasks(), scanSpeed(req.scanSpeed), searchArea(req.searchArea), motionSettleTime(req.motionSettleTime) + { + for (std::vector::const_iterator it = req.tasks.begin(); + it != req.tasks.end(); it++) + addTask(**it); + } + + //! Destructor + virtual ~LookoutScanRequest(); + + void addTask(const Task& t) { tasks.push_back(t.clone()); } + +}; // end of LookoutScanRequest + + + +// ================ LookoutTrackRequest ================ + +// ! Track an object with the head +class LookoutTrackRequest : public LookoutRequest { +public: + + friend class Lookout; + + //! Constructor + LookoutTrackRequest(const ShapeRoot& target=ShapeRoot()) + : LookoutRequest(track), targetShape(target), + minBlobArea(80), exitTest(NULL), cindex(0) {} + + //! Copy constructor + LookoutTrackRequest(const LookoutTrackRequest& req) + : LookoutRequest(req), targetShape(req.targetShape), + minBlobArea(req.minBlobArea), exitTest(req.exitTest), cindex(req.cindex) {} + + ShapeRoot targetShape; + int minBlobArea; //!< Minimum acceptable size of a region + bool (*exitTest)(); //!< If true, target has been found + +private: + color_index cindex; + + LookoutTrackRequest& operator=(const LookoutTrackRequest&); //!< don't call this }; -//-------------------------------------------- -// ------------TRACK requests------------------- -class TrackRequest : public LookoutRequest { +// ================ LookoutSearchRequest ================ + +//! Search for an object and return when found +class LookoutSearchRequest : public LookoutRequest { public: - TrackRequest(const vector& _landmarks, const ShapeRoot& _area) - : landmarks(_landmarks), area(_area), lmLocation(), lmInView(false) {} - TrackRequest(const vector& _landmarks, const Point& pt, const ShapeRoot& _area) - : landmarks(_landmarks), area(_area), lmLocation(pt), lmInView(false) {} - virtual HeadMotionType_t getHeadMotionType() const { return track; } - vector landmarks; - ShapeRoot area; - Point lmLocation; - bool lmInView; + + friend class Lookout; + + //! Constructor + LookoutSearchRequest(const ShapeRoot& target=ShapeRoot()) + : LookoutRequest(search,imageResult), targetShape(target), + minBlobArea(80), exitTest(NULL), cindex(0) {} + + //! Copy constructor + LookoutSearchRequest(const LookoutSearchRequest& req) + : LookoutRequest(req), targetShape(req.targetShape), + minBlobArea(req.minBlobArea), exitTest(req.exitTest), cindex(req.cindex) {} + + ShapeRoot targetShape; + int minBlobArea; //!< Minimum acceptable size of a region + bool (*exitTest)(); //!< If true, target has been found + +private: + color_index cindex; + + LookoutSearchRequest& operator=(const LookoutSearchRequest&); //!< don't call this }; -//-------------------------------------------- + } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/MapBuilder.cc ./DualCoding/MapBuilder.cc --- ../Tekkotsu_3.0/DualCoding/MapBuilder.cc 2006-10-03 19:26:06.000000000 -0400 +++ ./DualCoding/MapBuilder.cc 2007-11-18 01:47:02.000000000 -0500 @@ -1,31 +1,36 @@ //-*-c++-*- #include "Events/EventRouter.h" -#include "Events/LookoutEvents.h" #include "Events/TextMsgEvent.h" +#include "Events/LookoutEvents.h" #include "Motion/HeadPointerMC.h" #include "Shared/mathutils.h" #include "Shared/newmat/newmat.h" -#include "Measures.h" +#include "Shared/Measures.h" #include "EllipseData.h" // for extractEllipses #include "SphereData.h" // for extractSpheres #include "BlobData.h" // for extractSpheres #include "PolygonData.h" // for extractPolygons +#include "SphereData.h" +#include "TargetData.h" // for extractTarget #include "ShapeRoot.h" #include "ShapeLine.h" #include "ShapeEllipse.h" #include "ShapeBlob.h" #include "ShapePolygon.h" +#include "ShapeSphere.h" +#include "ShapeTarget.h" #include "Sketch.h" // for NEW_SKETCH #include "visops.h" #include "VRmixin.h" -#include "MapBuilder.h" +#include "LookoutRequests.h" #include "Lookout.h" +#include "MapBuilder.h" -namespace DualCoding { +using namespace std; -typedef map > colorMap; +namespace DualCoding { inline float distSq(const NEWMAT::ColumnVector& vec) { return vec(1)*vec(1) + vec(2)*vec(2) + vec(3)*vec(3); @@ -33,31 +38,46 @@ MapBuilder::MapBuilder() : BehaviorBase("MapBuilder"), - camSkS(VRmixin::getCamSkS()), - camShS(VRmixin::getCamSkS().getDualSpace()), - groundShS(VRmixin::groundShS), - local(maps::local,VRmixin::getLocalSkS()), world(maps::world,VRmixin::getWorldSkS()), - cur(&local), xres(camSkS.getWidth()), yres(camSkS.getHeight()), - ground_plane(4), theAgent(VRmixin::theAgent), + camSkS(VRmixin::getCamSkS()), camShS(camSkS.getDualSpace()), + groundShS(VRmixin::getGroundShS()), + localSkS(VRmixin::getLocalSkS()), localShS(localSkS.getDualSpace()), + worldSkS(VRmixin::getWorldSkS()), worldShS(worldSkS.getDualSpace()), + xres(camSkS.getWidth()), yres(camSkS.getHeight()), + ground_plane(4), + theAgent(VRmixin::theAgent), localToWorldMatrix(NEWMAT::IdentityMatrix(4)), worldToLocalTranslateMatrix(NEWMAT::IdentityMatrix(4)), worldToLocalRotateMatrix(NEWMAT::IdentityMatrix(4)), badGazePoints(), - agentAtOrigin(true), requests(), curReq(NULL), idCounter(0), maxDistSq(0), - pointAtID(Lookout::Invalid_LO_ID), scanID(Lookout::Invalid_LO_ID), + requests(), curReq(NULL), idCounter(0), maxDistSq(0), + pointAtID(Lookout::invalid_LO_ID), scanID(Lookout::invalid_LO_ID), nextGazePoint() {} void MapBuilder::DoStart() { - cout << "MapBuilder::DoStart()\n"; + if ( verbosity & MBVstart ) + cout << "MapBuilder::DoStart()\n"; BehaviorBase::DoStart(); - erouter->addListener(this,EventBase::textmsgEGID); + + camSkS.clear(); camShS.clear(); + groundShS.clear(); + localSkS.clear(); localShS.clear(); + worldSkS.clear(); worldShS.clear(); + badGazePoints.clear(); + setAgent(Point(0,0,0),0); + + erouter->addListener(this,EventBase::textmsgEGID); // listen for commands to move to next gaze point + erouter->addListener(this,EventBase::lookoutEGID); // listen for Lookout completion events } +bool MapBuilder::retain = true; +MapBuilder::MapBuilderVerbosity_t MapBuilder::verbosity = -1U; + /* - since MapBuilder is constructed as static from VRmixin, - destructor doesn't get called until dog shuts down. - And we have to do everything assumed to be done in destructor in DoStop, - such as clearing request queue and setting parameters to the initial values as set in constructor + Since MapBuilder is constructed as static from VRmixin, the + destructor doesn't get called until the robot shuts down. We have + to do everything assumed to be done in destructor in DoStop, such as + clearing the request queue and setting parameters to the initial + values as set in the constructor. */ void MapBuilder::DoStop() { cout << "MapBuilder::DoStop()\n"; @@ -66,153 +86,168 @@ requests.pop(); } curReq = NULL; - camSkS.clear(); camShS.clear(); - groundShS.clear(); - local.SkS.clear(); local.ShS.clear(); - world.SkS.clear(); world.ShS.clear(); - - badGazePoints.clear(); - local.gazePts.clear(); - world.gazePts.clear(); - setAgent(Point(0,0,0),0); - BehaviorBase::DoStop(); } -unsigned int MapBuilder::executeRequest(const MapBuilderRequest& req) { - switch (req.getRequestType()) { - case MapBuilderRequest::takeSnap: - if (const TakeSnapAtRequest* snapAtReq = dynamic_cast(&req)) - requests.push(new TakeSnapAtRequest(*snapAtReq)); - else - requests.push(new TakeSnapRequest(*dynamic_cast(&req))); - break; - case MapBuilderRequest::localMap: - if (const LocalMapTestRequest* testReq = dynamic_cast(&req)) - requests.push(new LocalMapTestRequest(*testReq)); - else - requests.push(new LocalMapRequest(*dynamic_cast(&req))); - break; - case MapBuilderRequest::worldMap: - if (const WorldMapTestRequest* testReq = dynamic_cast(&req)) - requests.push(new WorldMapTestRequest(*testReq)); - else - requests.push(new WorldMapRequest(*dynamic_cast(&req))); - break; - default: return -1U; - }; - requests.back()->requestID = idCounter++; - // cout << "MapBuilder::executeRequest: new request " << requests.back()->requestID - // << " added to the queue\n"; - if (requests.size() == 1) { - erouter->addListener(this,EventBase::lookoutEGID); - executeRequest(); - } - return requests.back()->requestID; +unsigned int MapBuilder::executeRequest(const MapBuilderRequest& req, unsigned int *req_id) { + MapBuilderRequest *newreq = new MapBuilderRequest(req); + const unsigned int this_request = ++idCounter; + newreq->requestID = this_request; + if ( req_id != NULL ) *req_id = this_request; + requests.push(newreq); + executeRequest(); + return this_request; } void MapBuilder::executeRequest() { - if ( requests.empty() || curReq != NULL ) return; + if ( curReq != NULL || requests.empty() ) return; curReq = requests.front(); - cout << "MapBuilder::executeRequest: execute " << curReq->requestID << endl; - erouter->postEvent(EventBase::mapbuilderEGID, requests.front()->requestID, EventBase::activateETID,0); - if (curReq->groundPlaneAssumption == MapBuilderRequest::onStand) - calculateGroundPlane(MapBuilderRequest::onStand); - - if (curReq->getRequestType() == MapBuilderRequest::takeSnap) - if (const TakeSnapAtRequest* snapAtReq = dynamic_cast(curReq)) - storeImageAt(snapAtReq->gazePt); - else - storeImage(); - else { - const LocalMapRequest& curMapReq = *dynamic_cast (&(*curReq)); - maxDistSq = curMapReq.maxDist*curMapReq.maxDist; - cur = (&curMapReq.shs==&local.ShS) ? &local : &world; - if (curMapReq.clearShapes) { // erase shapes and gaze points, start from scratch - cur->ShS.clear(); - cur->SkS.clear(); - cur->gazePts.clear(); - cur->baseToCamMats.clear(); - } - defineGazePts(cur->gazePts, curMapReq.area, curMapReq.doScan); - if ( determineNextGazePoint() ) - moveToNextGazePoint(); - else - requestComplete(); + if ( verbosity & MBVexecute ) + cout << "MapBuilder::executeRequest: execute " << curReq->requestID << endl; + erouter->postEvent(EventBase::mapbuilderEGID, curReq->requestID, EventBase::activateETID,0); + if ( (curReq->pursueShapes || curReq->doScan || curReq->worldTargets.size()>0) && + curReq->getRequestType() == MapBuilderRequest::cameraMap ) { + cout << "Warning: switching MapBuilderRequest type from cameraMap to localMap because request parameters require head movement." << endl; + curReq->requestType = MapBuilderRequest::localMap; } + + calculateGroundPlane(); + maxDistSq = curReq->maxDist*curReq->maxDist; + + if ( curReq->clearShapes ) { + curReq->gazePts.clear(); + curReq->baseToCamMats.clear(); + switch ( curReq->getRequestType() ) { + case MapBuilderRequest::localMap: + localShS.clear(); + localSkS.clear(); + break; + case MapBuilderRequest::worldMap: + worldShS.clear(); + worldSkS.clear(); + break; + default: + break; + } + } + + if ( curReq->immediateRequest() ) + grabCameraImageAndGo(); + else if ( !curReq->searchArea.isValid() & curReq->worldTargets.size() == 0 ) + storeImage(); + else { + defineGazePts(); + if ( curReq->doScan == true ) + return; // wait for Lookout to finish scanning + else if ( curReq->worldTargets.size() > 0 ) + doNextSearch(); + else if ( determineNextGazePoint() ) + moveToNextGazePoint(); + else + requestComplete(); + } } +/* +There are three kinds of events for MapBuilder::processEvent to handle: + +1. TextMsg event saying to move to the next gaze point; only needed +when we've asserted manual control of gaze point sequencing for +debugging. + +2. Lookout event announcing that a "point at" request is complete and +an image has been stored. We can now go ahead and process that image. + +3. Lookout event announcing that a "scan" request is complete and gaze +points have been stored. We can now start examining those gaze points. +*/ + + void MapBuilder::processEvent(const EventBase &e) { - cout << "MapBuilder::processEvent got " << e.getDescription() << endl; + if ( curReq == NULL) return; + if ( verbosity & MBVevents ) + cout << "MapBuilder got event " << e.getName() << "; current pointAtID=" << pointAtID + << " scanID=" << scanID << endl; + switch ( e.getGeneratorID() ) { - case EventBase::textmsgEGID: { - const TextMsgEvent &txtev = dynamic_cast(e); - if ( strcmp(txtev.getText().c_str(),"MoveHead") == 0 ) + case EventBase::textmsgEGID: + if ( strcmp(dynamic_cast(e).getText().c_str(),"MoveHead") == 0 ) moveToNextGazePoint(true); - break; } + break; + case EventBase::lookoutEGID: - // image stored, extract shapes and extend local/world shape space - cout << "MapBuilder got event " << e.getName() << " pointAtID=" << pointAtID << endl; - if (e.getSourceID() == pointAtID && e.getTypeID() == EventBase::deactivateETID) { - const Sketch& camImg = dynamic_cast(&e)->getSketch(); - NEW_SKETCH(camFrame, uchar, camImg); - const NEWMAT::Matrix& camToBase = dynamic_cast(&e)->toBaseMatrix; - const NEWMAT::Matrix baseToCam = camToBase.i(); - processImage(camFrame, camToBase, baseToCam); - if (curReq->getRequestType() == MapBuilderRequest::takeSnap) { - requestComplete(); - return; - } - if (cur->space == maps::local) - extendLocal(baseToCam); - else - extendWorld(baseToCam); - } - // gaze points defined by scan, start constructing map - else if (e.getSourceID() == scanID && e.getTypeID() != EventBase::activateETID) { + if ( e.getSourceID() == pointAtID ) + processImage(dynamic_cast(e)); + else if ( e.getSourceID() == scanID ) { const vector& pts = dynamic_cast(&e)->getTasks().front()->data; - cur->gazePts.insert(cur->gazePts.end(),pts.begin(), pts.end()); + cout << " doScan found " << pts.size() << " interest points." << endl; + curReq->gazePts.insert(curReq->gazePts.end(),pts.begin(), pts.end()); } - else - cout << "MapBuilder::processEvent(): unknown event " << e.getDescription() - << " pointAtID=" << pointAtID << endl; - - if ( requestExitTest() || !determineNextGazePoint() ) + else { + cout << "MapBuilder: unexpected Lookout event " << e.getDescription() + << ", current pointAtID=" << pointAtID << ", scanID=" << scanID << endl; + return; + } + // we've dealt with the event (processed an image or did a scan); now see what we should do next + if ( requestExitTest() ) requestComplete(); - else + else if ( curReq->worldTargets.size() > 0 ) + doNextSearch(); + else if ( determineNextGazePoint() ) moveToNextGazePoint(); + else + requestComplete(); break; + default: - cout << "Unexpected event " << e.getDescription() << endl; + cout << "MapBuilder received unexpected event: " << e.getDescription() << endl; } } -void MapBuilder::processImage(const Sketch& camFrame, - const NEWMAT::Matrix& camToBase, - const NEWMAT::Matrix& baseToCam) { - if (curReq->groundPlaneAssumption == MapBuilderRequest::onLegs) - calculateGroundPlane(MapBuilderRequest::onLegs); +void MapBuilder::processImage(const LookoutSketchEvent &e) { + camSkS.clear(); + if ( curReq->rawY ) { + NEW_SKETCH(rawY, uchar, VRmixin::sketchFromRawY()); + } + NEW_SKETCH(camFrame, uchar, e.getSketch()); + const NEWMAT::Matrix& camToBase = e.toBaseMatrix; + const NEWMAT::Matrix baseToCam = camToBase.i(); getCameraShapes(camFrame); - projectToGround(camToBase); - filterGroundShapes(baseToCam); + if (curReq->userCamProcessing != NULL) (*curReq->userCamProcessing)(); + if (curReq->getRequestType() > MapBuilderRequest::cameraMap) { + projectToGround(camToBase); + if (curReq->userGroundProcessing != NULL) (*curReq->userGroundProcessing)(); + filterGroundShapes(baseToCam); + } + switch ( curReq->getRequestType() ) { + case MapBuilderRequest::cameraMap: + case MapBuilderRequest::groundMap: + break; + case MapBuilderRequest::localMap: + extendLocal(baseToCam); + if (curReq->userLocalProcessing != NULL) (*curReq->userLocalProcessing)(); + break; + case MapBuilderRequest::worldMap: + extendWorld(baseToCam); + if (curReq->userWorldProcessing != NULL) (*curReq->userWorldProcessing)(); + } } bool MapBuilder::determineNextGazePoint() { - if (&cur->ShS == &world.ShS && !agentAtOrigin) { - cur->ShS.applyTransform(worldToLocalTranslateMatrix); - cur->ShS.applyTransform(worldToLocalRotateMatrix); - bool b = determineNextGazePoint(cur->ShS.allShapes()) || determineNextGazePoint(cur->gazePts); - cur->ShS.applyTransform(localToWorldMatrix); // transform back + if (curReq->getRequestType() == MapBuilderRequest::worldMap) { + worldShS.applyTransform(worldToLocalTranslateMatrix,egocentric); + worldShS.applyTransform(worldToLocalRotateMatrix,egocentric); + bool b = determineNextGazePoint(worldShS.allShapes()) || determineNextGazePoint(curReq->gazePts); + worldShS.applyTransform(localToWorldMatrix,allocentric); // transform back return b; } else - return determineNextGazePoint(cur->ShS.allShapes()) || determineNextGazePoint(cur->gazePts); + return determineNextGazePoint(localShS.allShapes()) || determineNextGazePoint(curReq->gazePts); } + bool MapBuilder::determineNextGazePoint(const vector& shapes) { - const LocalMapRequest *locReq = dynamic_cast(curReq); - if ( locReq == NULL || ! locReq->pursueShapes ) - return false; + if ( ! curReq->pursueShapes ) return false; HeadPointerMC headpointer_mc; for (vector::const_iterator it = shapes.begin(); it != shapes.end(); it++) { @@ -223,12 +258,15 @@ bool isLine = (*it)->isType(lineDataType); EndPoint p[2] = { isLine ? ld->end1Pt(): pd->end1Pt(), isLine ? ld->end2Pt() : pd->end2Pt()}; for (int i = 0; i < 2; i++) { - if (!p[i].isValid() && !isBadGazePoint(p[i]) + if ( !p[i].isValid() && !isBadGazePoint(p[i] ) && badGazePoints.end() == find(badGazePoints.begin(), badGazePoints.end(), (Point) p[i])) { - cout << "take snap at endpoint" << (i+1) << " of shape id " + cout << "Take image at endpoint" << (i+1) << " of shape id " << (*it)->getId() << " at " << p[i] << endl; - if (!headpointer_mc.lookAtPoint(p[i].coordX(),p[i].coordY(),p[i].coordZ())) + if ( !headpointer_mc.lookAtPoint(p[i].coordX(),p[i].coordY(),p[i].coordZ()) ) { + if ( verbosity & MBVbadGazePoint ) + cout << "MapBuilder noting unreachable gaze point " << (Point)p[i] << endl; badGazePoints.push_back((Point)p[i]); + } nextGazePoint = p[i]; return true; } @@ -236,11 +274,12 @@ } // look for shapes w/ <2 confidence if ((!(*it)->isType(agentDataType)) && + (*it)->getLastMatchId() != 0 && (*it)->getConfidence() <= 1 && ! isBadGazePoint((*it)->getCentroid()) && badGazePoints.end() == find(badGazePoints.begin(), badGazePoints.end(), (*it)->getCentroid())) { const Point pt = (*it)->getCentroid(); - cout << "take snap at shape " << (*it)->getId() + cout << "take image at shape " << (*it) << " (confidence level: " << (*it)->getConfidence() << ")" << endl; cout << " at " << pt << endl; if (! headpointer_mc.lookAtPoint(pt.coordX(),pt.coordY(),pt.coordZ())) @@ -248,29 +287,21 @@ nextGazePoint = pt; return true; } - cout << "Skipping shape " << (*it)->getId() - << " (confidence level: " << (*it)->getConfidence() << ")" << endl; + // cout << "Skipping shape " << (*it)->getId() + // << " (confidence level: " << (*it)->getConfidence() << ")" << endl; } return false; } bool MapBuilder::determineNextGazePoint(vector& gazePts) { - HeadPointerMC headpointer_mc; for (vector::iterator it = gazePts.begin(); it != gazePts.end(); it++) { - cout << "look at pre-defined gazePt: " << *it << endl; nextGazePoint = *it; gazePts.erase(it); - return true; + if ( ! isBadGazePoint(nextGazePoint) ) + return true; } - /* - cout << "Gaze points exhausted; " << badGazePoints.size() << " bad gaze points were eliminated: " << endl; - for (vector::const_iterator bad_it = badGazePoints.begin(); - bad_it != badGazePoints.end(); bad_it++) - cout << *bad_it << " "; - cout << endl; - */ return false; } @@ -279,142 +310,172 @@ cout << "curReq == NULL in moveToNextGazePoint!" << endl; return; } - cout << "curReq == " << (unsigned int)curReq << endl; - const LocalMapRequest* locReq = dynamic_cast(curReq); - if ( locReq != NULL && locReq->manualHeadMotion && manualOverride==false ) { + if ( (verbosity & MBVnextGazePoint) || (curReq->manualHeadMotion && manualOverride==false) ) + cout << "moveToNextGazePoint " << nextGazePoint << endl; + if ( curReq->manualHeadMotion && manualOverride==false ) { cout << "To proceed to this gaze point: !msg MoveHead" << endl; return; } - storeImageAt(nextGazePoint); + else + storeImage(nextGazePoint,true); } +void MapBuilder::doNextSearch() { + LookoutSearchRequest *curLSR = curReq->worldTargets.front(); + curReq->worldTargets.pop(); + pointAtID = VRmixin::lookout.executeRequest(*curLSR); +} + bool MapBuilder::isBadGazePoint(const Point& Pt) const { const coordinate_t x = Pt.coordX(); const coordinate_t y = Pt.coordY(); - return ( x*x + y*y > maxDistSq || - x < -30.0); + return ( x*x + y*y > maxDistSq || x < -30.0); } -void MapBuilder::storeImageAt(const Point& pt) { - pointAtID = VRmixin::lookout.executeRequest(StoreImageAtRequest(pt)); - cout << "MapBuilder sent new storeImageAt request; pointAtID=" << pointAtID << endl; +void MapBuilder::storeImage(const Point& pt, bool havepoint) { + LookoutPointRequest lreq; + if ( havepoint ) + lreq.setTarget(pt); + else + lreq.setHeadMotionType(LookoutRequest::noMotion); + lreq.motionSettleTime = curReq->motionSettleTime; + lreq.numSamples = curReq->numSamples; + lreq.sampleInterval = curReq->sampleInterval; + pointAtID = VRmixin::lookout.executeRequest(lreq); } -void MapBuilder::storeImage() { - pointAtID = VRmixin::lookout.executeRequest(StoreImageRequest()); - cout << "MapBuilder sent new storeImage request; pointAtID=" << pointAtID << endl; +void MapBuilder::grabCameraImageAndGo() { + // This is a performance hack to avoid calling the Lookout or event + // router, so the MapBuilder can produce results very quickly when + // we need real-time performance, e.g., for particle filtering where + // we take multiple snapshots. + pointAtID = 0; + Sketch camFrame(VRmixin::sketchFromSeg()); +#ifdef TGT_HAS_CAMERA + const NEWMAT::Matrix camToBase = kine->jointToBase(CameraFrameOffset); +#else + NEWMAT::Matrix camToBase(4,4); + camToBase << ROBOOP::fourbyfourident; +#endif + LookoutSketchEvent dummy(true, camFrame, camToBase, + EventBase::lookoutEGID, pointAtID, EventBase::deactivateETID); + processImage(dummy); + requestComplete(); } -void MapBuilder::scan(ScanRequest& req) { - set colors; - for (colorMap::const_iterator it1 = curReq->objectColors.begin(); +void MapBuilder::scanForGazePts() { + LookoutScanRequest lreq; + lreq.searchArea = curReq->searchArea; + lreq.motionSettleTime = curReq->motionSettleTime; + set colors; // colors of all the shape types we're looking for + for (map >::const_iterator it1 = curReq->objectColors.begin(); it1 != curReq->objectColors.end(); it1++) - for (set::const_iterator it2 = it1->second.begin(); + for (set::const_iterator it2 = it1->second.begin(); it2 != it1->second.end(); it2++) colors.insert(*it2); - req.addTask(ScanRequest::VisionRegionTask(colors,M_PI/18)); - scanID = VRmixin::lookout.executeRequest(req); + lreq.addTask(LookoutScanRequest::VisionRegionTask(colors,curReq->dTheta)); + scanID = VRmixin::lookout.executeRequest(lreq); } void MapBuilder::extendLocal(const NEWMAT::Matrix& baseToCam) { - vector all = local.ShS.allShapes(); - removeNoise(local.ShS, baseToCam); - matchSrcToDst(groundShS,local.ShS,curReq->objectColors[polygonDataType]); - removeGazePts(local.gazePts, baseToCam); - local.baseToCamMats.push_back(baseToCam); + vector all = localShS.allShapes(); + removeNoise(localShS, baseToCam); + matchSrcToDst(groundShS,localShS,curReq->objectColors[polygonDataType]); + removeGazePts(curReq->gazePts, baseToCam); + curReq->baseToCamMats.push_back(baseToCam); } void MapBuilder::extendWorld(const NEWMAT::Matrix& baseToCam) { - if (!agentAtOrigin) { - world.ShS.applyTransform(worldToLocalTranslateMatrix); - world.ShS.applyTransform(worldToLocalRotateMatrix); - } - removeNoise(world.ShS, baseToCam); - matchSrcToDst(groundShS,world.ShS,curReq->objectColors[polygonDataType]); - if (!agentAtOrigin) - world.ShS.applyTransform(localToWorldMatrix); - removeGazePts(world.gazePts,baseToCam); - world.baseToCamMats.push_back(baseToCam); + worldShS.applyTransform(worldToLocalTranslateMatrix,egocentric); + worldShS.applyTransform(worldToLocalRotateMatrix,egocentric); + removeNoise(worldShS, baseToCam); + matchSrcToDst(groundShS,worldShS,curReq->objectColors[polygonDataType]); + worldShS.applyTransform(localToWorldMatrix,allocentric); + removeGazePts(curReq->gazePts,baseToCam); + curReq->baseToCamMats.push_back(baseToCam); } bool MapBuilder::requestExitTest() { - if (const LocalMapTestRequest* localTestReq = dynamic_cast(curReq)) - return ((*localTestReq->exitTest)()); - else if (const WorldMapTestRequest* worldTestReq = dynamic_cast(curReq)) - return ((*worldTestReq->exitTest)()); - else + if ( curReq->exitTest == NULL ) return false; + else + return (*curReq->exitTest)(); } void MapBuilder::requestComplete() { const unsigned int reqID = curReq->requestID; - cout << "MapBuilderRequest " << reqID << " complete\n"; + if ( verbosity & MBVcomplete ) + cout << "MapBuilderRequest " << reqID << " complete\n"; delete curReq; curReq = NULL; requests.pop(); + erouter->postEvent(EventBase::mapbuilderEGID, reqID, EventBase::deactivateETID,0); if ( requests.empty() ) - erouter->removeListener(this,EventBase::lookoutEGID); // don't need to listen to Lookout events when there is no request pending - erouter->postEvent(EventBase::mapbuilderEGID, reqID, EventBase::statusETID,0); - executeRequest(); // execute next request AFTER status event has finished processing + VRmixin::lookout.relax(); + else + executeRequest(); // execute next request AFTER deactivate event has finished processing } -void MapBuilder::setAgent(const Point &location, const AngTwoPi heading) { - theAgent->setCentroidPt(location); - theAgent->setOrientation(heading); - const coordinate_t dx = location.coordX(); - const coordinate_t dy = location.coordY(); - const coordinate_t dz = location.coordZ(); - float localToWorld[] = {cos(heading), -sin(heading), 0, dx, - sin(heading),cos(heading), 0, dy, - 0, 0, 1, dz, - 0 ,0, 0, 1}; +void MapBuilder::setAgent(const Point &worldLocation, const AngTwoPi worldHeading) { + if ( verbosity & MBVsetAgent ) + cout << "Agent now at " << worldLocation << " hdg " << worldHeading + << " (= " << float(worldHeading)*180/M_PI << " deg.)" << endl; + theAgent->setCentroidPt(worldLocation); + theAgent->setOrientation(worldHeading); + const coordinate_t dx = worldLocation.coordX(); + const coordinate_t dy = worldLocation.coordY(); + const coordinate_t dz = worldLocation.coordZ(); + float const c = cos(worldHeading); + float const s = sin(worldHeading); + float localToWorld[] = {c, -s, 0, dx, + s, c, 0, dy, + 0, 0, 1, dz, + 0 , 0, 0, 1}; float worldToLocalTrans[] = {1, 0, 0, -dx, 0, 1, 0, -dy, 0, 0, 1, -dz, - 0 ,0, 0, 1}; - float worldToLocalRotate[] = {cos(heading), sin(heading), 0, 0, - -sin(heading),cos(heading), 0, 0, - 0, 0, 1, 0, - 0 ,0, 0, 1}; + 0 ,0, 0, 1}; + float worldToLocalRotate[] = { c, s, 0, 0, + -s, c, 0, 0, + 0, 0, 1, 0, + 0, 0, 0, 1}; localToWorldMatrix << localToWorld; worldToLocalTranslateMatrix << worldToLocalTrans; worldToLocalRotateMatrix << worldToLocalRotate; - agentAtOrigin = (heading == 0 || heading == 2*M_PI) && dx == 0 && dy == 0; } void MapBuilder::moveAgent(coordinate_t const local_dx, coordinate_t const local_dy, AngTwoPi dtheta) { + Point const agentLoc = theAgent->getCentroid(); AngTwoPi const heading = theAgent->getOrientation(); float const c = cos(heading); float const s = sin(heading); float const dx = local_dx*c + local_dy*-s; float const dy = local_dx*s + local_dy*c; - setAgent(Point(dx+theAgent->getCentroid().coordX(), - dy+theAgent->getCentroid().coordY(), - theAgent->getCentroid().coordZ()), - dtheta+heading); + setAgent(agentLoc + Point(dx,dy,agentLoc.coordZ(),allocentric), + heading+dtheta); } void MapBuilder::importLocalToWorld() { - if (!agentAtOrigin) { - world.ShS.applyTransform(worldToLocalTranslateMatrix); - world.ShS.applyTransform(worldToLocalRotateMatrix); - } - matchSrcToDst(local.ShS, world.ShS); - if (!agentAtOrigin) - world.ShS.applyTransform(localToWorldMatrix); + worldShS.applyTransform(worldToLocalTranslateMatrix,egocentric); + worldShS.applyTransform(worldToLocalRotateMatrix,egocentric); + matchSrcToDst(localShS,worldShS); + worldShS.applyTransform(localToWorldMatrix,allocentric); } -void MapBuilder::importWorldToLocal(const ShapeRoot &worldShape) { - ShapeRoot localShape(local.ShS.importShape(worldShape)); - localShape->applyTransform(worldToLocalTranslateMatrix); - localShape->applyTransform(worldToLocalRotateMatrix); +ShapeRoot MapBuilder::importWorldToLocal(const ShapeRoot &worldShape) { + ShapeRoot localShape(localShS.importShape(worldShape)); + localShape->applyTransform(worldToLocalTranslateMatrix,egocentric); + localShape->applyTransform(worldToLocalRotateMatrix,egocentric); + return localShape; } bool MapBuilder::isPointVisible(const Point &pt, const NEWMAT::Matrix& baseToCam, float maxDistanceSq) { NEWMAT::ColumnVector camCoords = baseToCam*pt.coords; - if (camCoords(3) <=0 || distSq(camCoords) >= maxDistanceSq) return false; + // if (camCoords(3) <=0 || distSq(camCoords) >= maxDistanceSq) return false; + if ( camCoords(1)*camCoords(1)+camCoords(2)*camCoords(2) >= maxDistanceSq ) + return false; float normX,normY; // normalized coordinates in cam frame config->vision.computePixel(camCoords(1),camCoords(2),camCoords(3),normX,normY); return (fabs(normX) < 0.9 && fabs(normY) < 0.9); //normX and normY range from -1 to 1. Giving 10% offset here @@ -481,15 +542,17 @@ const coordinate_t cenX = (*ground_it)->getCentroid().coordX(); const coordinate_t cenY = (*ground_it)->getCentroid().coordY(); if (cenX*cenX + cenY*cenY > maxDistSq) { // too far - cout << "ground shape " << (*ground_it)->getId() << "(lastMatch " - << (*ground_it)->getLastMatchId() << ") too far, delete\n"; + if ( verbosity & MBVnotAdmissible ) + cout << "ground shape " << (*ground_it)->getId() << " (lastMatch " + << (*ground_it)->getLastMatchId() << ") too far, delete\n"; ground_it->deleteShape(); } NEWMAT::ColumnVector coords = Kinematics::pack(cenX,cenY,(*ground_it)->getCentroid().coordZ()); coords = baseToCam*coords; if (coords(3) < 0) { // negative z-coordinate in camera frame indicates projection failed - cout << "Projection failed for ground shape " << (*ground_it)->getId() - << "(lastMatch " << (*ground_it)->getLastMatchId() << "), delete\n"; + if ( verbosity & MBVprojectionFailed ) + cout << "Projection failed for ground shape " << (*ground_it)->getId() + << " (lastMatch " << (*ground_it)->getLastMatchId() << "): deleting\n"; ground_it->deleteShape(); } // if a line is extending to maxDistance, chop it off at maxdistance and mark the endpoint invalid @@ -538,12 +601,12 @@ } } -void MapBuilder::calculateGroundPlane(const MapBuilderRequest::GroundPlaneAssumption_t& gpa) { - switch(gpa) { +void MapBuilder::calculateGroundPlane() { + switch(curReq->groundPlaneAssumption) { case MapBuilderRequest::onLegs: ground_plane << kine->calculateGroundPlane(); - cout << "Neck pan = " << state->outputs[HeadOffset+PanOffset] << endl; - cout << "Calculated ground plane: " << NEWMAT::printmat(ground_plane) << endl; + if ( verbosity & MBVgroundPlane ) + cout << "Calculated ground plane: " << NEWMAT::printmat(ground_plane) << endl; break; case MapBuilderRequest::onStand: #ifdef TGT_ERS210 @@ -553,7 +616,9 @@ #endif // cout << "Hard-coded ground plane: " << NEWMAT::printmat(ground_plane) << endl; break; - }; + case MapBuilderRequest::custom: + ground_plane = curReq->customGroundPlane; + } } void MapBuilder::projectToGround(const NEWMAT::Matrix& camToBase) { @@ -562,7 +627,7 @@ void MapBuilder::matchSrcToDst(ShapeSpace &srcShS, ShapeSpace &dstShS, - set polCols, bool mergeSrc, bool mergeDst) { + set polCols, bool mergeSrc, bool mergeDst) { vector src_shapes = srcShS.allShapes(); vector dst_shapes = dstShS.allShapes(); vector polygon_edges; @@ -571,8 +636,9 @@ for (vector::iterator src_it = src_shapes.begin(); src_it != src_shapes.end(); src_it++ ) { if (!(*src_it)->isAdmissible()) { - cout << "shape " << (*src_it)->getId() << "(lastMatch " - << (*src_it)->getLastMatchId() << ") is not admissible:" << endl; + if ( verbosity & MBVnotAdmissible ) + cout << "shape " << (*src_it)->getId() << "(lastMatch " + << (*src_it)->getLastMatchId() << ") is not admissible:" << endl; (*src_it)->printParams(); src_shapes.erase(src_it--); } @@ -582,7 +648,7 @@ src_shapes.erase(src_it--); } else if ((*src_it)->isType(lineDataType)) { - const int colorIndex = ProjectInterface::getColorIndex((*src_it)->getColor()); + const color_index colorIndex = ProjectInterface::getColorIndex((*src_it)->getColor()); if ( polCols.end() != find(polCols.begin(), polCols.end(), colorIndex)) { polygon_edges.push_back(ShapeRootTypeConst(*src_it, LineData).getData()); src_shapes.erase(src_it--); @@ -597,7 +663,8 @@ for ( vector::iterator it2 = it+1; it2 != src_shapes.end(); it2++) if ((*it2)->isMatchFor(*it) && (*it)->updateParams(*it2)) { - cout << "merging shape " << (*it)->getId() << " and shape " << (*it2)->getId() << endl; + if ( verbosity & MBVshapesMerge ) + cout << "merging shape " << (*it)->getId() << " and shape " << (*it2)->getId() << endl; src_shapes.erase(it2--); } @@ -612,8 +679,9 @@ src_it != src_shapes.end(); src_it++) if ((*dst_it)->isMatchFor(*src_it) && (*dst_it)->updateParams((*src_it))) { (*dst_it)->increaseConfidence(*src_it); - // cout << "Matched src shape " << (*src_it)->getId() << " (lastMatch " << (*src_it)->getLastMatchId() - // << ") to dst shape " << (*dst_it)->getId() << endl; + if ( verbosity & MBVshapeMatch ) + cout << "Matched src shape " << (*src_it)->getId() << " (lastMatch " << (*src_it)->getLastMatchId() + << ") to dst shape " << (*dst_it)->getId() << endl; src_shapes.erase(src_it--); } } @@ -628,8 +696,9 @@ delete_it->deleteShape(); dstShS.importShapes(newPolygons); dstShS.importShapes(src_shapes); - cout << "Imported " << (src_shapes.size()+newPolygons.size()) << " new shape(s) from " - << srcShS.name << "ShS to " << dstShS.name << "ShS\n"; + if ( verbosity & MBVimportShapes ) + cout << "Imported " << (src_shapes.size()+newPolygons.size()) << " new shape(s) from " + << srcShS.name << "ShS to " << dstShS.name << "ShS\n"; // match shapes inside dstShS if (mergeDst) { @@ -649,8 +718,8 @@ } } -// decrease confidence of those shapes should have been seen in the last snap, -// remove shapes from shapespace if confidence becomes <0 +// decrease confidence of those shapes that should have been seen in the last snap, +// remove shapes from ShapeSpace if confidence becomes < 0 void MapBuilder::removeNoise(ShapeSpace& ShS, const NEWMAT::Matrix& baseToCam) { // cout << "MapBuilder::removeNoise()\n"; vector shapes = ShS.allShapes(); @@ -668,25 +737,27 @@ for (vector::iterator edge_it = edges.begin(); edge_it != edges.end(); edge_it++, edge_index++) { if (isLineVisible(*edge_it, baseToCam)) { - cout << "edge " << edge_index << " of polygon " << (*it)->getId() << "(confidence: " - << edge_it->getConfidence() << ") should be visible in this frame" << endl; + if ( verbosity & MBVshouldSee ) + cout << "edge " << edge_index << " of polygon " << (*it)->getId() << "(confidence: " + << edge_it->getConfidence() << ") should be visible in this frame" << endl; edge_it->decreaseConfidence(); } } vector brokenPolygons = polygon->updateState(); ShS.importShapes(brokenPolygons); if (!polygon->isAdmissible()) { - cout << "delete polygon " << (*it)->getId() << " from map" << endl; + if ( verbosity & MBVdeleteShape ) + cout << "delete polygon " << (*it)->getId() << " from map" << endl; it->deleteShape(); } } else if ((!(*it)->isType(agentDataType)) && isShapeVisible(*it, baseToCam, maxDistSq)){ (*it)->decreaseConfidence(); // decrease confidence by 1 for every visible shape - cout << "shape " << (*it)->getId() << "(confidence: " << (*it)->getConfidence() - << ") should be visible in this frame" << endl; if ((*it)->getConfidence() < 0 ) { - cout << "confidence < 0, shape " << (*it)->getId() << " deleted from map" << endl; - // it->deleteShape(); + if ( verbosity & MBVshouldSee ) + cout << "shape " << (*it)->getId() << "(confidence: " << (*it)->getConfidence() + << ") should be visible in this frame; deleted" << endl; + it->deleteShape(); } } } @@ -694,132 +765,68 @@ //================ Gaze points ================ -void MapBuilder::defineGazePts(vector &gazePts, const ShapeRoot& area, bool doScan) { - cout << "MapBuilder::defineGazePts\n"; - static const float meshSize=50; - switch (area->getType()) { - case lineDataType: { - const Shape& line = ShapeRootTypeConst(area,LineData); - if (doScan) { - ScanAlongLineRequest req(line->end1Pt(),line->end2Pt()); - scan(req); - } - else { - int numIntervals = (int) (line->getLength()/meshSize); - const EndPoint& ep1 = line->end1Pt(); - const EndPoint& ep2 = line->end2Pt(); - gazePts.push_back(ep1); - for (int i = 1; i < numIntervals; i++) - gazePts.push_back((ep1*i + ep2*(numIntervals-i))/numIntervals); - gazePts.push_back(ep2); - } - } - break; - case blobDataType: { - const Shape& blob = ShapeRootTypeConst(area,BlobData); - if (doScan) { - ScanAreaRequest req(blob->topLeft.coordY(),blob->bottomRight.coordY(), - blob->topLeft.coordX(),blob->bottomRight.coordX()); - scan(req); - } - else { - vector corners; - corners.push_back(blob->topLeft); - corners.push_back(blob->topRight); - corners.push_back(blob->bottomRight); - corners.push_back(blob->bottomLeft); - defineGazePts(gazePts, corners, meshSize); - } - } - break; - case pointDataType: - gazePts.push_back(area->getCentroid()); - break; - case polygonDataType: { - const Shape &poly = ShapeRootTypeConst(area,PolygonData); - const vector &verts = poly->getVertices(); - gazePts.insert(gazePts.end(),verts.begin(),verts.end()); - } - break; - default: - cerr << "ERRORR MapBuilder::defineGazePts: Only types of area supported are Blob, Line, Point, and Polygon\n"; - requestComplete(); - break; - }; -} - -void MapBuilder::defineGazePts(vector& gazePts, const vector& corners, float meshSize) { - if (corners.size() != 4) { - cout << "Region of interest has to have four corners" << endl; +void MapBuilder::defineGazePts() { + const ShapeRoot &sArea = curReq->searchArea; + if ( !sArea.isValid() ) return; - } - for (vector::const_iterator it = corners.begin(); - it != corners.end()-1; it++) { - if (find(it+1, corners.end(), *it) != corners.end()) { - cout << "At least two corners are identical" << endl; - return; - } - } - LineData ln1(groundShS, corners.at(0),corners.at(1)); - LineData ln2(groundShS, corners.at(0),corners.at(2)); - const bool edge0_next_to_edge1 = !ln1.intersectsLine(LineData(groundShS, corners.at(2),corners.at(3))); - const bool edge0_next_to_edge2 = !ln2.intersectsLine(LineData(groundShS, corners.at(1),corners.at(3))); - vector horizontal, vertical; - - // passed corners may not be in the right order, sort them in clockwise or counterclockwise direction - const Point p0(corners.at(0)); - const Point p1(edge0_next_to_edge1 ? corners.at(1) : corners.at(3)); - const Point p2(edge0_next_to_edge1 ? (edge0_next_to_edge2 ? corners.at(3) : corners.at(2)) : corners.at(1)); - const Point p3(edge0_next_to_edge2 ? corners.at(2) : corners.at(3)); + else if ( curReq->doScan == true ) + scanForGazePts(); + else + switch ( sArea->getType() ) { - // define horizontal lines - Point p1_minus_p0 = p1-p0; - Point p2_minus_p3 = p2-p3; - const int num_steps_x = - (int) (sqrt(max(p1_minus_p0.coordX()*p1_minus_p0.coordX() + p1_minus_p0.coordY()*p1_minus_p0.coordY(), - p2_minus_p3.coordX()*p2_minus_p3.coordX() + p2_minus_p3.coordY()*p2_minus_p3.coordY())) - / meshSize) + 1; - p1_minus_p0 /= (float) num_steps_x; - p2_minus_p3 /= (float) num_steps_x; - - for (int i = 0; i <= num_steps_x; i++) - horizontal.push_back(LineData(groundShS, p0+p1_minus_p0*i, p3+p2_minus_p3*i)); + case pointDataType: + curReq->gazePts.push_back(sArea->getCentroid()); + break; - // define vertical lines - Point p3_minus_p0 = p3-p0; - Point p2_minus_p1 = p2-p1; - const int num_steps_y = - (int) (sqrt(max(p3_minus_p0.coordX()*p3_minus_p0.coordX() + p3_minus_p0.coordY()*p3_minus_p0.coordY(), - p2_minus_p1.coordX()*p2_minus_p1.coordX() + p2_minus_p1.coordY()*p2_minus_p1.coordY())) - / meshSize) + 1; - p3_minus_p0 /= (float) num_steps_y; - p2_minus_p1 /= (float) num_steps_y; + case lineDataType: { + static const float meshSize=50; + const Shape& line = ShapeRootTypeConst(sArea,LineData); + if ( curReq->doScan == true ) + scanForGazePts(); + else { + int numIntervals = (int) (line->getLength()/meshSize); + const EndPoint& ep1 = line->end1Pt(); + const EndPoint& ep2 = line->end2Pt(); + curReq->gazePts.push_back(ep1); + for (int i = 1; i < numIntervals; i++) + curReq->gazePts.push_back((ep1*i + ep2*(numIntervals-i))/numIntervals); + curReq->gazePts.push_back(ep2); + } + } + break; - for (int i = 0; i <= num_steps_y; i++) - vertical.push_back(LineData(groundShS, p0+p3_minus_p0*i, p1+p2_minus_p1*i)); - - // define check points = intersection of horizontal and vertical lines - // cout << "checkList: " << endl; - for (vector::const_iterator H_it = horizontal.begin(); - H_it != horizontal.end(); H_it++) - for (vector::const_iterator V_it = vertical.begin(); - V_it != vertical.end(); V_it++) - gazePts.push_back(H_it->intersectionWithLine(*V_it)); + case polygonDataType: + if ( curReq->doScan == true ) + scanForGazePts(); + else { + const Shape &poly = ShapeRootTypeConst(sArea,PolygonData); + const vector &verts = poly->getVertices(); + curReq->gazePts.insert(curReq->gazePts.end(),verts.begin(),verts.end()); + } + break; + + default: + cerr << "ERROR MapBuilder::defineGazePts: Supported searchArea shapes are Point, Line, and Polygon\n"; + requestComplete(); + break; + } } + void MapBuilder::removeGazePts(vector &gazePts, const NEWMAT::Matrix& baseToCam) { - if ( ! dynamic_cast(curReq)->removePts ) - return; - int num_points_seen = 0; - for ( vector::iterator it = gazePts.begin(); - it != gazePts.end(); it++ ) { - if (isPointVisible(*it, baseToCam, maxDistSq)) { - num_points_seen++; - gazePts.erase(it--); + if (curReq->removePts) { + int num_points_seen = 0; + for ( vector::iterator it = gazePts.begin(); + it != gazePts.end(); it++ ) { + if ( isPointVisible(*it,baseToCam,maxDistSq) ) { + cout << "Removing already-visible gaze point " << *it << endl; + num_points_seen++; + gazePts.erase(it--); + } } + // cout << num_points_seen << " pre-defined gaze points seen in last image, " + // << gazePts.size() << " left\n"; } - // cout << num_points_seen << " pre-defined gaze points seen in last snap, " - // << gazePts.size() << " left\n"; } @@ -854,7 +861,6 @@ //================ Shape extraction ================ - void MapBuilder::getCameraShapes(const Sketch& camFrame) { camShS.clear(); getCamLines(camFrame, curReq->objectColors[lineDataType], curReq->occluderColors[lineDataType]); @@ -862,63 +868,74 @@ getCamPolygons(camFrame, curReq->objectColors[polygonDataType], curReq->occluderColors[polygonDataType]); getCamSpheres(camFrame, curReq->objectColors[sphereDataType], curReq->occluderColors[sphereDataType]); getCamWalls(camFrame, curReq->floorColor); - BlobData::extractBlobs(camFrame, curReq->objectColors[blobDataType]); + if ( curReq->numSamples == 1 && !curReq->searchArea.isValid() ) // for fast blob extraction from current camera frame + getCamBlobs(); + else + getCamBlobs(camFrame, curReq->objectColors[blobDataType], curReq->minBlobAreas, curReq->blobOrientations, curReq->assumedBlobHeights); + getCamTargets(camFrame, curReq->objectColors[targetDataType], curReq->occluderColors[targetDataType]); } -vector > MapBuilder::getCamLines(const Sketch &camFrame, const set& objectColors, - const set& occluderColors) const { - vector > lines; - if (objectColors.empty() ) - return lines; - cout << "*** Find the lines ***" << endl; +vector > MapBuilder::getCamLines(const Sketch &camFrame, const set& objectColors, + const set& occluderColors) const { + vector > linesReturned; + if ( objectColors.empty() ) + return linesReturned; + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the lines ***" << endl; NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame)); - for ( set::const_iterator it = occluderColors.begin(); + for ( set::const_iterator it = occluderColors.begin(); it != occluderColors.end(); it++ ) occluders |= visops::minArea(visops::colormask(camFrame,*it)); - for (set::const_iterator it = objectColors.begin(); + for (set::const_iterator it = objectColors.begin(); it != objectColors.end(); it++) { NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it)); NEW_SKETCH_N(cleancolor,bool,visops::minArea(colormask)); NEW_SKETCH_N(fatmask,bool,visops::fillin(cleancolor,1,2,8)); NEW_SKETCH_N(skel,bool,visops::skel(fatmask)); - vector > line_shapes = LineData::extractLines(skel,cleancolor|occluders); - lines.insert(lines.end(), line_shapes.begin(), line_shapes.end()); - cout << "Found " << line_shapes.size() << " lines." << endl; + vector > line_shapes(LineData::extractLines(skel,cleancolor|occluders)); + linesReturned.insert(linesReturned.end(), line_shapes.begin(), line_shapes.end()); + if ( verbosity & MBVshapesFound ) + cout << "Found " << line_shapes.size() << " " + << ProjectInterface::getColorName(*it) << " lines." << endl; } - return lines; + return linesReturned; } vector > MapBuilder::getCamEllipses(const Sketch &camFrame, - const set& objectColors, const set& ) const { + const set& objectColors, const set& ) const { vector > ellipses; if (objectColors.empty()) return ellipses; - cout << "*** Find the ellipses ***" << endl; - for (set::const_iterator it = objectColors.begin(); + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the ellipses ***" << endl; + for (set::const_iterator it = objectColors.begin(); it !=objectColors.end(); it++) { NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it)); vector > ellipse_shapes = EllipseData::extractEllipses(colormask); ellipses.insert(ellipses.end(), ellipse_shapes.begin(),ellipse_shapes.begin()); - cout << "Found " << ellipse_shapes.size() << " ellipses." << endl; + if ( verbosity & MBVshapesFound ) + cout << "Found " << ellipse_shapes.size() << " " + << ProjectInterface::getColorName(*it) << " ellipses." << endl; } return ellipses; } vector > MapBuilder::getCamPolygons(const Sketch &camFrame, - const set& objectColors, const set& occluderColors) const { + const set& objectColors, const set& occluderColors) const { vector > polygons; if ( objectColors.empty() ) return polygons; - cout << "*** Find the polygons ***" << endl; + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the polygons ***" << endl; NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame)); - for ( set::const_iterator it = occluderColors.begin(); + for ( set::const_iterator it = occluderColors.begin(); it !=occluderColors.end(); it++ ) occluders |= visops::colormask(camFrame,*it); - for (set::const_iterator it = objectColors.begin(); + for (set::const_iterator it = objectColors.begin(); it !=objectColors.end(); it++) { NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it)); NEW_SKETCH_N(fatmask,bool,visops::fillin(colormask,1,2,8)); @@ -927,24 +944,27 @@ vector > polygon_lines = PolygonData::extractPolygonEdges(fatskel,fatmask|occluders); polygons.insert(polygons.end(), polygon_lines.begin(), polygon_lines.end()); - cout << "Found " << polygon_lines.size() << " lines." << endl; + if ( verbosity & MBVshapesFound ) + cout << "Found " << polygon_lines.size() << " lines." << endl; } return polygons; } vector > MapBuilder::getCamSpheres(const Sketch &camFrame, - const set& objectColors, const set& ) const { + const set& objectColors, const set& ) const { vector > spheres; if ( objectColors.empty() ) return spheres; - cout << "*** Find the spheres ***" << endl; - for (set::const_iterator it = objectColors.begin(); + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the spheres ***" << endl; + for (set::const_iterator it = objectColors.begin(); it !=objectColors.end(); it++) { NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it)); - vector sphere_shapes = SphereData::extractSpheres(colormask); + vector > sphere_shapes = SphereData::extractSpheres(colormask); spheres.insert(spheres.end(), spheres.begin(), spheres.end()); - cout << "Found " << sphere_shapes.size() << " spheres." << endl; + if ( verbosity & MBVshapesFound ) + cout << "Found " << sphere_shapes.size() << " spheres." << endl; } return spheres; } @@ -953,7 +973,8 @@ MapBuilder::getCamWalls(const Sketch &camFrame, unsigned int floorColor) const { if (floorColor == 0) return vector >(); - cout << "*** Find the walls ***" << endl; + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the walls ***" << endl; const int camFrame_offset = 8; NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,floorColor)); @@ -988,32 +1009,82 @@ (*it)->end2Pt().setValid(false); } - cout << "Found " << wall_bounds.size() << " wall boundary lines" << endl; + if ( verbosity & MBVshapesFound ) + cout << "Found " << wall_bounds.size() << " wall boundary lines" << endl; return wall_bounds; } +void MapBuilder::getCamBlobs(const Sketch& camFrame, + const set& colors, + const map& minBlobAreas, + const map& blobOrientations, + const map& assumedBlobHeights) { + if ( colors.empty() ) + return; + int const maxblobs = 50; + vector > result(BlobData::extractBlobs(camFrame, colors, minBlobAreas, blobOrientations, assumedBlobHeights, maxblobs)); + if ( verbosity & MBVshapesFound ) + cout << "Found " << result.size() << " blobs." << endl; +} + +// The code below grabs blobs directly from the region generator stream, instead of +// calling CMVision to do region extraction on camFrame void MapBuilder::getCamBlobs() { if ( curReq->objectColors[blobDataType].empty() ) return; - cout << "*** Find the blobs ***" << endl; - int minarea; - BlobData::BlobOrientation_t orient; - set& blobColors = curReq->objectColors[blobDataType]; - // unsigned int const numBlobColors = blobColors.size(); - // for ( unsigned int i = 0; i::const_iterator it = blobColors.begin(); + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the blobs ***" << endl; + const set& blobColors = curReq->objectColors[blobDataType]; + for (set::const_iterator it = blobColors.begin(); it != blobColors.end(); it++) { - // minarea = ( i < (curReq->minBlobAreas).size() ) ? (curReq->minBlobAreas)[i] : 0; - // minarea = ( i < (curReq->minBlobAreas).size() ) ? 1 : 0; - // orient = ( i < curReq->blobOrientations.size() ) ? curReq->blobOrientations[i] : BlobData::groundplane; - // vector > blob_shapes(VRmixin::getBlobsFromRegionGenerator(blobColors[i],minarea,orient)); - minarea = (curReq->minBlobAreas.find(*it)==curReq->minBlobAreas.end()) ? + int const minarea = (curReq->minBlobAreas.find(*it)==curReq->minBlobAreas.end()) ? 0 : curReq->minBlobAreas[*it]; - orient = (curReq->blobOrientations.find(*it)==curReq->blobOrientations.end()) ? + BlobData::BlobOrientation_t const orient = (curReq->blobOrientations.find(*it)==curReq->blobOrientations.end()) ? BlobData::groundplane : curReq->blobOrientations[*it]; - vector > blob_shapes(VRmixin::getBlobsFromRegionGenerator(*it,minarea,orient)); - cout << "Found " << blob_shapes.size() << " blobs." << endl; + coordinate_t const height = (curReq->assumedBlobHeights.find(*it)==curReq->assumedBlobHeights.end()) ? + 0 : curReq->assumedBlobHeights[*it]; + vector > blob_shapes(VRmixin::getBlobsFromRegionGenerator(*it,minarea,orient,height)); + if ( verbosity & MBVshapesFound ) + cout << "Found " << blob_shapes.size() << " " << ProjectInterface::getColorName(*it) << " blobs." << endl; } } +vector > +MapBuilder::getCamTargets(const Sketch &camFrame, const set& objectColors, const set& occluderColors) const { + vector > targets; + if (objectColors.empty()) + return targets; + if ( verbosity & MBVshapeSearch ) + cout << "*** Find the targets ***" << endl; + + NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame)); + for (set::const_iterator it = occluderColors.begin(); + it != occluderColors.end(); it++) + occluders |= visops::minArea(visops::colormask(camFrame,*it)); + + // assumes multiples of 3 for objectColors (stays on the last color otherwise) + for (set::const_iterator it = objectColors.begin(); + it != objectColors.end(); it++) { + NEW_SKETCH_N(front_colormask, bool, visops::colormask(camFrame,*it)); + it++; + if (it == objectColors.end()) { + it--; + } + NEW_SKETCH_N(back_colormask, bool, visops::colormask(camFrame,*it)); + it++; + if (it == objectColors.end()) { + it--; + } + NEW_SKETCH_N(right_colormask, bool, visops::colormask(camFrame,*it)); + Shape target = TargetData::extractLineTarget(front_colormask, back_colormask, right_colormask, occluders); + if (target.isValid()) { + targets.insert(targets.end(), target); + } + if ( verbosity & MBVshapesFound ) + cout << "Found " << (target.isValid() ? 1 : 0) << " targets." << endl; + } + + return targets; +} + } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/MapBuilder.h ./DualCoding/MapBuilder.h --- ../Tekkotsu_3.0/DualCoding/MapBuilder.h 2006-10-02 18:50:38.000000000 -0400 +++ ./DualCoding/MapBuilder.h 2007-11-11 18:57:21.000000000 -0500 @@ -7,291 +7,240 @@ #include "Behaviors/BehaviorBase.h" #include "Shared/newmat/newmat.h" +#include "Point.h" + #include "BlobData.h" +#include "EllipseData.h" #include "LineData.h" -#include "Point.h" +#include "SphereData.h" +#include "TargetData.h" + #include "VRmixin.h" -#include "LookoutRequests.h" -#include "MapBuilderRequests.h" +#include "MapBuilderRequest.h" #include "SketchTypes.h" #include "ShapeSpace.h" +#include "PolygonData.h" + +class LookoutSketchEvent; // note: this is NOT in the DualCoding namespace namespace DualCoding { class SketchSpace; -class ScanRequest; class MapBuilder : public BehaviorBase { protected: SketchSpace &camSkS; ShapeSpace &camShS, &groundShS; + SketchSpace &localSkS; + ShapeSpace &localShS; + SketchSpace &worldSkS; + ShapeSpace &worldShS; - struct maps { - enum Space { local, world } space; - SketchSpace &SkS; - ShapeSpace &ShS; - vector gazePts; - vector baseToCamMats; - maps(Space _space, SketchSpace& _SkS) : - space(_space), SkS(_SkS), ShS(_SkS.getDualSpace()), gazePts(), baseToCamMats() {} - } local, world, *cur; - -public: const int xres, yres; //!< width and height of camera frame + NEWMAT::ColumnVector ground_plane; //!< ground plane to which shapes are projected + static bool retain; //!< if true, VRmixin::stopCrew will not clear MapBuilder structures + +public: + //! Control whether static structures (mapbuilder, sketchGUI sockets, etc.) are retained + static void setRetain(bool r) { retain = r; } + static bool isRetained() { return retain; } + + typedef unsigned int MapBuilderVerbosity_t; + static const MapBuilderVerbosity_t MBVstart = 1<<0; + static const MapBuilderVerbosity_t MBVevents = 1<<1; + static const MapBuilderVerbosity_t MBVexecute = 1<<2; + static const MapBuilderVerbosity_t MBVcomplete = 1<<3; + static const MapBuilderVerbosity_t MBVdefineGazePoints = 1<<4; + static const MapBuilderVerbosity_t MBVnextGazePoint = 1<<5; + static const MapBuilderVerbosity_t MBVshapeSearch = 1<<6; + static const MapBuilderVerbosity_t MBVshapesFound = 1<<7; + static const MapBuilderVerbosity_t MBVgroundPlane = 1<<8; + static const MapBuilderVerbosity_t MBVprojectionFailed = 1<<9; + static const MapBuilderVerbosity_t MBVimportShapes = 1<<10; + static const MapBuilderVerbosity_t MBVnotAdmissible = 1<<11; + static const MapBuilderVerbosity_t MBVshapeMatch = 1<<12; + static const MapBuilderVerbosity_t MBVshapesMerge = 1<<13; + static const MapBuilderVerbosity_t MBVshouldSee = 1<<14; + static const MapBuilderVerbosity_t MBVdeleteShape = 1<<15; + static const MapBuilderVerbosity_t MBVsetAgent = 1<<16; + static const MapBuilderVerbosity_t MBVbadGazePoint = 1<<17; + +private: + static MapBuilderVerbosity_t verbosity; +public: + static void setVerbosity(MapBuilderVerbosity_t v) { verbosity = v; } + protected: - Shape &theAgent; //!< agent in the world frame - //! trasformation matrices between local and world frames. + friend class Lookout; + + Shape &theAgent; //!< Agent in the world frame + //!@name Transformation matrices between local and world frames + //@{ NEWMAT::Matrix localToWorldMatrix, worldToLocalTranslateMatrix, worldToLocalRotateMatrix; + //@} - vector badGazePoints; //!< gaze points for which HeadPointerMC.lookAtPoint() returned false - bool agentAtOrigin; //!< whether or not agent is at origin and orientation is zero or two pi. + std::vector badGazePoints; //!< gaze points for which HeadPointerMC.lookAtPoint() returned false - queue requests; + std::queue requests; MapBuilderRequest *curReq; unsigned int idCounter; - unsigned int maxDistSq; //!< sqrt of current request's max distance parameter + float maxDistSq; //!< square of current request's max distance parameter unsigned int pointAtID, scanID; //!< ID's for lookout requests Point nextGazePoint; - - //! posts completion event and deletes current request, executes next request if there is one - void requestComplete(); - //! triggers action to execute the front one in requests queue + //! Triggers action to execute the request at the front of the queue void executeRequest(); //! calls exitTest of current request if there is one and returns the result bool requestExitTest(); + //! posts completion event and deletes current request, executes next request if there is one + void requestComplete(); public: MapBuilder(); //!< Constructor virtual ~MapBuilder() {} //!< Destructor virtual void DoStart(); virtual void DoStop(); - virtual void processEvent(const EventBase&); virtual std::string getDescription() const { return "MapBuilder"; } void printShS(ShapeSpace&) const; - unsigned int executeRequest(const MapBuilderRequest& req); + unsigned int executeRequest(const MapBuilderRequest&, unsigned int *req_id=NULL); // execute a MapBuilder request, and optionally store the request id in a variable; the id will be returned in any case - void processImage(const Sketch&, const NEWMAT::Matrix& camToBase, const NEWMAT::Matrix& baseToCam); + virtual void processEvent(const EventBase&); + void processImage(const LookoutSketchEvent&); - // returns if a ground shape should be seen in the current camera frame + // Returns true if a ground shape should be seen in the current camera frame static bool isPointVisible(const Point &pt, const NEWMAT::Matrix& baseToCam, float maxDistanceSq) ; static bool isLineVisible(const LineData& ln, const NEWMAT::Matrix& baseToCam); static bool isShapeVisible(const ShapeRoot &ground_shape, const NEWMAT::Matrix& baseToCam, float maxDistanceSq); - //!@ utility functions which may be used by MapBuilderRequests' exit condition and others + //! utility functions which may be used by MapBuilderRequest's exit condition and others + //@{ const Shape& getAgent() const { return theAgent; } // sets the agent location and heading - void setAgent(const Point &location, const AngTwoPi heading); + void setAgent(const Point &worldLocation, const AngTwoPi worldHeading); // updates the agent location and heading void moveAgent(coordinate_t const local_dx, coordinate_t const local_dy, AngTwoPi dtheta); + //@} - vector getShapes(const ShapeSpace& ShS, int minConf=2) const { - const vector allShapes = ShS.allShapes(); + std::vector getShapes(const ShapeSpace& ShS, int minConf=2) const { + const std::vector allShapes = ShS.allShapes(); if (&ShS == &camShS || &ShS == &groundShS || minConf <= 0) return allShapes; - vector nonNoiseShapes; - for (vector::const_iterator it = allShapes.begin(); + std::vector nonNoiseShapes; + for (std::vector::const_iterator it = allShapes.begin(); it != allShapes.end(); it++) if ((*it)->getConfidence() >= minConf) nonNoiseShapes.push_back(*it); return nonNoiseShapes; } - const vector& getGazePts() const { return cur->gazePts; } - static bool returnTrue() { return true; } - static bool returnFalse() { return false; } - //}@ + void importLocalToWorld(); - //!@ Shape extraction functions - vector > - getCamLines(const Sketch&, const set& objectColors, - const set& occluderColors) const ; - vector > - getCamPolygons(const Sketch&, const set& objectColors, - const set& occluderColors) const ; - vector > - getCamEllipses(const Sketch&, const set& objectColors, - const set& occluderColors) const ; - vector > - getCamSpheres(const Sketch&, const set& objectColors, - const set& occluderColors) const ; - vector > - getCamWalls(const Sketch&, unsigned int) const ; - vector > - getCamBlobs(const Sketch& sketch, const set& objectColors) const { - return BlobData::extractBlobs(sketch, objectColors); - } - //}@ + ShapeRoot importWorldToLocal(const ShapeRoot &worldShape); + template Shape importWorldToLocal(const Shape &worldShape); - static Shape formBoundingBox(coordinate_t left, coordinate_t right, - coordinate_t front, coordinate_t rear) { - return Shape - (new BlobData(VRmixin::groundShS, Point(front,left), Point(front,right), - Point(rear,right), Point(rear,left), fabs((left-right)*(front-rear)), - vector(), BlobData::groundplane, rgb())); - } +protected: + //!@name Shape extraction functions + //@{ + void getCameraShapes(const Sketch& camFrame); + + std::vector > + getCamLines(const Sketch&, const std::set& objectColors, + const std::set& occluderColors) const; + + std::vector > + getCamEllipses(const Sketch&, const std::set& objectColors, + const std::set& occluderColors) const; + + std::vector > + getCamPolygons(const Sketch&, const std::set& objectColors, + const std::set& occluderColors) const; + + std::vector > + getCamWalls(const Sketch&, unsigned int) const; + + std::vector > + getCamSpheres(const Sketch&, const std::set& objectColors, + const std::set& occluderColors) const; + + void getCamBlobs(const Sketch& camFrame, + const std::set& colors, + const std::map& minBlobAreas, + const std::map& blobOrientations, + const std::map& assumedBlobHeights); + void getCamBlobs(); + + std::vector > + getCamTargets(const Sketch &camFrame, const std::set& objectColors, + const std::set& occluderColors) const; + //@} - void importLocalToWorld(); - void importWorldToLocal(const ShapeRoot &shape); // matching shapes between two spaces. - static void matchSrcToDst(ShapeSpace &src, ShapeSpace &dst, set polygonEdgeColors=set(), + static void matchSrcToDst(ShapeSpace &src, ShapeSpace &dst, std::set polygonEdgeColors=std::set(), bool mergeSrc=true, bool mergeDst=true); -protected: - //! functions to make requests to lookout - void scan(ScanRequest& req); - void storeImageAt(const Point& pt); - void storeImage(); + //!@name Functions to make requests to the Lookout + //@{ + void storeImage() { storeImage(Point(),false); } + void storeImage(const Point& pt, bool havepoint=true); + void grabCameraImageAndGo(); + void scanForGazePts(); + //@} //! define gazePts either virtually or by scan - void defineGazePts(vector&, const ShapeRoot& area, bool doScan);// {} - void defineGazePts(vector& gazePts, const vector& corners, float meshSize); + void defineGazePts(); - void getCameraShapes(const Sketch& camFrame); - void getCamBlobs(); - void extendLocal(const NEWMAT::Matrix& baseToCam); void extendWorld(const NEWMAT::Matrix& baseToCam); //! decrement confidence of shapes which should have been seen according to the baseToCam matrix void removeNoise(ShapeSpace&, const NEWMAT::Matrix& baseToCam); //! erase gaze points which should have been seen according to the baseToCam matrix - void removeGazePts(vector&, const NEWMAT::Matrix& baseToCam); + void removeGazePts(std::vector&, const NEWMAT::Matrix& baseToCam); //! Returns true if it has set up a valid next gaze point in nextGazePoint bool determineNextGazePoint(); //! Returns true if there is a shape which needs be looked at again and is reachable; sets it up as nextGazePoint - bool determineNextGazePoint(const vector&); - // Returns true if an element of gazePt can be looked at; sets it up as nextGazePoint - bool determineNextGazePoint(vector &gazePts); + bool determineNextGazePoint(const std::vector&); + // Returns true if an element of gazePts can be looked at; sets it up as nextGazePoint + bool determineNextGazePoint(std::vector &gazePts); //! Starts robot moving to the next gaze point void moveToNextGazePoint(const bool manualOverride=false); + void doNextSearch(); + void doNextSearch2(); // operations in ground shape space bool isBadGazePoint(const Point&) const ; void projectToGround(const NEWMAT::Matrix& camToBase); void filterGroundShapes(const NEWMAT::Matrix& baseToCam); - // calculates ground place based on ground plane assumption type - void calculateGroundPlane(const MapBuilderRequest::GroundPlaneAssumption_t& gpa); + // calculates ground plane based on ground plane assumption type + void calculateGroundPlane(); private: MapBuilder(const MapBuilder&); //!< never call this MapBuilder& operator=(const MapBuilder&); //!< never call this }; -/* - -Functions of the MapBuilder subsystem: - -1. Given a series of camera views from the same body position (but -varying head positions), assemble them into a local world view. This -requires: - - a) Matching functions to establish correspondence between - groundspace objects and local worldspace objects. This is - tricky when lines have missing endpoints, or ellipses lie - partially offscreen. - - Matching algorithm: - do ellipses first -- they're simpler: just match color, center point - - Line matching: - pick a starting line (longest first) in groundShS - then find all colinear line segments in groundShS matching its rho/theta - do the same in localworldShS - now a smart algorithm can assemble line segments into a more - complex match than just 1-1 - but for starters can code just a 1-1 match - - Find nearby ellipses in ground and world space and cluster them together - before matching. This will allow us to handle piles of free game pieces. - - Make a list of ambiguous points that we would like to examine further - by taking another image, moving the head and maybe even the body. - - Idea: we have to deal with lots of ambiguity in matching camera frames - to the local world map, and may want to confirm some things with - additional camera frames if we suspect noise. But the world map should - be considered to be reliable so we shouldn't need the same kind of - expensive tentative matching there. However, we may want to allow for - "hints" of things to be put in the world map if we're not certain of our - data. For example, a far off ellipse may be of indeterminate size and - orientation, so put it in the world map as a hint-of-ellipse and let the - robot wander over there and get a close up view if it wants to resolve - whether this is a real ellipse or noise. - - Can use distance from the camera as a parameter to control how we - treat an object; small, far away objects should be treated as less reliable. - Can keep counts on how many frames an object was seen or not seen, and - delete objects as spurious if they were only seen once or twice and - then not seen in a while. - - Unmatched object: to know that a mobile object has disappeared, we - need to recognize that we should see it but we don't. How? For each - camera frame, project the four corners to ground, yielding a trapezoid. - As we build the local world map we have a collection of trapezoids. For - any object in the global map that isn't matched by something in the local, - we can check its coordinates to see if it falls within one of the - trapizeoids. If so, then we looked and didn't see it, so it's gone. - - b) Update functions that update local worldspace object descriptions - once correspondences have been determined. - -2. Given a local worldspace map and a global worldspace map, and -possibly an estimate of current position and orientation on the -latter, determine the robot's true position and orientation in the -world, and update the global worldspace map. This requires: - - a) A search method to find the best translation and rotation of - the local worldspace map to fit the global worldspace map. - A particle filter looks like a good candidate method. - - b) Update functions that update the global worldspace description - once correspondences have been determined. - - c) A mechanism for recognizing when the world has changed, e.g., - objects have been added, deleted, or moved. This requires: - - i) Designation of objects as fixed or mobile - - ii) Declaration of objects as unique, of a fixed number, - or multitudinous. Unique fixed objects are the best - landmarks. Multitudinous mobile objects may need to - be monitored more frequently. - -3. Given a request to self-localize, acquire the minimum necessary -number of local views to perform that function. This requires: - - a) Designation of objects to be used as beacons or key landmarks. - - b) Head motion constraints. - - c) Body motion constraints (possibly "no body motion allowed".) - -Ideally, rather than directly executing motion commands, the system -should pass its requests to look in certain directions to the -affordance generator, which will figure out what is feasible, e.g., if -we're up against a wall and can't turn in that direction, we may have -to take a step sideways first. Let the affordance system worry abou -that. - -4. Given a prototype global world map description, visually explore -the world and instantiate the prototype as an actual global world map. -For example, we might define a tic-tac-toe environment as containing -two sets of perpendicular lines defining the game board, plus a pool -of free pieces. We may not know the exact lengths of the lines, or -their orientation, or the location of the pool relative to the board; -these need to be determined by observation. We may not even know the -color of the lines, in which case we'll have to look for a contrast -difference, but that is too advanced to worry about at present. +template Shape MapBuilder::importWorldToLocal(const Shape &worldShape) { + ShapeRoot temp(localShS.importShape(worldShape)); + Shape localShape(ShapeRootType(temp,T)); + localShape->applyTransform(worldToLocalTranslateMatrix); + localShape->applyTransform(worldToLocalRotateMatrix); + return localShape; +} -*/ +//! Utility function for deleting queues of pointers to Lookout or MapBuilder requests +template void deleteAll(std::queue &q) { + while ( ! q.empty() ) { + delete q.front(); + q.pop(); + } +} } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/MapBuilderRequest.h ./DualCoding/MapBuilderRequest.h --- ../Tekkotsu_3.0/DualCoding/MapBuilderRequest.h 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/MapBuilderRequest.h 2007-11-11 18:57:21.000000000 -0500 @@ -0,0 +1,118 @@ +//-*-c++-*- +#ifndef INCLUDED_MapBuilderRequest_h_ +#define INCLUDED_MapBuilderRequest_h_ + +#include + +#include "ShapeTypes.h" + +namespace DualCoding { + +class LookoutSearchRequest; + +class MapBuilderRequest { + friend class MapBuilder; + +public: + enum MapBuilderRequestType_t { + cameraMap, + groundMap, + localMap, + worldMap + }; + + MapBuilderRequestType_t requestType; //!< Type of map to build + std::map > objectColors; //!< For each object type, a set of object color indices + std::map > occluderColors; //!< For each object type, a set of occluder color indices + std::map minBlobAreas; //!< Minimum acceptable areas for blobs of specified colors, e.g., req.minBlobAreas[pink_index]=50 + std::map blobOrientations; //!< Default orientation for blobs of specified colors + std::map assumedBlobHeights; //!< Fixed heights for pillar or poster blobs of specified colors + unsigned int floorColor; + unsigned int motionSettleTime; //!< Time in msec to wait before taking measurements or throwing completion event after head reaches gazePt. + int numSamples; //!< Number of camera images to combine, for noise reduction + int sampleInterval; //!< Interval in msec between successive samples + float maxDist; //!< Ignore objects farther than this distance + bool clearShapes; //!< If true, clear the shape space at start of request + bool pursueShapes; //!< If true, generate new gaze points as shapes are recognized + bool manualHeadMotion; //!< If true, waits for !msg MoveHead before moving to next gaze point (for debugging) + bool rawY; //!< If true, leave an intensity (Y-channel) image in camera space for debugging + bool removePts; //!< If true, remove pending gaze points if they're visible in current image + bool doScan; //!< If true, do a continuous scan of the area to find interest points to be examined + AngPi dTheta; //!< Angular step for scanning + ShapeRoot searchArea; //!< The area to search, in egocentric coords + std::queue worldTargets; //!< Queue of search requests for world targets + void (*userCamProcessing)(); //!< User routine to call after cam space processing + void (*userGroundProcessing)(); //!< User routine to call after ground space processing + void (*userLocalProcessing)(); //!< User routine to call after local space processing + void (*userWorldProcessing)(); //!< User routine to call after world space processing + bool (*exitTest)(); //!< If true, terminate map building and post completion event + enum GroundPlaneAssumption_t { onStand, onLegs, custom } groundPlaneAssumption; + NEWMAT::ColumnVector customGroundPlane; //!< User-supplied ground plane +private: + std::vector gazePts; + std::vector baseToCamMats; + unsigned int requestID; //!< Set by mapbuilder when the request is added to its request queue + +public: + //! Constructor + MapBuilderRequest(MapBuilderRequestType_t reqtype=cameraMap) + : requestType(reqtype), objectColors(), occluderColors(), + minBlobAreas(), blobOrientations(), assumedBlobHeights(), floorColor(0), + motionSettleTime(1000), numSamples(1), sampleInterval(0), maxDist(1e10), + clearShapes(true), pursueShapes(false), manualHeadMotion(false), rawY(true), removePts(true), + doScan(false), dTheta(M_PI/18), + searchArea(), worldTargets(), + userCamProcessing(NULL), userGroundProcessing(NULL), + userLocalProcessing(NULL), userWorldProcessing(NULL), + exitTest(NULL), + groundPlaneAssumption(onLegs), customGroundPlane(4), + gazePts(), baseToCamMats(), + requestID(0) + {} + + //! Copy constructor + MapBuilderRequest(const MapBuilderRequest &req) + : requestType(req.requestType), + objectColors(req.objectColors), occluderColors(req.occluderColors), + minBlobAreas(req.minBlobAreas), blobOrientations(req.blobOrientations), assumedBlobHeights(req.assumedBlobHeights), + floorColor(req.floorColor), motionSettleTime(req.motionSettleTime), + numSamples(req.numSamples), sampleInterval(req.sampleInterval), + maxDist(req.maxDist), clearShapes(req.clearShapes), pursueShapes(req.pursueShapes), + manualHeadMotion(req.manualHeadMotion), rawY(req.rawY), removePts(req.removePts), + doScan(req.doScan), dTheta(req.dTheta), + searchArea(req.searchArea), worldTargets(req.worldTargets), + userCamProcessing(req.userCamProcessing), + userGroundProcessing(req.userGroundProcessing), + userLocalProcessing(req.userLocalProcessing), + userWorldProcessing(req.userWorldProcessing), + exitTest(req.exitTest), + groundPlaneAssumption(req.groundPlaneAssumption), + customGroundPlane(req.customGroundPlane), + gazePts(req.gazePts), baseToCamMats(req.baseToCamMats), + requestID(req.requestID) + {} + + virtual ~MapBuilderRequest() {} //!< Destructor + + MapBuilderRequestType_t getRequestType() const { return requestType; } + + void setCustomGroundPlane(float const angle, float const height) { + float const s = std::sin(-angle); + float const c = std::cos(-angle); + customGroundPlane = Kinematics::pack(s, 0, c, -height * c); + groundPlaneAssumption = custom; + } + + //! Returns true if the request can complete immediately (no head motion required and numSamples <= 1) + bool immediateRequest() const { + return !searchArea.isValid() && worldTargets.size() == 0 && !pursueShapes && !doScan && numSamples <= 1; + } + +private: + MapBuilderRequest& operator=(const MapBuilderRequest& req); + +}; + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/MapBuilderRequests.h ./DualCoding/MapBuilderRequests.h --- ../Tekkotsu_3.0/DualCoding/MapBuilderRequests.h 2006-09-23 23:44:30.000000000 -0400 +++ ./DualCoding/MapBuilderRequests.h 1969-12-31 19:00:00.000000000 -0500 @@ -1,202 +0,0 @@ -//-*-c++-*- -#ifndef INCLUDED_MapBuilderRequests_h_ -#define INCLUDED_MapBuilderRequests_h_ - -#include "BlobData.h" -#include "ShapeTypes.h" -#include "VRmixin.h" - -namespace DualCoding { - -class MapBuilderRequest { - typedef map > colorMap; - friend class MapBuilder; - -public: - enum MapBuilderRequestType_t { - none, - takeSnap, - localMap, - worldMap - }; - - virtual MapBuilderRequestType_t getRequestType() const=0; - - virtual ~MapBuilderRequest() {} - - unsigned int requestID; // set by mapbuilder when added to request queue - colorMap objectColors, occluderColors; - map minBlobAreas; - map blobOrientations; - unsigned int floorColor; - unsigned int numImages; - enum GroundPlaneAssumption_t { onStand, onLegs } groundPlaneAssumption; - - //! Constructor - MapBuilderRequest(unsigned int num=1) - : requestID(0), objectColors(), occluderColors(), - minBlobAreas(), blobOrientations(), floorColor(0), - numImages(num), groundPlaneAssumption(onLegs) {} - - //! Copy constructor - MapBuilderRequest(const MapBuilderRequest& req) - : requestID(req.requestID), - objectColors(req.objectColors), occluderColors(req.occluderColors), - minBlobAreas(req.minBlobAreas), blobOrientations(req.blobOrientations), - floorColor(req.floorColor), numImages(req.numImages), - groundPlaneAssumption(req.groundPlaneAssumption) {} - -private: - MapBuilderRequest& operator=(const MapBuilderRequest& req); -}; - -class TakeSnapRequest : public MapBuilderRequest { -public: - virtual MapBuilderRequestType_t getRequestType() const { return takeSnap; } - TakeSnapRequest(unsigned int num=1) - : MapBuilderRequest(num) {} - TakeSnapRequest(const TakeSnapRequest& req) - : MapBuilderRequest(req) {} -}; - -class TakeSnapAtRequest : public TakeSnapRequest { -public: - TakeSnapAtRequest(const Point& pt, unsigned int num=1) - : TakeSnapRequest(num), gazePt(pt) {} - TakeSnapAtRequest(const TakeSnapAtRequest& req) - : TakeSnapRequest(req), gazePt(req.gazePt) {} - Point gazePt; -}; - - -class LocalMapRequest : public MapBuilderRequest { -public: - virtual MapBuilderRequestType_t getRequestType() const { return localMap; } - - //! Constructor with bounding box - LocalMapRequest(coordinate_t maxX, coordinate_t minX, coordinate_t maxY, - coordinate_t minY, unsigned int _maxDist, unsigned int num=1, - bool clear=true, bool _doScan=true) - : MapBuilderRequest(num), shs(VRmixin::localShS), - area(Shape - (new BlobData - (VRmixin::groundShS,Point(maxX,maxY),Point(maxX,minY), - Point(minX,maxY),Point(minX,minY),(maxX-minX)*(maxY-minY), - vector(),BlobData::groundplane,rgb(0,0,0)))), - maxDist(_maxDist), clearShapes(clear), pursueShapes(true), manualHeadMotion(false), - removePts(true), doScan(_doScan) {} - - //! Constructor with point target - LocalMapRequest(const Point& pt, unsigned int _maxDist, unsigned int num=1, - bool clear=true, bool _doScan=true) - : MapBuilderRequest(num), shs(VRmixin::localShS), - area(Shape(new PointData(VRmixin::groundShS,pt))), - maxDist(_maxDist), clearShapes(clear), pursueShapes(true), manualHeadMotion(false), - removePts(true), doScan(_doScan) {} - - //! Constructor with ShapeRoot to define scan region - LocalMapRequest(const ShapeRoot _area, unsigned int _maxDist, unsigned int num=1, - bool clear=true, bool _doScan=true) - : MapBuilderRequest(num), shs(VRmixin::localShS), - area(_area), maxDist(_maxDist), clearShapes(clear), pursueShapes(true), manualHeadMotion(false), - removePts(true), doScan(_doScan) {} - - //! Copy constructor - LocalMapRequest(const LocalMapRequest& req) - : MapBuilderRequest(req), shs(req.shs), area(req.area), maxDist(req.maxDist), - clearShapes(req.clearShapes), pursueShapes(req.pursueShapes), manualHeadMotion(req.manualHeadMotion), - removePts(req.removePts), doScan(req.doScan) {} - - virtual ~LocalMapRequest() {} - - ShapeSpace& shs; - ShapeRoot area; //!< The area to search, in egocentric coords - unsigned int maxDist; //!< Ignore objects farther than this distance - bool clearShapes; //!< If true, clear the shape space at start of request - bool pursueShapes; //!< If true, generate new gaze points as shapes are recognized - bool manualHeadMotion; //!< If true, waits for !msg MoveHead before moving to next gaze point (for debugging) - bool removePts; //!< If true, remove pending gaze points if they're visible in current image - bool doScan; //!< If true, do a continuous scan of the area to find interest points to be examined - -protected: - //! Constructor used by subclass WorldMapRequest - LocalMapRequest(ShapeSpace& _shs, const ShapeRoot& _area, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : MapBuilderRequest(num), shs(_shs), area(_area), - maxDist(_maxDist), clearShapes(clear), pursueShapes(true), manualHeadMotion(false), - removePts(true), doScan(_doScan) {} - - //! Constructor used by subclass WorldMapRequest - LocalMapRequest(ShapeSpace& _shs, coordinate_t maxX, coordinate_t minX, - coordinate_t maxY, coordinate_t minY, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : MapBuilderRequest(num), shs(_shs), - area(Shape - (new BlobData - (VRmixin::groundShS,Point(maxX,maxY),Point(maxX,minY), - Point(minX,maxY),Point(minX,minY),(maxX-minX)*(maxY-minY), - vector(),BlobData::groundplane,rgb(0,0,0)))), - maxDist(_maxDist), clearShapes(clear), pursueShapes(true), manualHeadMotion(false), - removePts(true), doScan(_doScan) {} -}; - -class LocalMapTestRequest : public LocalMapRequest { -public: - LocalMapTestRequest(bool (*func)(), coordinate_t maxX, coordinate_t minX, - coordinate_t maxY, coordinate_t minY, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : LocalMapRequest(maxX,minX,maxY,minY,_maxDist,num,clear,_doScan), exitTest(func){} - - LocalMapTestRequest(const LocalMapTestRequest& req) - : LocalMapRequest(req), exitTest(req.exitTest) {} - - virtual ~LocalMapTestRequest() {} - - bool (*exitTest)(); - -private: - LocalMapTestRequest& operator=(const LocalMapTestRequest&); -}; - -class WorldMapRequest : public LocalMapRequest { -public: - virtual MapBuilderRequestType_t getRequestType() const { return worldMap; } - - //! Constructor using a shape to specify area - WorldMapRequest(const ShapeRoot& _area, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : LocalMapRequest(VRmixin::worldShS,_area,_maxDist,num,clear,_doScan) {} - - //! Constructor using a bounding box - WorldMapRequest(coordinate_t maxX, coordinate_t minX, coordinate_t maxY, - coordinate_t minY, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : LocalMapRequest(VRmixin::worldShS,maxX,minX,maxY,minY,_maxDist,num,clear,_doScan) {} - - //! Copy constructor - WorldMapRequest(const WorldMapRequest& req) : LocalMapRequest(req) {} - - virtual ~WorldMapRequest() {} -}; - -class WorldMapTestRequest : public WorldMapRequest { -public: - // virtual MapBuilderRequestType_t getRequestType() const { return worldMapTest; } - WorldMapTestRequest(bool (*func)(), const ShapeRoot& _area, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : WorldMapRequest(_area,_maxDist,num,clear,_doScan), exitTest(func){} - WorldMapTestRequest(bool (*func)(), coordinate_t maxX, coordinate_t minX, - coordinate_t maxY, coordinate_t minY, unsigned int _maxDist, - unsigned int num=1, bool clear=true, bool _doScan=true) - : WorldMapRequest(maxX,minX,maxY,minY,_maxDist,num,clear,_doScan), exitTest(func){} - WorldMapTestRequest(const WorldMapTestRequest& req) - : WorldMapRequest(req), exitTest(req.exitTest) {} - virtual ~WorldMapTestRequest() {} - bool (*exitTest)(); -private: - WorldMapTestRequest& operator=(const WorldMapTestRequest&); -}; - -} // namespace - -#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Measures.cc ./DualCoding/Measures.cc --- ../Tekkotsu_3.0/DualCoding/Measures.cc 2006-03-21 16:03:48.000000000 -0500 +++ ./DualCoding/Measures.cc 1969-12-31 19:00:00.000000000 -0500 @@ -1,72 +0,0 @@ -#include "Measures.h" - -namespace DualCoding { - -AngPi::AngPi(orientation_t const &v) : value(v) { - // Do cheap tests first; use fmod only if necessary. - if ( value < 0 ) - value += Pi; - else if ( value >= Pi) - value -= Pi; - else return; - // If we're still out of range, give up and call fmod. - if ( value < 0 || value >= Pi) { - value = fmod(value,Pi); - if ( value < 0 ) - value += Pi; - }; -} - - -AngPi angdist(AngPi const &arg1, AngPi const &arg2) { - AngPi diff = arg1.value - arg2.value; - if ( diff > Pi/2 ) - diff = Pi - diff; - return diff; -} - -AngTwoPi::AngTwoPi(direction_t const &v) : value(v) { - // Do cheap tests first; use fmod only if necessary. - if ( value < 0 ) - value += TwoPi; - else if ( value >= TwoPi) - value -= TwoPi; - else return; - // If we're still out of range, give up and call fmod. - if ( value < 0 || value >= TwoPi) { - value = fmod(value,TwoPi); - if ( value < 0 ) - value += TwoPi; - }; -} - -AngPi angdist(AngTwoPi const &arg1, AngTwoPi const &arg2) { - AngTwoPi diff = arg1.value - arg2.value; - if ( diff > Pi ) - diff = TwoPi - diff; - return AngPi(diff); -} - -AngSignPi::AngSignPi(direction_t const &v) : value(v) { - // Do cheap tests first; use fmod only if necessary. - if ( value < -Pi ) - value += TwoPi; - else if ( value > Pi) - value -= TwoPi; - else return; - // If we're still out of range, give up and call fmod. - if ( value < -Pi || value > Pi) { - value = fmod(value,TwoPi); - if (value < -Pi) - value += TwoPi; - }; -} - -AngPi angdist(AngSignPi const &arg1, AngSignPi const &arg2) { - AngSignPi diff = arg1.value - arg2.value; - if ( diff > Pi ) - diff = TwoPi - diff; - return AngPi(diff); -} - -} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Measures.h ./DualCoding/Measures.h --- ../Tekkotsu_3.0/DualCoding/Measures.h 2006-09-21 18:58:57.000000000 -0400 +++ ./DualCoding/Measures.h 1969-12-31 19:00:00.000000000 -0500 @@ -1,83 +0,0 @@ -#ifndef _MEASURES_H_ -#define _MEASURES_H_ - -#include - -namespace DualCoding { - -typedef float coordinate_t; //!< type used for positional coordinates -typedef float orientation_t; //!< type used for orientation values (0 to Pi) -typedef float direction_t; //!< type used for direction values (0 to 2*Pi) - -const direction_t Pi=M_PI; //!< shorthand for ::M_PI from math.h -const direction_t TwoPi=2*M_PI; //!< shorthand for 2*M_PI - -typedef coordinate_t Slope; //!< type used for ratio of coordinate offsets -const Slope BIG_SLOPE=5000.0; //!< slopes larger than this are considered vertical, or in other words, infinite slopes are rounded to this - -//! Circular arithmetic on angles between 0 and pi (180 degrees) -class AngPi { - public: - orientation_t value; - - AngPi(void) : value(0) {}; - AngPi(orientation_t const &v); - AngPi operator+(AngPi const &arg) const { return AngPi(value+arg.value); }; - AngPi operator-(AngPi const &arg) const { return AngPi(value-arg.value); }; - AngPi operator*(orientation_t const &arg) const { return AngPi(value*arg); }; - AngPi operator/(orientation_t const &arg) const { return AngPi(value/arg); }; - - AngPi& operator=(AngPi const &arg) { value = arg.value; return(*this); }; - AngPi& operator=(orientation_t const &arg) { value = AngPi(arg); return(*this); }; - - operator orientation_t() const { return value; }; -}; - -//! Angular distance: value is between 0 and pi -AngPi angdist(AngPi const &arg1, AngPi const &arg2); - -//! Circular arithmetic on angles between 0 and two pi (360 degrees) -class AngTwoPi { - public: - direction_t value; - - AngTwoPi(void) : value(0) {}; - AngTwoPi(direction_t const &v); - AngTwoPi operator+(AngTwoPi const &arg) const { return AngTwoPi(value+arg.value); }; - AngTwoPi operator-(AngTwoPi const &arg) const { return AngTwoPi(value-arg.value); }; - AngTwoPi operator*(direction_t const &arg) const { return AngTwoPi(value*arg); }; - AngTwoPi operator/(direction_t const &arg) const { return AngTwoPi(value/arg); }; - - AngTwoPi& operator=(AngTwoPi const &arg) { value = arg.value; return(*this); }; - AngTwoPi& operator=(direction_t const &arg) { value = AngTwoPi(arg); return(*this); }; - - operator direction_t() const { return value; }; -}; - -//! Angular distance: value is between 0 and pi -AngPi angdist(AngTwoPi const &arg1, AngTwoPi const &arg2); - -//! Circular arithmetic on angles between -pi and pi (360 degrees) -class AngSignPi { - public: - direction_t value; - - AngSignPi(void) : value(0) {}; - AngSignPi(direction_t const &v); - AngSignPi operator+(AngSignPi const &arg) const { return AngSignPi(value+arg.value); }; - AngSignPi operator-(AngSignPi const &arg) const { return AngSignPi(value-arg.value); }; - AngSignPi operator*(direction_t const &arg) const { return AngSignPi(value*arg); }; - AngSignPi operator/(direction_t const &arg) const { return AngSignPi(value/arg); }; - - AngSignPi& operator=(AngSignPi const &arg) { value = arg.value; return(*this); }; - AngSignPi& operator=(direction_t const &arg) { value = AngSignPi(arg); return(*this); }; - - operator direction_t() const { return value; }; -}; - -//! Angular distance: value is between 0 and pi -AngPi angdist(AngSignPi const &arg1, AngSignPi const &arg2); - -} // namespace - -#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PFShapeLocalization.cc ./DualCoding/PFShapeLocalization.cc --- ../Tekkotsu_3.0/DualCoding/PFShapeLocalization.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/PFShapeLocalization.cc 2007-04-20 06:50:52.000000000 -0400 @@ -0,0 +1,180 @@ +//-*-c++-*- + +#include +#include + +#include "MapBuilder.h" +#include "PFShapeLocalization.h" +#include "ShapeLocalizationParticle.h" +#include "ShapeSpace.h" +#include "ShapeFuns.h" +#include "VRmixin.h" // for mapBuilder + +using namespace std; + +namespace DualCoding { + + ParticleShapeEvaluator::ParticleShapeEvaluator(ShapeSpace &localShS, ShapeSpace &worldShS) : + localLms(), worldLms(), + maxDist(0), + localMatches(), numMatches(0), localScores(), + particleViewX(), particleViewY(), particleViewX2(), particleViewY2() + { + PfRoot::loadLms(localShS.allShapes(), false, localLms); + PfRoot::loadLms(worldShS.allShapes(), true, worldLms); + if ( localLms.size()==0 || worldLms.size()==0 ) { + cout << "ParticleFilter::loadLms found " << localLms.size() << " local and " + << worldLms.size() << " world landmarks: can't localize!" << endl; + return; + } + unsigned int nlocal = localLms.size(); + localScores.resize(nlocal); + localMatches.resize(nlocal); + particleViewX.resize(nlocal); + particleViewY.resize(nlocal); + particleViewX2.resize(nlocal); + particleViewY2.resize(nlocal); + } + + void ParticleShapeEvaluator::evaluate(LocalizationParticle& part) { + // determine position of local space landmark in world given the current particle + float const cosT = cos(-part.theta); + float const sinT = sin(-part.theta); + float const negSinT = -sinT; + // constructor has already verified that localLms > 0 and worldLms > 0 + for ( unsigned int j=0; j < localLms.size(); j++ ) { + PfRoot &landmark = *(localLms[j]); + particleViewX[j] = landmark.x * cosT + landmark.y * sinT + part.x; + particleViewY[j] = landmark.x * negSinT + landmark.y * cosT + part.y; + if ( landmark.type == lineDataType ) { + const PfLine &line = static_cast(landmark); + particleViewX2[j] = line.x2 * cosT + line.y2 * sinT + part.x; + particleViewY2[j] = line.x2 * negSinT + line.y2 * cosT + part.y; + } + } + + // now compute score for the particle by finding matches between local landmarks and world landmarks + numMatches=0; + for ( unsigned int j = 0; jtype == worldLms[k]->type && + localLms[j]->color == worldLms[k]->color ) { + float const lx = particleViewX[j]; + float const ly = particleViewY[j]; + float const wx = worldLms[k]->x; + float const wy = worldLms[k]->y; + float tempDistsq; + switch ( localLms[j]->type ) { + case lineDataType: { + PfLine &localLine = *static_cast(localLms[j]); + PfLine &worldLine = *static_cast(worldLms[k]); + float tempDistsq1, tempDistsq2; + // If endpoints are valid, compare distance between endpoints. + // If not valid, measure perpendicular distance from the local endpoint + // to the world line segment, if the projection of the endpoint onto the + // segment occurs within the segment, not beyond it. Instead of calculating + // the projection we use a heuristic test: either the x or y endpoint value must + // lie within the range of the line segment. + if ( (localLine.valid1 && worldLine.valid1) || + !( lx >= min(worldLine.x,worldLine.x2) && + lx <= max(worldLine.x,worldLine.x2) || + ly >= min(worldLine.y,worldLine.y2) && + ly <= max(worldLine.y,worldLine.y2) ) ) + tempDistsq1 = (lx-wx)*(lx-wx) + (ly-wy)*(ly-wy); + else { + float const tempDist1 = distanceFromLine(lx,ly,worldLine); + tempDistsq1 = tempDist1 * tempDist1; + } + float const lx2 = particleViewX2[j]; + float const ly2 = particleViewY2[j]; + float const wx2 = worldLine.x2; + float const wy2 = worldLine.y2; + if ( (localLine.valid2 && worldLine.valid2) || + !( lx2 >= min(worldLine.x,worldLine.x2) && + lx2 <= max(worldLine.x,worldLine.x2) || + ly2 >= min(worldLine.y,worldLine.y2) && + ly2 <= max(worldLine.y,worldLine.y2) ) ) + tempDistsq2 = (lx2-wx2)*(lx2-wx2) + (ly2-wy2)*(ly2-wy2); + else { + float const tempDist2 = distanceFromLine(lx2,ly2,worldLine); + tempDistsq2 = tempDist2 * tempDist2; + } + AngPi const localOrient = localLine.orientation + part.theta; + AngPi const odiff = worldLine.orientation - localOrient; + float const odist = 500 * sin(odiff); + float const odistsq = odist * odist; + tempDistsq = tempDistsq1 + tempDistsq2 + odistsq; // plus orientation match term? + } + break; + case ellipseDataType: + case pointDataType: + case blobDataType: { + tempDistsq = (lx-wx)*(lx-wx) + (ly-wy)*(ly-wy); + break; + } + default: + std::cout << "ParticleFilter::computeMatchScore() can't match landmark type " + << localLms[j]->type << std::endl; + return; + } + if ( tempDistsq < distsq ) { + distsq = tempDistsq; + localMatches[j] = k; + } + } + } + + if ( localMatches[j] != -1 || !localLms[j]->mobile ) + localScores[numMatches++]=distsq; + } + } + + float ParticleShapeEvaluator::distanceFromLine(coordinate_t x0, coordinate_t y0, PfLine &wline) { + float const &x1 = wline.x; + float const &y1 = wline.y; + float const &x2 = wline.x2; + float const &y2 = wline.y2; + float const &length = wline.length; + float const result = fabs((x2-x1)*(y1-y0) - (x1-x0)*(y2-y1)) / length; + return result; + } + + void PFShapeLocalization::setAgent() const { + const PFShapeLocalization::particle_type& best = particles[bestIndex]; + VRmixin::mapBuilder.setAgent(Point(best.x,best.y,0,allocentric), best.theta); + } + + void PFShapeLocalization::setPosition(float const x, float const y, AngTwoPi const orientation, float variance) { + LocalizationParticle part(x, y, orientation); + setPosition(part, variance); + } + + void PFShapeLocalization::setWorldBounds(const Shape &bounds) { + PFShapeDistributionPolicy *dist = + dynamic_cast *>(&(getResamplingPolicy()->getDistributionPolicy())); + if ( dist != NULL ) + dist->setWorldBounds(bounds); + else + cout << "Error: setWorldBounds found wrong type of DistributionPolicy" << endl; + } + + void PFShapeLocalization::displayParticles(float const howmany) const { + ShapeSpace &wShS = sensorModel->getWorldShS(); + wShS.deleteShapes(); + NEW_SHAPE(best, LocalizationParticleData, new LocalizationParticleData(wShS,particles[bestIndex])); + best->setColor(VRmixin::mapBuilder.getAgent()->getColor()); + if ( howmany <= 0 ) return; + unsigned int increment; + if ( howmany <= 1.0 ) + increment = (unsigned int)ceil(1.0/howmany); + else + increment = (unsigned int)ceil(particles.size()/howmany); + for (unsigned int i=0; i +#include +#include +#include "Shared/LocalizationParticle.h" +#include "ParticleShapes.h" +#include "Behaviors/Services/DeadReckoningBehavior.h" +#include "DualCoding/ShapePolygon.h" + +#ifndef USE_LOGWEIGHTS +# define USE_LOGWEIGHTS 1 +#endif + +namespace DualCoding { + +class ShapeSpace; + + //! provides evaluation of the matching between local and world given a candidate particle + /*! The reason for separating ParticleShapeEvaluator and ShapeSensorModel? Partly so the + * fairly lengthy evaluation code can go in the .cc file to avoid repeated recompilation, but also to + * allow inheritance (e.g. SLAMShapeParticleEvaluator) as a clean way to extend the + * evaluation code for particle sub-types. */ +class ParticleShapeEvaluator { +public: + //! constructor, pass the local and world shape spaces, these will be used to initialize the appropriate particle-independent fields of the class + ParticleShapeEvaluator(ShapeSpace &localShS, ShapeSpace &worldShS); + virtual ~ParticleShapeEvaluator() {} //!< destructor + + //! the heart of the class, call with a particle, will adjust the weight + void evaluate(LocalizationParticle& part); + + void setMaxDist(float const dist) { maxDist = dist; } + const std::vector& getLocalScores() const { return localScores; } + unsigned int getNumMatches() const { return numMatches; } + + std::vector localLms; //!< a vector of the landmarks in the local space + std::vector worldLms; //!< a vector of landmarks in the world space + + float maxDist; //!< maximum distance for a landmark to be useful in distance error calculation + + std::vector localMatches; //!< Index of best matching world landmark for each local landmark according to the currently-selected particle + unsigned int numMatches; //!< number of matches found + std::vector localScores; //!< Match scores for local landmarks according to this particle, only first #numMatches are filled in (skip non-matching) + + //! helper function which calculates the distance between a point and a line along a perpendicular + static float distanceFromLine(coordinate_t x0, coordinate_t y0, PfLine &wline); + + std::vector particleViewX; //!< x coords of local landmarks according to the currently-selected particle + std::vector particleViewY; //!< y coords of local landmarks according to the currently-selected particle + std::vector particleViewX2; //!< x coords of other point of local line + std::vector particleViewY2; //!< y coords of other point of local line +}; + + + +//================ ShapeSensorModel ================ + +//! this wraps the ParticleShapeEvaluator in a ParticleFilter::SensorModel so it can be used by the particle filter +/*! The reason for separating ParticleShapeEvaluator and ShapeSensorModel? Partly so the + * fairly length evaluation code can go in the .cc file to avoid repeated recompilation, but also to + * allow inheritance (e.g. SLAMShapesParticleEvaluator) as a clean way to extend the + * evaluation code for particle sub-types. Ideally, I'd like to combine these classes. */ + +template +class ShapeSensorModel : public ParticleFilter::SensorModel { +public: + typedef typename ParticleFilter::SensorModel::index_t index_t; //!< convenience typedef + typedef typename ParticleFilter::SensorModel::particle_collection particle_collection; //!< convenience typedef + + //! constructor, the standard deviation on matches defaults to 60, but you can always reassign #stdevSq directly + ShapeSensorModel(ShapeSpace &localShS, ShapeSpace &worldShS) : + stdevSq(60*60), lShS(localShS), wShS(worldShS) + {} + + //! controls how much weight is given to "near-misses" + float stdevSq; + + //! applies the ParticleShapeEvaluator across a collection of particles and tracks the best weight + virtual void evaluate(particle_collection& particles, index_t& bestIndex) { + float bestWeight=-FLT_MAX; + ParticleShapeEvaluator eval(lShS,wShS); + for(typename particle_collection::size_type p=0; pbestWeight) { + bestWeight=particles[p].weight; + bestIndex=p; + } + } + } + + ShapeSpace& getLocalShS() const { return lShS; } + ShapeSpace& getWorldShS() const { return wShS; } + +protected: + ShapeSpace &lShS; //!< Local shape space + ShapeSpace &wShS; //!< World shape space + + //!< computes a (non-normalized) gaussian distribution + /*! normalization isn't needed because the scale factor is constant across particles, and so + * doesn't matter for purposes of comparison between particles */ + inline float normpdf(float const distsq) { return std::exp(-distsq/stdevSq); } +}; + + +//================ PFShapeDistributionPolicy ================ + +template +class PFShapeDistributionPolicy : public LocalizationParticleDistributionPolicy { +public: + typedef ParticleT particle_type; //!< just for convenience + typedef typename ParticleFilter::index_t index_t; //!< just for convenience + + PFShapeDistributionPolicy() : LocalizationParticleDistributionPolicy(), worldBounds() {} + + virtual void randomize(particle_type* begin, index_t num) { + particle_type* end=&begin[num]; + while(begin!=end) { + while (1) { // loop until particle is acceptable + begin->x = float(rand())/RAND_MAX * LocalizationParticleDistributionPolicy::mapWidth + + LocalizationParticleDistributionPolicy::mapMinX; + begin->y = float(rand())/RAND_MAX * LocalizationParticleDistributionPolicy::mapHeight + + LocalizationParticleDistributionPolicy::mapMinY; + if ( !worldBounds.isValid() || worldBounds->isInside(Point(begin->x,begin->y)) ) + break; + } + begin->theta = float(rand())/RAND_MAX * 2 * M_PI; + ++begin; + } + } + + virtual void jiggle(float var, particle_type* begin, index_t num) { + if(var==0) + return; + particle_type* end=&begin[num]; + while(begin!=end) { + float dx=0, dy=0; + for (int i=0; i<4; i++) { + float rx = DRanNormalZig32()*LocalizationParticleDistributionPolicy::positionVariance*var; + float ry = DRanNormalZig32()*LocalizationParticleDistributionPolicy::positionVariance*var; + if ( !worldBounds.isValid() || worldBounds->isInside(Point(begin->x+rx, begin->y+ry)) ) { + dx = rx; + dy = ry; + break; + } + } + begin->x += dx; + begin->y += dy; + begin->theta+=DRanNormalZig32()*LocalizationParticleDistributionPolicy::orientationVariance*var; + ++begin; + } + } + + virtual void setWorldBounds(const Shape bounds) { + worldBounds = bounds; + if ( worldBounds.isValid() ) { + BoundingBox b(worldBounds->getBoundingBox()); + LocalizationParticleDistributionPolicy::mapMinX = b.xmin; + LocalizationParticleDistributionPolicy::mapWidth = b.xmax - b.xmin; + LocalizationParticleDistributionPolicy::mapMinY = b.ymin; + LocalizationParticleDistributionPolicy::mapHeight = b.ymax - b.ymin; + } + } + +protected: + Shape worldBounds; //!< If valid shape, particles must lie inside it. +}; + +//================ PFShapeLocalization ================ + +//! bundles a DeadReckoning motion model and a ShapeSensorModel for easy use of a shape-based particle filter for localization + +class PFShapeLocalization : public ParticleFilter { +public: + //! constructor, must pass local and world shape spaces, which will be used in future calls to update() + PFShapeLocalization(ShapeSpace &localShS, ShapeSpace &worldShS, unsigned int numParticles=2000) + : ParticleFilter(numParticles, new DeadReckoningBehavior), + sensorModel(new ShapeSensorModel(localShS,worldShS)) + { + getResamplingPolicy()->setDistributionPolicy(new PFShapeDistributionPolicy); + if(BehaviorBase* motBeh = dynamic_cast(motion)) + motBeh->DoStart(); + } + + //! destructor + virtual ~PFShapeLocalization() { + if(BehaviorBase* motBeh = dynamic_cast(motion)) { + motBeh->DoStop(); + // behaviors are reference counted, stopping removes our reference, set to NULL to avoid call to delete in ParticleFilter + motion=NULL; + } + delete sensorModel; + } + + //! update, triggers a particle filter update using the embedded #sensorModel + virtual void update(bool updateMot=true, bool doResample=true) { updateSensors(*sensorModel,updateMot,doResample); } + + //! accessor for #sensorModel + virtual ShapeSensorModel& getSensorModel() const { return *sensorModel; } + + //! replaces the sensor model in use, the particle filter will take responsibility for deallocating the sensor model's memory when destructed or replaced + virtual void setSensorModel(ShapeSensorModel* customSensorModel) { + delete sensorModel; + sensorModel=customSensorModel; + } + + //! updates the mapbuilder's agent's position on worldShS + virtual void setAgent() const; + + //! resets particles to the specified position and orientation, and optionally jiggles them by variance + virtual void setPosition(float const x, float const y, AngTwoPi const orientation, float variance=0); + using ParticleFilter::setPosition; + + //! sets boundary within which particles should lie + virtual void setWorldBounds(const Shape &bounds); + + //! displays particles on the world map; howmany can either be a percentage (<= 1.0) or a whole number + virtual void displayParticles(float const howmany=100) const; + +protected: + ShapeSensorModel * sensorModel; //!< provides evaluation of particles + +private: + PFShapeLocalization(const PFShapeLocalization&); //!< don't call (copy constructor) + PFShapeLocalization& operator=(const PFShapeLocalization&); //!< don't call (assignment operator) +}; + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PFShapeSLAM.cc ./DualCoding/PFShapeSLAM.cc --- ../Tekkotsu_3.0/DualCoding/PFShapeSLAM.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/PFShapeSLAM.cc 2007-03-01 06:17:34.000000000 -0500 @@ -0,0 +1,123 @@ +//-*-c++-*- + +#include +#include + +#include "ShapeSpace.h" +#include "MapBuilder.h" +#include "PFShapeSLAM.h" +#include "ShapeLocalizationParticle.h" +#include "VRmixin.h" // for mapBuilder + +using namespace std; + +namespace DualCoding { + + void SLAMParticleShapeEvaluator::evaluate(SLAMShapesParticle& part) { + ParticleShapeEvaluator::evaluate(part); + for(unsigned int i=0; imobile ); + if ( localMobile ) + determineAdditions(part); + if ( worldMobile ) + determineDeletions(part); + // cout << "computeParticleScores(): best particle = " << bestIndex + // << ": " << bestProb << endl; + } + + void SLAMParticleShapeEvaluator::determineAdditions(SLAMShapesParticle& part) { + for (unsigned int j = 0; jmobile ) { + float const randval = float(rand()) / (RAND_MAX*6); + if (randval >= localScores[j]) { + part.addLocal[j] = true; + localScores[numMatches++] = ADDITION_PENALTY; + localMatches[j] = -1; + continue; + } + for (unsigned int j2 = (j+1); j2 localScores[j]) { + part.addLocal[j] = true; + localScores[numMatches++] = ADDITION_PENALTY; + localMatches[j] = -1; + } else { + part.addLocal[j2] = true; + localScores[numMatches++] = ADDITION_PENALTY; + localMatches[j2] = -1; + } + } + } + } + } + + void SLAMParticleShapeEvaluator::determineDeletions(SLAMShapesParticle& part) { + part.deleteWorld.assign(part.deleteWorld.size(),true); + + float minXLoc = HUGE_VAL; + float minYLoc = HUGE_VAL; + float maxXLoc = -HUGE_VAL; + float maxYLoc = -HUGE_VAL; + for (unsigned int j = 0; j maxXLoc) + maxXLoc = particleViewX[j]; + if (particleViewY[j] < minYLoc) + minYLoc = particleViewY[j]; + else if (particleViewY[j] > maxYLoc) + maxYLoc = particleViewY[j]; + } + + for (unsigned int k = 0; kmobile || + !( worldLms[k]->x >= minXLoc && worldLms[k]->x <= maxXLoc && + worldLms[k]->y >= minYLoc && worldLms[k]->y <= maxYLoc ) ) + part.deleteWorld[k] = false; // don't delete world LM if not mobile, or it was outside local view + } + + + void PFShapeSLAM::setAgent() const { + const PFShapeSLAM::particle_type& best = particles[bestIndex]; + VRmixin::mapBuilder.setAgent(Point(best.x,best.y), best.theta); + } + + void PFShapeSLAM::displayParticles(float const howmany) const { + ShapeSpace &wShS = sensorModel->getWorldShS(); + wShS.deleteShapes(); + NEW_SHAPE(best, LocalizationParticleData, new LocalizationParticleData(wShS,particles[bestIndex])); + best->setColor(VRmixin::mapBuilder.getAgent()->getColor()); + if ( howmany <= 0 ) return; + int increment; + if ( howmany <= 1.0 ) + increment = (int)ceil(1.0/howmany); + else + increment = (int)ceil(particles.size()/howmany); + for (unsigned int i=0; i +#include +#include +#include "Behaviors/Services/DeadReckoningBehavior.h" +#include "Shared/LocalizationParticle.h" + +#include "PFShapeLocalization.h" + +#ifndef USE_LOGWEIGHTS +# define USE_LOGWEIGHTS 1 +#endif + +namespace DualCoding { + + class ShapeSpace; + class SLAMShapesParticleDistributionPolicy; + + //! Each Particle represents a hypothesis about the match of the local map to the world map, considering changes to the map + /*! Only handles adding or removing landmarks, not moving existing landmarks. (A move + * can be modeled as an addition plus a deletion, but there will be two penalties to pay.) + * + * Note that the particle evaluation doesn't modify the world map, only + * tracks suggestions about what @e should be changed. + * + * The size of addLocal and deleteWorld may not exactly match the number + * of current local or world landmarks -- the SensorModel is lazy about resizing + * for efficiency reasons. */ + class SLAMShapesParticle : public LocalizationParticle { + public: + //! Defines a default DistributionPolicy for the particle type (just reuse the same one as LocalizationParticle) + typedef LocalizationParticleDistributionPolicy DistributionPolicy; + + //! Constructor + SLAMShapesParticle() : LocalizationParticle(), addLocal(), deleteWorld() {} + + std::vector addLocal; //!< true for local landmarks missing from the world map + std::vector deleteWorld; //!< true for world landmarks missing from the local map + }; + + //! extends ParticleShapeEvaluator to handle the addition and removal of landmarks as necessary + class SLAMParticleShapeEvaluator : public ParticleShapeEvaluator { + public: + //! constructor, addPenalty specifies how much to add/multiply (logspace/linear space) weight when considering a landmark as an addition + SLAMParticleShapeEvaluator(ShapeSpace &localShS, ShapeSpace &worldShS, float addPenalty) : + ParticleShapeEvaluator(localShS,worldShS), localMobile(false), worldMobile(false), ADDITION_PENALTY(addPenalty) + { + for ( unsigned int j=0; jmobile; + for ( unsigned int k=0; kmobile; + } + using ParticleShapeEvaluator::evaluate; + void evaluate(SLAMShapesParticle& part); //!< provides evaluation of SLAM-particles + protected: + void determineAdditions(SLAMShapesParticle& part); //!< may mark landmarks for addition which don't appear in the world map + void determineDeletions(SLAMShapesParticle& part); //!< may mark landmarks for removal which don't appear in the world map + bool localMobile; //!< set to true if *any* landmarks are marked as "mobile" + bool worldMobile; //!< set to true if *any* landmarks are marked as "mobile" + const float ADDITION_PENALTY; //!< the value passed to the constructor, limits how readily landmarks are added to the map + }; + + +//================ SLAMShapesSensorModel ================ + + //! this wraps the SLAMParticleShapeEvaluator in a ParticleFilter::SensorModel so it can be used by the particle filter + /*! see ShapeSensorModel for discussion of architectural issues vs separation of SLAMParticleShapeEvaluator */ + template + class SLAMShapesSensorModel : public ParticleFilter::SensorModel { + public: + typedef typename ParticleFilter::SensorModel::index_t index_t; //!< convenience typedef + typedef typename ParticleFilter::SensorModel::particle_collection particle_collection; //!< convenience typedef + + //! constructor, the standard deviation on matches defaults to 60, but you can always reassign #stdevSq directly + SLAMShapesSensorModel(ShapeSpace &localShS, ShapeSpace &worldShS) : + stdevSq(60*60), addPenalty(50), lShS(localShS), wShS(worldShS), + particleLocalLandmarks(0), particleWorldLandmarks(0) + {} + + //! controls how much weight is given to "near-misses" + float stdevSq; + //! controls how readily new landmarks are added to the map, vs. penalizing the particle for a bad match + float addPenalty; + + //! applies the SLAMParticleShapeEvaluator across a collection of particles and tracks the best weight + virtual void evaluate(particle_collection& particles, index_t& bestIndex) { + float bestWeight=-FLT_MAX; + SLAMParticleShapeEvaluator eval(lShS,wShS,addPenalty); + + if(eval.localLms.size()>particleLocalLandmarks || eval.localLms.size()addLocal.resize(particleLocalLandmarks); + + if(eval.worldLms.size()>particleWorldLandmarks || eval.worldLms.size()deleteWorld.resize(particleWorldLandmarks); + + for(typename particle_collection::size_type p=0; pbestWeight) { + bestWeight=particles[p].weight; + bestIndex=p; + } + } + } + + ShapeSpace& getLocalShS() const { return lShS; } + ShapeSpace& getWorldShS() const { return wShS; } + + protected: + ShapeSpace &lShS; //!< Local shape space + ShapeSpace &wShS; //!< World shape space + + unsigned int particleLocalLandmarks; //!< number of entries in particles' individual addLocal (so we know if we need to resize it in all particles) + unsigned int particleWorldLandmarks; //!< number of entries in particles' individual deleteWorld (so we know if we need to resize it in all particles) + + //! computes a (non-normalized) gaussian distribution + /*! normalization doesn't matter because it's constant across particles, and so + * doesn't matter for purposes of comparison between particles */ + inline float normpdf(float const distsq) { return std::exp(-distsq/stdevSq); } + }; + + +//================ PFShapeSLAM ================ + + //! bundles a DeadReckoning motion model and a SLAMShapesSensorModel for easy use of a shape-based particle filter for mapping and localization + class PFShapeSLAM : public ParticleFilter { + public: + //! constructor, must pass local and world shape spaces, which will be used in future calls to update() + PFShapeSLAM(ShapeSpace &localShS, ShapeSpace &worldShS, unsigned int numParticles=2000) + : ParticleFilter(numParticles, new DeadReckoningBehavior), + sensorModel(new SLAMShapesSensorModel(localShS,worldShS)) + { + if(BehaviorBase* motBeh = dynamic_cast(motion)) + motBeh->DoStart(); + } + //! destructor + virtual ~PFShapeSLAM() { + if(BehaviorBase* motBeh = dynamic_cast(motion)) { + motBeh->DoStop(); + // behaviors are reference counted, stopping removes our reference, set to NULL to avoid call to delete in ParticleFilter + motion=NULL; + } + delete sensorModel; + } + + //! update, triggers a particle filter update using the embedded #sensorModel + virtual void update(bool updateMot=true, bool doResample=true) { updateSensors(*sensorModel,updateMot,doResample); } + + //! accessor for #sensorModel + virtual SLAMShapesSensorModel& getSensorModel() const { return *sensorModel; } + + //! replaces the sensor model in use, the particle filter will take responsibility for deallocating the sensor model's memory when destructed or replaced + virtual void setSensorModel(SLAMShapesSensorModel* customSensorModel) { delete sensorModel; sensorModel=customSensorModel; } + + //! updates the mapbuilder's agent's position on worldShS + virtual void setAgent() const; + + //! displays particles on the world map; howmany can either be a percentage (<= 1.0) or a whole number + virtual void displayParticles(float const howmany=100) const; + + protected: + SLAMShapesSensorModel * sensorModel; //!< provides evaluation of particles + + private: + PFShapeSLAM(const PFShapeSLAM&); //!< don't call (copy constructor) + PFShapeSLAM& operator=(const PFShapeSLAM&); //!< don't call (assignment operator) + }; + + //! allows display of particles on console + std::ostream& operator<< (std::ostream& os, const SLAMShapesParticle &p); + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Particle.cc ./DualCoding/Particle.cc --- ../Tekkotsu_3.0/DualCoding/Particle.cc 2006-05-10 19:21:57.000000000 -0400 +++ ./DualCoding/Particle.cc 1969-12-31 19:00:00.000000000 -0500 @@ -1,26 +0,0 @@ -//-*-c++-*- - -#include -#include - -#include "Particle.h" - -namespace DualCoding { - -ostream& operator << (ostream& os, const Particle &p){ - os << "Particle(p=" << p.prob - << ", dx=" << p.dx - << ", dy=" << p.dy - << ", th=" << p.theta - << ", add="; - for (unsigned int i = 0; i -#include - -#include "Measures.h" // coordinate_t, AngTwoPi - -using namespace std; - -namespace DualCoding { - -//! Each Particle represents a hypothesis about the match of the local map to the world map. - -class Particle { - public: - coordinate_t dx, dy; //!< Translation from local to world coordinates - AngTwoPi theta; //!< Rotation of local map into world map - vector addLocal; //!< true for local landmarks missing from the world map - // vector deleteWorld; //!< true for world landmarks missing from the local map - float prob; //!< Computed likelihood of this Particle - - //! Constructor - Particle() : dx(0), dy(0), theta(0), addLocal(), - // deleteWorld(nworld,false), - prob(-1) {} - -}; - -ostream& operator << (ostream& os, const Particle &p); - -} // namespace - -#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ParticleFilter.cc ./DualCoding/ParticleFilter.cc --- ../Tekkotsu_3.0/DualCoding/ParticleFilter.cc 2006-10-02 17:54:56.000000000 -0400 +++ ./DualCoding/ParticleFilter.cc 1969-12-31 19:00:00.000000000 -0500 @@ -1,406 +0,0 @@ -//-*-c++-*- - -#include -#include - -#include - -#include "BaseData.h" // for BoundingBox -#include "Particle.h" -#include "ParticleShapes.h" -#include "ParticleFilter.h" - -namespace DualCoding { - -const float ParticleFilter::INITIAL_XY_NOISE; -const float ParticleFilter::INITIAL_THETA_NOISE; -const float ParticleFilter::NOISE_REDUCTION_XY; -const float ParticleFilter::NOISE_REDUCTION_T; -const float ParticleFilter::INFINITE_DISTANCE; -const float ParticleFilter::STDEV; -const float ParticleFilter::ADDITION_PENALTY; -const float ParticleFilter::PERCENT_RANDOM; - - -void ParticleFilter::reinitialize() { - delete curParticles; - delete newParticles; - curParticles=NULL; - newParticles=NULL; - numParticles = NUM_PARTICLES; - numParticles = NUM_PARTICLES; - numGenerations = NUM_GENERATIONS; - numTries = NUM_TRIES; - noiseFactorXY = INITIAL_XY_NOISE; - noiseFactorT = INITIAL_THETA_NOISE; - worldBounds = Shape(); - bestIndex = -1; - localScores.clear(); - localMatches.clear(); -} - -void ParticleFilter::makeParticles() { - delete curParticles; - delete newParticles; - curParticles = new vector(numParticles); - newParticles = new vector(numParticles); -} - -void ParticleFilter::resizeParticles() { - for ( int i=0; isize(); - nworld = worldLms->size(); - if ( nlocal==0 || nworld==0 ) { - cout << "ParticleFilter::loadLMs found " << nlocal << " local and " - << nworld << " world landmarks: can't localize!" << endl; - return; - } - - // Determine x,y bounds for resampling. If there is a world bounding - // polygon, use its bounding box. - if ( worldBounds.isValid() ) { - BoundingBox b(worldBounds->getBoundingBox()); - xmin = b.xmin; - xmax = b.xmax; - ymin = b.ymin; - ymax = b.ymax; - } - else { - coordinate_t localXmin, localYmin, localXmax, localYmax; - coordinate_t worldXmin, worldYmin, worldXmax, worldYmax; - PfRoot::findBounds(*localLms, localXmin, localYmin, localXmax, localYmax); - PfRoot::findBounds(*worldLms, worldXmin, worldYmin, worldXmax, worldYmax); - const coordinate_t localMax = max(fabs(localXmin), - max(fabs(localYmin), - max(fabs(localXmax), fabs(localYmax)))); - xmin = worldXmin - localMax; - xmax = worldXmax + localMax; - ymin = worldYmin - localMax; - ymax = worldYmax + localMax; - } - xrange = xmax - xmin; - yrange = ymax - ymin; - - // create or resize particles if necessary - if ( curParticles == NULL ) { - makeParticles(); - uniformlyDistribute(); - } - if ( (int)((*curParticles)[0].addLocal.size()) != nlocal ) - resizeParticles(); -} - -void ParticleFilter::uniformlyDistribute() { - // Determine space to generate random samples - loadLms(); - for (int i = 0; i < numParticles; i++) - randomizeNewParticle(i); - vector * const oldParticles = curParticles; - curParticles = newParticles; - newParticles = oldParticles; - -} - -void ParticleFilter::randomizeNewParticle(int const i) { - Particle &part = (*newParticles)[i]; - while (1) { // loop until particle is acceptable - part.dx = float(rand())/RAND_MAX * xrange + xmin; - part.dy = float(rand())/RAND_MAX * yrange + ymin; - if ( !worldBounds.isValid() || - worldBounds->isInside(Point(part.dx,part.dy)) ) - break; - } - part.theta = float(rand())/RAND_MAX * 2 * M_PI; -} - -int ParticleFilter::localize() { - loadLms(); - if ( nlocal == 0 || nworld == 0 ) - return -1; - getInitialGuess(); - noiseFactorXY = INITIAL_XY_NOISE; - noiseFactorT = INITIAL_THETA_NOISE; - for ( int gen = 0; gen < numGenerations; gen++ ) { - resample(); - noiseFactorXY = noiseFactorXY * NOISE_REDUCTION_XY; - noiseFactorT = noiseFactorT * NOISE_REDUCTION_T; - /* - cout << "Generation " << gen << ":" << endl; - for ( int i=0; i<40; i++ ) { - Particle &part = (*curParticles)[i]; - printf(" %3d: %7.2f , %7.2f @ %6.4f = %6.4f\n", i, part.dx, part.dy, (float)part.theta, part.prob); - } - */ - } - return bestIndex; -} - -void ParticleFilter::moveBy(float const xdelta, float const ydelta, AngPi const tdelta) { - for ( int i = 0; i= minAcceptableProb ) - break; - else - uniformlyDistribute(); // no decent match, so randomize all particles and try another pass - } -} - -void ParticleFilter::computeParticleScores() { - float bestProb = -1; - bestIndex = -1; - for ( int i = 0; i bestProb ) { - bestProb = s; - bestIndex = i; - } - } - // cout << "computeParticleScores(): best particle = " << bestIndex - // << ": " << bestProb << endl; -} - -void ParticleFilter::setParticleView(int const i) { - Particle const &part = (*curParticles)[i]; - float const partDx = part.dx; - float const partDy = part.dy; - float const cosT = cos(-part.theta); - float const sinT = sin(-part.theta); - float const negSinT = -sinT; - for ( int j=0; j < nlocal; j++ ) { - PfRoot &landmark = *((*localLms)[j]); - particleViewX[j] = landmark.x * cosT + landmark.y * sinT + partDx; - particleViewY[j] = landmark.x * negSinT + landmark.y * cosT + partDy; - if ( landmark.type == lineDataType ) { - const PfLine &line = dynamic_cast(landmark); - particleViewX2[j] = line.x2 * cosT + line.y2 * sinT + partDx; - particleViewY2[j] = line.x2 * negSinT + line.y2 * cosT + partDy; - } - } -} - -void ParticleFilter::computeLocalMatch (int const i, int const j) { - float distsq = INFINITE_DISTANCE; - int worldMatch = -1; - for ( int k=0; ktype == (*worldLms)[k]->type && - (*localLms)[j]->color == (*worldLms)[k]->color ) { - float const lx = particleViewX[j]; - float const ly = particleViewY[j]; - float const wx = (*worldLms)[k]->x; - float const wy = (*worldLms)[k]->y; - float tempDistsq; - switch ( (*localLms)[j]->type ) { - case lineDataType: { - PfLine &localLine = *dynamic_cast((*localLms)[j]); - PfLine &worldLine = *dynamic_cast((*worldLms)[k]); - float tempDistsq1, tempDistsq2; - // If endpoints are valid, compare distance between endpoints. - // If not valid, measure perpendicular distance from the local endpoint - // to the world line segment, if the projection of the endpoint onto the - // segment occurs within the segment, not beyond it. Instead of calculating - // the projection we use a heuristic test: either the x or y endpoint value must - // lie within the range of the line segment. - if ( (localLine.valid1 && worldLine.valid1) || - !( lx >= min(worldLine.x,worldLine.x2) && - lx <= max(worldLine.x,worldLine.x2) || - ly >= min(worldLine.y,worldLine.y2) && - ly <= max(worldLine.y,worldLine.y2) ) ) - tempDistsq1 = (lx-wx)*(lx-wx) + (ly-wy)*(ly-wy); - else { - float const tempDist1 = distanceFromLine(lx,ly,worldLine); - tempDistsq1 = tempDist1 * tempDist1; - } - float const lx2 = particleViewX2[j]; - float const ly2 = particleViewY2[j]; - float const wx2 = worldLine.x2; - float const wy2 = worldLine.y2; - if ( (localLine.valid2 && worldLine.valid2) || - !( lx2 >= min(worldLine.x,worldLine.x2) && - lx2 <= max(worldLine.x,worldLine.x2) || - ly2 >= min(worldLine.y,worldLine.y2) && - ly2 <= max(worldLine.y,worldLine.y2) ) ) - tempDistsq2 = (lx2-wx2)*(lx2-wx2) + (ly2-wy2)*(ly2-wy2); - else { - float const tempDist2 = distanceFromLine(lx2,ly2,worldLine); - tempDistsq2 = tempDist2 * tempDist2; - } - AngPi const localOrient = localLine.orientation + (*curParticles)[i].theta; - AngPi const odiff = worldLine.orientation - localOrient; - float const odist = 500 * sin(odiff); - float const odistsq = odist * odist; - tempDistsq = tempDistsq1 + tempDistsq2 + odistsq; // plus orientation match term? - } - break; - case ellipseDataType: - case pointDataType: - case blobDataType: { - tempDistsq = (lx-wx)*(lx-wx) + (ly-wy)*(ly-wy); - break; - } - default: - std::cout << "ParticleFilter::computeMatchScore() can't match landmark type " - << (*localLms)[j]->type << std::endl; - return; - } - if ( tempDistsq < distsq ) { - distsq = tempDistsq; - worldMatch = k; - } - } - } - localMatches[j] = worldMatch; - if ( worldMatch == -1 ) { - (*curParticles)[i].addLocal[j] = true; - localScores[j] = 1.0; - } - else - localScores[j] = normpdf(distsq); -} - -float ParticleFilter::distanceFromLine(coordinate_t x0, coordinate_t y0, PfLine &wline) { - float const &x1 = wline.x; - float const &y1 = wline.y; - float const &x2 = wline.x2; - float const &y2 = wline.y2; - float const &length = wline.length; - float const result = fabs((x2-x1)*(y1-y0) - (x1-x0)*(y2-y1)) / length; - return result; -} - -void ParticleFilter::resample() { - float const normFactor = (*curParticles)[bestIndex].prob; - // cout << "resample(): normFactor = " << normFactor << endl; - int newParticleCount = 0; - (*newParticles)[newParticleCount++] = (*curParticles)[bestIndex]; - while (newParticleCount < numParticles) { - for ( int i=0; i * const oldParticles = curParticles; - curParticles = newParticles; - newParticles = oldParticles; - computeParticleScores(); -} - -void ParticleFilter::spawnInto(int const i, int const j) { - Particle &parent = (*curParticles)[i]; - Particle &spawned = (*newParticles)[j]; - - while (1) { // loop until we generate an acceptable particle - float const xRand = 2*float(rand())/RAND_MAX - 1; - float const yRand = 2*float(rand())/RAND_MAX - 1; - spawned.dx = parent.dx + xRand * noiseFactorXY; - spawned.dy = parent.dy + yRand * noiseFactorXY; - if ( !worldBounds.isValid() || - worldBounds->isInside(Point(spawned.dx, spawned.dy)) ) { - float const tRand = 2*float(rand())/RAND_MAX - 1; - spawned.theta = parent.theta + AngTwoPi(tRand * noiseFactorT); - break; - } - } -} - -void ParticleFilter::determineAdditions(int const i) { - Particle &part = (*curParticles)[i]; - for (int j = 0; j= localScores[j]) { - part.addLocal[j] = true; - localScores[j] = ADDITION_PENALTY; - localMatches[j] = -1; - } - else - for (int j2 = (j+1); j2 localScores[j]) { - part.addLocal[j] = true; - localScores[j] = ADDITION_PENALTY; - localMatches[j] = -1; - } else { - part.addLocal[j2] = true; - localScores[j2] = ADDITION_PENALTY; - localMatches[j2] = -1; - } - } -} - - /* -void ParticleFilter::determineDeletions (int const i) { - Particle &part = (*curParticles)[i]; - part.deleteWorld.assign(nworld,true); - - float minXLoc = INFINITEDISTANCE; - float minYLoc = INFINITEDISTANCE; - float maxXLoc = 0; - float maxYLoc = 0; - for (int j = 0; j maxXLoc) - maxXLoc = particleViewX[j]; - if (particleViewY[j] < minYLoc) - minYLoc = particleViewY[j]; - else if (particleViewY[j] > maxYLoc) - maxYLoc = particleViewY[j]; - } - - for (int k = 0; kx >= minXLoc && - worldLms[k]->x <= maxXLoc && - worldLms[k]->y >= minYLoc && - worldLms[k]->y <= maxYLoc ) ) - part.deleteWorld[k] == false; // don't delete world LM if it was outside local view -} - */ - -} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ParticleFilter.h ./DualCoding/ParticleFilter.h --- ../Tekkotsu_3.0/DualCoding/ParticleFilter.h 2006-10-02 17:56:29.000000000 -0400 +++ ./DualCoding/ParticleFilter.h 1969-12-31 19:00:00.000000000 -0500 @@ -1,159 +0,0 @@ -//-*-c++-*- - -#ifndef LOADED_ParticleFilter_h -#define LOADED_ParticleFilter_h - -#include -#include - -#include "Particle.h" -#include "ParticleShapes.h" -#include "ShapePolygon.h" - -using namespace std; - -namespace DualCoding { - -//! ParticleFilter localizes the robot by matching local shapes against world shapes. - -/*! Create an instance of ParticleFilter, and set its parameters by modifying member - variables such as num_particles and num_generations. Then call its localize() - method to determine the robot's location. Subsequent calls will start with the current - particle distribution unless you call uniformly_distribute() to randomize things. -*/ - -class ParticleFilter { -public: - static const int NUM_PARTICLES = 2000; - static const int NUM_GENERATIONS = 15; - static const int NUM_TRIES = 5; - static const float INITIAL_XY_NOISE = 100; - static const float INITIAL_THETA_NOISE = 30 * M_PI/180; - static const float NOISE_REDUCTION_XY = 0.85; - static const float NOISE_REDUCTION_T = 0.9; - static const float INFINITE_DISTANCE = 10000000; - static const float STDEV = 50; - static const float ADDITION_PENALTY = 0.1; - static const float PERCENT_RANDOM = 0.1; //!< Percent of random particles in each resampling - - ShapeSpace &localShS; //!< Local shape space - ShapeSpace &worldShS; //!< World shape space - int numParticles; //!< Number of particles to use - int numGenerations; //!< Maximum number of generations of resampling - int numTries; //!< Number of times to restart if no good initial guess - float noiseFactorXY; //!< Scale of noise for translation parameters x,y - float noiseFactorT; //!< Scale of noise for rotation parameter theta - Shape worldBounds; //!< If valid shape, particles must lie inside it. - int nlocal; //!< Current number of local landmarks - int nworld; //!< Current number of world landmarks - //! Bound box of world shapes - //@{ - float xmin, xmax, xrange; - float ymin, ymax, yrange; - //@} - vector *curParticles; //!< Pointer to vector holding the current set of particles - int bestIndex; //!< Index of highest scoring particle from most recent resampling. - - //private: - vector *newParticles; //!< Pointer to vector where new particles are generated by resampling - vector *localLms; //!< Pointer to current vector of local landmarks - vector *worldLms; //!< Pointer to current vector of world landmarks - vector particleViewX; //!< x coords of local landmarks according to the currently-selected particle - vector particleViewY; //!< y coords of local landmarks according to the currently-selected particle - vector particleViewX2; //!< x coords of other point of local line - vector particleViewY2; //!< y coords of other point of local line - vector localScores; //!< Match scores for local landmarks according to the currently-selected particle - vector localMatches; //!< Index of best matching world landmark for each local landmark according to the currently-selected particle - -public: - ParticleFilter(ShapeSpace &LocalShS, ShapeSpace &WorldShS) : - localShS(LocalShS), worldShS(WorldShS), - numParticles(NUM_PARTICLES), - numGenerations(NUM_GENERATIONS), - numTries(NUM_TRIES), - noiseFactorXY(INITIAL_XY_NOISE), - noiseFactorT(INITIAL_THETA_NOISE), - worldBounds(), - nlocal(0), - nworld(0), - xmin(0), xmax(0), xrange(0), - ymin(0), ymax(0), yrange(0), - curParticles(NULL), - bestIndex(-1), - newParticles(NULL), - localLms(), worldLms(), - particleViewX(), particleViewY(), - particleViewX2(), particleViewY2(), - localScores(), localMatches() - {}; - - //! Reset particle filter and restore default settings - void reinitialize(); - - //! Constrain new particles to world boundaries defined by a polygon - void setWorldBounds(const Shape &poly) { worldBounds = poly; } - - //! Invoke the particle filter: determine best match of local view to world map. Returns index of best particle, or -1 if failure. - int localize(); - - //! Uniformly distribute particles throughout the region spanned by the world landmarks - void uniformlyDistribute(); - - //! Update the current particles when the robot moves - void moveBy(float const xdelta, float const ydelta, AngPi const tdelta); - - //! Create two Particle vectors of length numParticles, stored in curParticles and newParticles. - /*! This function is called once, automatically, by localize() to initialize the Particle vectors. - It should only be called explicitly when the value of numParticles has changed. - */ - void makeParticles(); - - //private: - - //! Load the local and world landmarks from their shape spaces, and create or resize particles if necessary. - void loadLms(); - - //! Set the size of each Particle's addLocal vector to nlocal, and resize some internal vectors - void resizeParticles(); - - //! Set new Particle i to random dx, dy, and theta values. Called by uniformlyDistribute(). - void randomizeNewParticle(int const i); - - //! Check particle scores, and randomize and repeat if no particle is close to a solution - void getInitialGuess(); - - //! Calculate the score for each Particle p, leaving it in p.prob - void computeParticleScores(); - - //! Set up particleView vectors based on the parameters of the i-th Particle - void setParticleView(int const i); - - //! Match each local landmark against the world landmarks - void computeLocalMatch(int const i, int const j); - - static float distanceFromLine(coordinate_t x, coordinate_t y, PfLine &wline); - - //! Generate newParticles from curParticles, then swap the two vectors and compute scores. - void resample(); - - void spawnInto(int const i, int const j); - - void determineAdditions(int const i); - - // void determineDeletions(int const i); - -public: - static inline float normpdf(float const distsq) { return exp(-distsq/(STDEV*STDEV)); } - -private: - ParticleFilter& operator=(const ParticleFilter&); //!< don't call this - ParticleFilter(const ParticleFilter&); //!< don't call this - -}; - - - -} // namespace - -#endif - diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ParticleShapes.cc ./DualCoding/ParticleShapes.cc --- ../Tekkotsu_3.0/DualCoding/ParticleShapes.cc 2006-10-02 17:54:56.000000000 -0400 +++ ./DualCoding/ParticleShapes.cc 2007-11-11 02:57:26.000000000 -0500 @@ -16,73 +16,72 @@ namespace DualCoding { -vector* PfRoot::loadLms(const vector &lms, bool isWorld){ +void PfRoot::loadLms(const std::vector &lms, bool isWorld, std::vector& landmarks){ int id; int type; rgb color; - vector *landmarks = new vector(2*lms.size(),(PfRoot*)NULL); - landmarks->clear(); + bool mobile; + deleteLms(landmarks); + landmarks.reserve(lms.size()); for (unsigned int i = 0; igetType(); color = lms[i]->getColor(); + mobile = lms[i]->getMobile(); if (type == lineDataType) { const Shape &line = ShapeRootTypeConst(lms[i],LineData); id = line->getId(); const EndPoint &pt1 = line->end1Pt(); const EndPoint &pt2 = line->end2Pt(); - PfLine *land = new PfLine(id, color, pt1.coordX(), pt1.coordY(), + PfLine *land = new PfLine(id, color, mobile, pt1.coordX(), pt1.coordY(), pt2.coordX(), pt2.coordY(), pt1.isValid(), pt2.isValid()); land->link = &lms[i]; land->orientation = atan2(pt2.coordY()-pt1.coordY(), pt2.coordX()-pt1.coordX()); land->length = sqrt((pt2.coordX()-pt1.coordX())*(pt2.coordX()-pt1.coordX()) + (pt2.coordY()-pt1.coordY())*(pt2.coordY()-pt1.coordY())); - landmarks->push_back(land); + landmarks.push_back(land); if ( isWorld ) { - PfLine *land2 = new PfLine(id, color, pt2.coordX(), pt2.coordY(), - pt1.coordX(), pt1.coordY(), pt2.isValid(), pt1.isValid()); + PfLine *land2 = new PfLine(id, color, mobile, pt2.coordX(), pt2.coordY(), + pt1.coordX(), pt1.coordY(), pt2.isValid(), pt1.isValid()); land2->link = &lms[i]; land2->orientation = land->orientation; land2->length = land->length; - landmarks->push_back(land2); + landmarks.push_back(land2); } } else if (type == ellipseDataType) { const Shape &ellipse = ShapeRootTypeConst(lms[i],EllipseData); id = ellipse->getId(); const Point &pt = ellipse->getCentroid(); - PfEllipse* land = new PfEllipse(id, color, pt.coordX(), pt.coordY()); + PfEllipse* land = new PfEllipse(id, color, mobile, pt.coordX(), pt.coordY()); land->link = &lms[i]; - landmarks->push_back(land); + landmarks.push_back(land); } else if (type == pointDataType) { const Shape &point = ShapeRootTypeConst(lms[i],PointData); id = point->getId(); const Point &pt = point->getCentroid(); - PfPoint* land = new PfPoint(id, color, pt.coordX(), pt.coordY()); + PfPoint* land = new PfPoint(id, color, mobile, pt.coordX(), pt.coordY()); land->link = &lms[i]; - landmarks->push_back(land); + landmarks.push_back(land); } else if (type == blobDataType) { const Shape &blob = ShapeRootTypeConst(lms[i],BlobData); id = blob->getId(); Point pt = blob->getCentroid(); - PfBlob* land = new PfBlob(id, color, pt.coordX(), pt.coordY()); + PfBlob* land = new PfBlob(id, color, mobile, pt.coordX(), pt.coordY()); land->link = &lms[i]; - landmarks->push_back(land); + landmarks.push_back(land); } } - return landmarks; } -void PfRoot::deleteLms(vector *vec) { - if ( vec != NULL ) { - for ( unsigned int i = 0; i < vec->size(); i++ ) - delete (*vec)[i]; - delete vec; - } +void PfRoot::deleteLms(std::vector& vec) { + for ( unsigned int i = 0; i < vec.size(); i++ ) + delete vec[i]; + vec.clear(); } -void PfRoot::findBounds(const vector &landmarks, +void PfRoot::findBounds(const std::vector &landmarks, coordinate_t &xmin, coordinate_t &ymin, coordinate_t &xmax, coordinate_t &ymax) { if ( landmarks.size() == 0 ) { // should never get here @@ -103,23 +102,24 @@ } } -void PfRoot::printLms(const vector &landmarks) { +void PfRoot::printLms(const std::vector &landmarks) { for (unsigned int i = 0; i* loadLms(const vector &lms, bool isWorld); + static void loadLms(const std::vector &lms, bool isWorld, std::vector& landmarks); - static void deleteLms(vector *vec); + static void deleteLms(std::vector& vec); - static void findBounds(const vector &map, + static void findBounds(const std::vector &map, coordinate_t &xmin, coordinate_t &ymin, coordinate_t &xmax, coordinate_t &ymax); - static void printLms(const vector &lmvec); + static void printLms(const std::vector &lmvec); private: PfRoot(const PfRoot&); //!< don't call this @@ -53,42 +54,42 @@ AngPi orientation; float length; - PfLine(int _id, rgb _color, coordinate_t _x, coordinate_t _y, + PfLine(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y, coordinate_t _x2, coordinate_t _y2, bool _v1, bool _v2) : - PfRoot(lineDataType, _id, _color, _x, _y), + PfRoot(lineDataType, _id, _color, _mobile, _x, _y), x2(_x2), y2(_y2), valid1(_v1), valid2(_v2), orientation(0), length(0) {} - virtual void print(ostream &os) const; + virtual void print(std::ostream &os) const; }; //! An ellipse landmark class PfEllipse : public PfRoot { public: - PfEllipse(int _id, rgb _color, coordinate_t _x, coordinate_t _y) : - PfRoot(ellipseDataType, _id, _color, _x, _y) {} + PfEllipse(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) : + PfRoot(ellipseDataType, _id, _color, _mobile, _x, _y) {} - virtual void print(ostream &os) const; + virtual void print(std::ostream &os) const; }; //! A point landmark class PfPoint : public PfRoot { public: - PfPoint(int _id, rgb _color, coordinate_t _x, coordinate_t _y) : - PfRoot(pointDataType, _id, _color, _x, _y) {} + PfPoint(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) : + PfRoot(pointDataType, _id, _color, _mobile, _x, _y) {} - virtual void print(ostream &os) const; + virtual void print(std::ostream &os) const; }; //! A blob landmark class PfBlob : public PfRoot { public: - PfBlob(int _id, rgb _color, coordinate_t _x, coordinate_t _y) : - PfRoot(blobDataType, _id, _color, _x, _y) {} + PfBlob(int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) : + PfRoot(blobDataType, _id, _color, _mobile, _x, _y) {} - virtual void print(ostream &os) const; + virtual void print(std::ostream &os) const; }; -ostream& operator<<(ostream &os, const PfRoot &x); +std::ostream& operator<<(std::ostream &os, const PfRoot &x); } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PathPlanner.cc ./DualCoding/PathPlanner.cc --- ../Tekkotsu_3.0/DualCoding/PathPlanner.cc 2006-05-19 14:01:11.000000000 -0400 +++ ./DualCoding/PathPlanner.cc 2007-11-13 21:31:27.000000000 -0500 @@ -290,7 +290,7 @@ } } -PathPlanner::state* PathPlanner::thereIs(unsigned int pos, direction dir, pair lms) { +PathPlanner::state* PathPlanner::thereIs(unsigned int pos, PathPlanner::direction dir, std::pair lms) { // cout << "thereIs: " << pos << ',' << dir << ',' << (pos+dir) << endl; const vector& states = unreached[pos*4 + (unsigned int) dir]; for (vector::const_iterator it = states.begin(); @@ -301,7 +301,7 @@ } -vector > PathPlanner::findLMs(location loc) { +std::vector > PathPlanner::findLMs(location loc) { vector lms; lms.push_back(-1); // no landmark is also an option for (map::const_iterator it = landmarks.begin(); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PathPlanner.h ./DualCoding/PathPlanner.h --- ../Tekkotsu_3.0/DualCoding/PathPlanner.h 2006-05-19 14:01:12.000000000 -0400 +++ ./DualCoding/PathPlanner.h 2007-11-12 13:00:41.000000000 -0500 @@ -24,7 +24,7 @@ //{ data structures used to represent the map and path struct direction { - bitset<2> bitVal; // 00=N, 01=W, 10=S, 11=E + std::bitset<2> bitVal; // 00=N, 01=W, 10=S, 11=E direction (unsigned int i) : bitVal(i) {} operator unsigned int() const { return (unsigned int) bitVal.to_ulong(); } enum directions { N=0,W=1,S=2,E=3 };// dir; @@ -45,11 +45,11 @@ struct state { // structure representing each node location loc; unsigned int cost; - pair lms; + std::pair lms; state* dst; // optimal transition to be found state(location _loc, int lm1, int lm2) : loc(_loc), cost(0), lms(lm1, lm2), dst(NULL) {} //, links() {} - state(location _loc, pair _lms) + state(location _loc, std::pair _lms) : loc(_loc), cost(0), lms(_lms), dst(NULL) {} //, links() {} state(const state& s) : loc(s.loc), cost(s.cost), lms(s.lms), dst(&(*s.dst)) {} //, links(s.links) {} @@ -67,11 +67,11 @@ //} protected: - queue allStates; // all possible states - vector *unreached; // collection of states for which optimal action is not determined yet + std::queue allStates; // all possible states + std::vector *unreached; // collection of states for which optimal action is not determined yet // priority queue containing edges evaluated so far in order of increasing cost, core of this algorithm struct lessCost { bool operator()(const edge& e1, const edge& e2) const { return e1.cost > e2.cost; }}; - priority_queue,lessCost> reached; + std::priority_queue,lessCost> reached; static const int size=300; // length of dog unsigned int numX, numY; float minX, minY, dX, dY; @@ -79,27 +79,27 @@ public: unsigned int maxDistance; enum Cost { transF, transB, transY, tranB, rotate, noLM, oneLM }; - map costs; // all costs must be positive for this algorithm to work + std::map costs; // all costs must be positive for this algorithm to work Point startPt, goalPt; AngTwoPi startOrientation, goalOrientation; protected: unsigned int *costMap; // measure of how close you are to obstacles // maps b/w shape id and location/color info - map landmarks; + std::map landmarks; // maps b/w shape ids and their score(distinguishability from other lms) - map lmCosts; - vector > obstacles; // lmCosts; + std::vector > obstacles; // + landmarks.insert(std::make_pair (lm->getId(),PointData(VRmixin::worldShS,Point(lm->getCentroid())))); } void addLandmarkAsObstacle(const ShapeRoot& lm, unsigned int cost) { // adds landmark also as obstacle addLandmark(lm); - obstacles.push_back(pair(lm->getCentroid(),cost)); + obstacles.push_back(std::pair(lm->getCentroid(),cost)); } protected: @@ -107,8 +107,8 @@ void initialize(); // defines all possible states (vertices) void fillState(unsigned int low, unsigned int high); void findLinks(state& s); // find all possible links for given state and store them inside the state - vector > findLMs(location loc); - state* thereIs(unsigned int pos, direction dir, pair lms); + std::vector > findLMs(location loc); + state* thereIs(unsigned int pos, direction dir, std::pair lms); void computeLandmarkCosts(); Point findWorldCoords(unsigned int pos); std::string toString(const PathPlanner::state &s); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Pilot.cc ./DualCoding/Pilot.cc --- ../Tekkotsu_3.0/DualCoding/Pilot.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/Pilot.cc 2007-11-11 18:57:21.000000000 -0500 @@ -0,0 +1,971 @@ +#include "Behaviors/Transitions/CompletionTrans.h" +#include "Behaviors/Transitions/EventTrans.h" +#include "Behaviors/Transitions/TimeOutTrans.h" +#include "Events/EventRouter.h" +#include "Events/LocomotionEvent.h" + +#include "MapBuilder.h" +#include "Lookout.h" +#include "VRmixin.h" + +#include "ShapeTarget.h" + +#include "Pilot.h" + +using namespace std; + +namespace DualCoding { + +Pilot::Pilot() : + StateNode("Pilot"), requests(), curReq(NULL), idCounter(0), + waypointwalk_id(MotionManager::invalid_MC_ID), posture_id(MotionManager::invalid_MC_ID), + lastDisplayParticleTime(0), + dispatchNode(NULL) +{ + setRetain(false); // don't want VRmixin-based subnodes to persist when Pilot is stopped +} + + +void Pilot::DoStart() { + StateNode::DoStart(); + SharedObject waypointwalk_mc; + waypointwalk_id = motman->addPersistentMotion(waypointwalk_mc,MotionManager::kIgnoredPriority); + SharedObject posture_mc; + posture_id = motman->addPersistentMotion(posture_mc,MotionManager::kIgnoredPriority); + if ( verbosity & PVstart ) + cout << "Pilot starting up: waypointwalk_id=" << waypointwalk_id + << ", posture_id=" << posture_id << endl; +} + +void Pilot::DoStop() { + if ( verbosity & PVstart ) + cout << "Pilot is shutting down." << endl; + abort(); + motman->removeMotion(waypointwalk_id); + waypointwalk_id = MotionManager::invalid_MC_ID; + motman->removeMotion(posture_id); + posture_id = MotionManager::invalid_MC_ID; + StateNode::DoStop(); +} + +void Pilot::abort() { + if ( dispatchNode ) + dispatchNode->DoStop(); + curReq = NULL; + while (!requests.empty()) { + delete requests.front(); + requests.pop(); + } + motman->setPriority(waypointwalk_id,MotionManager::kIgnoredPriority); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); +} + +void Pilot::setup() { + StateNode::setup(); + dispatchNode = new Dispatch; + addNode(dispatchNode); +} + +unsigned int Pilot::executeRequest(const PilotRequest &req) { + requests.push(new PilotRequest(req)); + const unsigned int id = ++idCounter; + requests.back()->requestID = id; + executeRequest(); + return id; +} + +void Pilot::executeRequest() { + // check carefully because event from prior request completion could + // have caused user code to already queue and start another request + if ( curReq == NULL & !requests.empty() ) { + curReq = requests.front(); + if ( verbosity & PVexecute ) + cout << "Pilot executing request " << curReq->requestID << endl; + dispatchNode->DoStart(); + } +} + +void Pilot::requestComplete(const bool result) { + if ( curReq == NULL ) { + cout << "Pilot::requestComplete had NULL curReq !!!!!!!!!!!!!!!!" << endl; + return; + } + if ( curReq->trackRequest != NULL ) + VRmixin::lookout.stopTrack(); + const unsigned int reqID = curReq->requestID; + delete curReq; + curReq = NULL; + requests.pop(); + motman->setPriority(waypointwalk_id,MotionManager::kIgnoredPriority); + motman->setPriority(posture_id,MotionManager::kIgnoredPriority); + if ( verbosity & PVcomplete ) + cout << "Pilot request " << reqID << " complete." << endl; + erouter->postEvent(EventBase(EventBase::pilotEGID, reqID, EventBase::deactivateETID,0, "Pilot Completion",float(result))); + executeRequest(); +} + +//================ Dispatch + +void Pilot::Dispatch::setup() { + VisualRoutinesStateNode::setup(); + successNode = new Success; + addNode(successNode); + failureNode = new Failure; + addNode(failureNode); + + //================ Walk + + walkNode = new Walk; + addNode(walkNode); + walkNode->setMC(pilot.waypointwalk_id); + walkNode->addTransition(new CompletionTrans(successNode)); + + //================ Visual Search + + visualsearchNode = new VisualSearch; + addNode(visualsearchNode); + VisualSearchHaveMap *visualsearchhavemapNode = new VisualSearchHaveMap; + addNode(visualsearchhavemapNode); + VisualSearchWalk *visualsearchwalkNode = new VisualSearchWalk; + visualsearchwalkNode->setMC(pilot.waypointwalk_id); + addNode(visualsearchwalkNode); + + visualsearchNode->addTransition(new EventTrans(visualsearchhavemapNode, EventBase::mapbuilderEGID, + &(visualsearchNode->mapbuilder_id), EventBase::deactivateETID)); + visualsearchhavemapNode->addTransition(new CompletionTrans(visualsearchwalkNode)); + visualsearchwalkNode->addTransition(new CompletionTrans(visualsearchNode)); + + //================ GotoShape + + gotoshapeNode = new GotoShape; + gotoshapeNode->setMC(pilot.waypointwalk_id); + addNode(gotoshapeNode); + gotoshapeNode->addTransition(new CompletionTrans(successNode)); + + //================ GotoTarget + + gotoTargetNode = new GotoTarget; + gotoTargetNode->setMC(pilot.waypointwalk_id); + addNode(gotoTargetNode); + + CreepToShapeStand *gotoTargetStandNode = new CreepToShapeStand; + gotoTargetStandNode->setMC(pilot.posture_id); + addNode(gotoTargetStandNode); + + CreepToShapeWait *gotoTargetWaitNode = new CreepToShapeWait; + addNode(gotoTargetWaitNode); + + CreepToShapeBuildMap *gotoTargetBuildMapNode = new CreepToShapeBuildMap; + addNode(gotoTargetBuildMapNode); + + gotoTargetNode->buildTargetNode = new BuildTarget; + addNode(gotoTargetNode->buildTargetNode); + + gotoTargetNode->addTransition(new CompletionTrans(gotoTargetStandNode)); + gotoTargetStandNode->addTransition(new CompletionTrans(gotoTargetWaitNode)); + gotoTargetWaitNode->addTransition(new TimeOutTrans(gotoTargetBuildMapNode,2000)); + gotoTargetBuildMapNode->addTransition(new EventTrans(gotoTargetNode->buildTargetNode, + EventBase::mapbuilderEGID, + &CreepToShapeBuildMap::mapreq_id, + EventBase::deactivateETID)); + gotoTargetNode->buildTargetNode->addTransition(new CompletionTrans(gotoTargetNode)); + + //================ PushTarget + + pushTargetNode = new PushTarget; + pushTargetNode->setMC(pilot.waypointwalk_id); + addNode(pushTargetNode); + + CreepToShapeStand *pushTargetStandNode = new CreepToShapeStand; + pushTargetStandNode->setMC(pilot.posture_id); + addNode(pushTargetStandNode); + + CreepToShapeWait *pushTargetWaitNode = new CreepToShapeWait; + addNode(pushTargetWaitNode); + + CreepToShapeBuildMap *pushTargetBuildMapNode = new CreepToShapeBuildMap; + addNode(pushTargetBuildMapNode); + + pushTargetNode->buildTargetNode = new BuildTarget; + addNode(pushTargetNode->buildTargetNode); + + pushTargetNode->addTransition(new CompletionTrans(pushTargetStandNode)); + pushTargetStandNode->addTransition(new CompletionTrans(pushTargetWaitNode)); + pushTargetWaitNode->addTransition(new TimeOutTrans(pushTargetBuildMapNode,2000)); + pushTargetBuildMapNode->addTransition(new EventTrans(pushTargetNode->buildTargetNode, + EventBase::mapbuilderEGID, + &CreepToShapeBuildMap::mapreq_id, + EventBase::deactivateETID)); + pushTargetNode->buildTargetNode->addTransition(new CompletionTrans(pushTargetNode)); + + //================ CreepToShape + + creeptoshapeNode = new CreepToShape; + creeptoshapeNode->setMC(pilot.waypointwalk_id); + addNode(creeptoshapeNode); + + CreepToShapeStand *creeptoshapestandNode = new CreepToShapeStand; + creeptoshapestandNode->setMC(pilot.posture_id); + addNode(creeptoshapestandNode); + + CreepToShapeWait *creeptoshapewaitNode = new CreepToShapeWait; + addNode(creeptoshapewaitNode); + + CreepToShapeBuildMap *creeptoshapebuildmapNode = new CreepToShapeBuildMap; + addNode(creeptoshapebuildmapNode); + + CreepToShapeLocalize *creeptoshapelocalizeNode = new CreepToShapeLocalize; + addNode(creeptoshapelocalizeNode); + + creeptoshapeNode->addTransition(new CompletionTrans(creeptoshapestandNode)); + creeptoshapestandNode->addTransition(new CompletionTrans(creeptoshapewaitNode)); + creeptoshapewaitNode->addTransition(new TimeOutTrans(creeptoshapebuildmapNode,500)); + creeptoshapebuildmapNode->addTransition(new EventTrans(creeptoshapelocalizeNode, + EventBase::mapbuilderEGID, + &CreepToShapeBuildMap::mapreq_id, + EventBase::deactivateETID)); + creeptoshapelocalizeNode->addTransition(new CompletionTrans(creeptoshapeNode)); + + //================ IRCliff and IRObstacle +#ifdef TGT_HAS_IR_DISTANCE +#ifdef TGT_ERS7 + ircliffNode = new IRCliff; + addNode(ircliffNode); +#endif //TGT_ERS7 + irobstacleNode = new IRObstacle; + addNode(irobstacleNode); +#endif // TGT_HAS_IR_DISTANCE + + //================ Localize + + localizeNode = new Localize; + addNode(localizeNode); + +} + +void Pilot::Dispatch::DoStart() { + VisualRoutinesStateNode::DoStart(); +#ifdef TGT_HAS_IR_DISTANCE +#ifdef TGT_ERS7 + if ( pilot.curReq->avoidCliffs ) + ircliffNode->DoStart(); +#endif // TGT_ERS7 + if ( pilot.curReq->avoidObstacles ) + irobstacleNode->DoStart(); +#endif // TGT_HAS_IR_DISTANCE + if ( pilot.curReq->trackRequest ) + if ( lookout.busy() ) + cout << "Error: Pilot cannot launch track request because the Lookout is busy!" << endl; + else + lookout.executeRequest(*pilot.curReq->trackRequest); + if ( pilot.curReq->localizationInterval > 0 ) + localizeNode->DoStart(); + else if ( pilot.curReq->localizationDisplayInterval > 0 ) + cout << "Pilot warning: localizationDisplayInterval > 0 but no localization requested." << endl; + switch ( pilot.curReq->getRequestType() ) { + case PilotRequest::walk: + walkNode->DoStart(); + break; + case PilotRequest::visualSearch: + visualsearchNode->DoStart(); + break; + case PilotRequest::gotoShape: + gotoshapeNode->DoStart(); + break; + case PilotRequest::gotoTarget: + gotoTargetNode->DoStart(); + break; + case PilotRequest::pushTarget: + pushTargetNode->DoStart(); + break; + case PilotRequest::creepToShape: + if ( pilot.curReq->mapBuilderRequest == NULL || + pilot.curReq->mapBuilderRequest->worldTargets.size() == 0 || + pilot.curReq->trackRequest != NULL ) { + cout << "Pilot error: creeptoShape requires mapBuilderRequest with a worldTarget, and no trackRequest" << endl; + VRmixin::pilot.failure(); + } + else + creeptoshapeNode->DoStart(); + break; + default: + cout << "Pilot request type " << pilot.curReq->getRequestType() << " not yet implemented." << endl; + VRmixin::pilot.failure(); + } +} + +//================ Success and Failure + +void Pilot::Success::DoStart() { + StateNode::DoStart(); + if ( Pilot::getVerbosity() & Pilot::PVsuccess ) + cout << "Pilot result: Success" << endl; + VRmixin::pilot.dispatchNode->DoStop(); + VRmixin::pilot.requestComplete(true); +} + +void Pilot::Failure::DoStart() { + StateNode::DoStart(); + if ( Pilot::getVerbosity() & Pilot::PVfailure ) + cout << "Pilot result: Failure" << endl; + VRmixin::pilot.dispatchNode->DoStop(); + VRmixin::pilot.requestComplete(false); +} + +//================ Walk + +void Pilot::Walk::DoStart() { + WaypointWalkNode::DoStart(); + PilotRequest &req = *VRmixin::pilot.curReq; + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(req.dx/1000, req.dy/1000, req.da, true, 0.1); + getMC()->go(); +} + +//================ VisualSearch + +void Pilot::VisualSearch::DoStart() { + VisualRoutinesStateNode::DoStart(); + if ( pilot.curReq->mapBuilderRequest == NULL ) { + cout << "Pilot received visualSearch request with invalid mapBuilderRequest field" << endl; + pilot.failure(); + } + else if ( pilot.curReq->exitTest == NULL && pilot.curReq->searchRotationAngle != 0 ) { + cout << "Pilot received visualSearch request with no exitTest and nonzero searchRotationAngle" << endl; + pilot.failure(); + } + else + mapbuilder_id = VRmixin::mapBuilder.executeRequest(*pilot.curReq->mapBuilderRequest); +} + +void Pilot::VisualSearchHaveMap::DoStart() { + VisualRoutinesStateNode::DoStart(); + if ( (*pilot.curReq->exitTest)() ) + pilot.success(); + else if ( pilot.curReq->searchRotationAngle == 0 ) + pilot.failure(); + else + postCompletionEvent(); // go to VisualSearchWalk to turn body +} + +void Pilot::VisualSearchWalk::DoStart() { + WaypointWalkNode::DoStart(); + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(0,0,VRmixin::pilot.curReq->searchRotationAngle,true,0); + getMC()->go(); +} + +//================ GotoShape + +void Pilot::GotoShape::DoStart() { + WaypointWalkNode::DoStart(); + const ShapeRoot &target = VRmixin::pilot.curReq->targetShape; + Point const targetLoc(target->getCentroid()); + getMC()->getWaypointList().clear(); + switch ( target->getRefFrameType() ) { + case unspecified: + case camcentric: + cout << "Pilot: GotoShape target " << target << " has suspect reference frame type; assuming egocentric." << endl; + // fall through to next case + case egocentric: { + AngSignPi bearing = atan2(targetLoc.coordY(),targetLoc.coordX()); + float const distance = targetLoc.distanceFrom(Point(0,0)); + cout << "Pilot egocentric gotoShape: rotate by " << float(bearing)*180/M_PI << " deg., then forward " + << distance << " mm" << endl; + getMC()->addEgocentricWaypoint(0,0,bearing,true,0); + getMC()->addEgocentricWaypoint(distance/1000,0,0,true,0.1); // convert distance from mm to meters + break; + } + case allocentric: + cout << "Pilot alloocentric gotoShape: " << targetLoc + << " current position: " << VRmixin::theAgent->getCentroid() << endl; + getMC()->addAbsoluteWaypoint(targetLoc.coordX()/1000, targetLoc.coordY()/1000, 0, true, 0.1); + } + getMC()->go(); +} + +//================ GotoTarget + +// Assumes the target has been set in the Pilot request +void Pilot::GotoTarget::DoStart() { + WaypointWalkNode::DoStart(); + + // Set the parameters for building the target + bool buildFrontLeft = true, buildFrontRight = true, buildBackLeft = true, buildBackRight = true, lookAtCentroid = true; + int maxRetries = 10; + if (VRmixin::pilot.curReq->buildTargetParamsFn != NULL) { + (*VRmixin::pilot.curReq->buildTargetParamsFn)(&buildFrontLeft, &buildFrontRight, &buildBackLeft, &buildBackRight, &lookAtCentroid, &maxRetries); + } + if (buildTargetNode != NULL) + buildTargetNode->setParams(buildFrontLeft, buildFrontRight, buildBackLeft, buildBackRight, lookAtCentroid, maxRetries); + + Point waypoint; + AngSignPi angle; + int result = getNextWaypoint( &waypoint, &angle ); + if (result < 0) { + VRmixin::pilot.failure(); + return; + } + else if (result > 0) { + VRmixin::pilot.success(); + return; + } + + if ( waypoint != Point(0, 0, 0) ) { + if (abs(angle) <= M_PI / 6) { + //cout << "Going to (" << waypoint.coordX() << ", " << waypoint.coordY() << ", " << waypoint.coordZ() << ") and turning " << (float)angle / M_PI * 180.0f << " degrees." << endl; + float currentAngle = getMC()->getCurA() + angle; + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(waypoint.coordX() / 1000, waypoint.coordY() / 1000, (float)currentAngle, false, 0.1f); + getMC()->go(); + } + else { + // Turning angle too large, only turning in place + angle = (angle >= 0) ? M_PI / 6 : -M_PI / 6; + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(0, 0, (float)angle, true, 0.1f); + getMC()->go(); + } + } + else { + //cout << "At destination, only turning " << (float)angle / M_PI * 180.0f << " degrees." << endl; + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(0, 0, (float)angle, true, 0.1f); + getMC()->go(); + } + +} + +/** Calculates the next waypoint and angle to turn in local coordinates. + * \return 0 on success (got a new waypoint), 1 on success (arrived at destination), -1 on failure + */ +int Pilot::GotoTarget::getNextWaypoint(Point *point, AngSignPi *angle) { + const Shape& target = ShapeRootTypeConst( VRmixin::pilot.curReq->targetShape, TargetData ); + if (!target.isValid()) { + return -1; + } + if (target->getRefFrameType() != egocentric) { + return -1; + } + + bool pointOK = true; + bool angleOK = false; + + const float orientation = target->getOrientation(); + + // These points are relative to the target (in local coordinates) i.e. offset from target's centroid but not orientation + Point desiredPoint( VRmixin::pilot.curReq->positionRelativeToTarget.coordX() * cos(orientation) - VRmixin::pilot.curReq->positionRelativeToTarget.coordY() * sin(orientation), + VRmixin::pilot.curReq->positionRelativeToTarget.coordX() * sin(orientation) + VRmixin::pilot.curReq->positionRelativeToTarget.coordY() * cos(orientation), + VRmixin::pilot.curReq->positionRelativeToTarget.coordZ() ); + Point presentPoint = target->getCentroid() * -1; + + // If we're within 100mm of the desired point, only need to check angle + *point = Point(0, 0, 0); + if (presentPoint.distanceFrom(desiredPoint) > 100) { + pointOK = false; + + // Calculate present and desired angle around target + AngSignPi desiredAngle = atan2(desiredPoint.coordY(), desiredPoint.coordX()); + AngSignPi presentAngle = atan2(presentPoint.coordY(), presentPoint.coordX()); + + // Go to the desired point if present angle is close to desired angle + if (abs((double)(presentAngle - desiredAngle)) <= VRmixin::pilot.curReq->approachAngle) { + *point = desiredPoint + target->getCentroid(); + } + // Go to the next safe point + else { + // decide whether to go clockwise or anti-clockwise + AngSignPi diff = desiredAngle - presentAngle; + if (abs((double)diff) < VRmixin::pilot.curReq->subtendAngle) { + presentAngle = desiredAngle; + } + else if ((double)diff >= 0) { + presentAngle += VRmixin::pilot.curReq->subtendAngle; + } + else { + presentAngle -= VRmixin::pilot.curReq->subtendAngle; + } + *point = getPointAtAngle(presentAngle); + } + + // Cap distance to a maximum of 200mm + *point = Point( point->coordX(), point->coordY(), 0 ); + float distance = point->distanceFrom( Point( 0, 0, 0) ); + float scaleFactor = distance < 200 ? 1.0 : 200 / distance; + *point = *point * scaleFactor; + } + + Point delta = target->getCentroid() - *point; + *angle = atan2(delta.coordY(), delta.coordX()); + + // If the angle is within 15 degrees and no translation is needed, we're done + if (pointOK && (abs( (float)*angle / M_PI * 180.0f ) <= 15)) { + *angle = 0; + angleOK = true; + } + + return ( pointOK && angleOK ) ? 1 : 0; +} + +/** Returns a point in local coordinates corresponding to an angle around the target at + * the distance given in the pilot request. + */ +Point Pilot::GotoTarget::getPointAtAngle(AngSignPi angle) { + Point point(VRmixin::pilot.curReq->safeDistanceAroundTarget * cos(angle), + VRmixin::pilot.curReq->safeDistanceAroundTarget * sin(angle), + VRmixin::pilot.curReq->positionRelativeToTarget.coordZ()); + point += VRmixin::pilot.curReq->targetShape->getCentroid(); + return point; +} + +//================ PushTarget + +void Pilot::PushTarget::DoStart() { + WaypointWalkNode::DoStart(); + + // Set the parameters for building the target + bool buildFrontLeft = true, buildFrontRight = true, buildBackLeft = true, buildBackRight = true, lookAtCentroid = true; + int maxRetries = 10; + if (VRmixin::pilot.curReq->buildTargetParamsFn != NULL) { + (*VRmixin::pilot.curReq->buildTargetParamsFn)(&buildFrontLeft, &buildFrontRight, &buildBackLeft, &buildBackRight, &lookAtCentroid, &maxRetries); + } + if (buildTargetNode != NULL) + buildTargetNode->setParams(buildFrontLeft, buildFrontRight, buildBackLeft, buildBackRight, lookAtCentroid, maxRetries); + + const Shape& target = ShapeRootTypeConst( VRmixin::pilot.curReq->targetShape, TargetData ); + + double orientation = target->getOrientation(); + // This point is in local coordinates + Point desiredPoint = Point( VRmixin::pilot.curReq->positionRelativeToTarget.coordX() * cos(orientation) - VRmixin::pilot.curReq->positionRelativeToTarget.coordY() * sin(orientation), + VRmixin::pilot.curReq->positionRelativeToTarget.coordX() * sin(orientation) + VRmixin::pilot.curReq->positionRelativeToTarget.coordY() * cos(orientation), + VRmixin::pilot.curReq->positionRelativeToTarget.coordZ() ) + + target->getCentroid(); + + // Create push line + AngSignPi pushAngle = (double)VRmixin::pilot.curReq->angleToPushTarget + orientation; + LineData pushLine(VRmixin::localShS, desiredPoint, pushAngle); + + // Get present position relative to target + Point origin(0, 0, 0); + double totalDisplacement = 200.0; + double xDisplacement = 200.0; + double yDisplacement = pushLine.perpendicularDistanceFrom(origin); + // figure out which side of the line the dog is on and change direction if needed + Point leftPoint(pushLine.getCentroid().coordX(), pushLine.getCentroid().coordY() + 100, pushLine.getCentroid().coordZ()); + if (pushLine.pointsOnSameSide( leftPoint, origin )) { + yDisplacement = -yDisplacement; + } + + float scaleFactor = abs(yDisplacement) < totalDisplacement ? 1.0 : totalDisplacement / yDisplacement; + yDisplacement = yDisplacement * scaleFactor; + totalDisplacement -= abs(yDisplacement); + if (totalDisplacement <= 0) { + xDisplacement = 0; + } + else { + scaleFactor = xDisplacement < totalDisplacement ? 1.0 : totalDisplacement / xDisplacement; + xDisplacement = xDisplacement * scaleFactor; + } + + if (abs((float)pushAngle) <= M_PI / 6) { + //cout << "PushTarget: turning by " << (float)pushAngle / M_PI * 180.0f << " deg, y by " << yDisplacement << " mm, x by " << xDisplacement << " mm." << endl; + + float currentAngle = getMC()->getCurA() + pushAngle; + + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(0, 0, (float)pushAngle, true, 0.1f); + if (abs(yDisplacement) > 10) { + getMC()->addEgocentricWaypoint(0, yDisplacement / 1000, currentAngle, false, 0.1f); + } + if (abs(xDisplacement) > 10) { + getMC()->addEgocentricWaypoint(xDisplacement / 1000, 0, currentAngle, false, 0.1f); + } + getMC()->go(); + } + else { + // Turn angle too large, only turning in place + pushAngle = (pushAngle >= 0) ? M_PI / 6 : -M_PI / 6; + getMC()->getWaypointList().clear(); + getMC()->addEgocentricWaypoint(0, 0, (float)pushAngle, true, 0.1f); + getMC()->go(); + } +} + +//================ BuildTarget +void Pilot::BuildTarget::DoStart() { + VisualRoutinesStateNode::DoStart(); + + std::cout << "BuildTarget: DoStart" << std::endl; + + erouter->addListener(this, EventBase::mapbuilderEGID); + + triesLeft = maxRetries; + generateMapBuilderRequest(); +} + +void Pilot::BuildTarget::DoStop() { + std::cout << "BuildTarget: DoStop" << std::endl; + + myState = none; + VisualRoutinesStateNode::DoStop(); +} + +void Pilot::BuildTarget::processEvent(const EventBase& event) { + switch ( event.getGeneratorID() ) { + + case EventBase::mapbuilderEGID: { + if ((myState == build) && (event.getTypeID() == EventBase::deactivateETID)) { + GET_SHAPE(target, TargetData, localShS); + if (target.isValid()) { + target->printParams(); + } + + generateMapBuilderRequest(); + } + + break; + }; + default: + std::cout << "BuildTarget: Unexpected event: " << event.getDescription() << std::endl; + } +} + +void Pilot::BuildTarget::setParams(bool _buildFrontLeft, bool _buildFrontRight, bool _buildBackLeft, bool _buildBackRight, bool _lookAtCentroid, int _maxRetries) { + buildFrontLeft = _buildFrontLeft; + buildFrontRight = _buildFrontRight; + buildBackLeft = _buildBackLeft; + buildBackRight = _buildBackRight; + lookAtCentroid = _lookAtCentroid; + maxRetries = _maxRetries; +} + +void Pilot::BuildTarget::generateMapBuilderRequest() { + keepBestTarget(); + GET_SHAPE(target, TargetData, localShS); + if (target.isValid()) { + + Point nextPt; + if (getNextPoint(&nextPt)) { + VRmixin::pilot.curReq->targetShape = target; + + //cout << "BuildTarget: no more points to build." << endl; + myState = complete; + postCompletionEvent(); + return; + } + + myState = build; + + if ( VRmixin::pilot.curReq->buildTargetMapBuilderRequestFn != NULL ) { + MapBuilderRequest* mapreq = (*VRmixin::pilot.curReq->buildTargetMapBuilderRequestFn)(nextPt); + VRmixin::mapBuilder.executeRequest(*mapreq); + delete mapreq; + } + else { + cout << "BuildTarget: No MapBuilderRequest function provided." << endl; + myState = error; + VRmixin::pilot.failure(); + return; + } + } + else { + cout << "BuildTarget: Cannot find target in build phase." << endl; + myState = error; + VRmixin::pilot.failure(); + return; + } +} + +void Pilot::BuildTarget::keepBestTarget() { + Shape best; + int bestCount = 0; + std::vector >target_vector = select_type(localShS); + std::vector >::iterator targetIterator; + + // Iterates through all targets in local space, and keeps the one with the most number of valid endpoints, or the longest, in that order + for (targetIterator = target_vector.begin(); targetIterator != target_vector.end(); targetIterator++) { + Shape target = *(targetIterator); + int targetCount = 0; + if (target->getFrontLeftPt().isValid()) + targetCount++; + if (target->getFrontRightPt().isValid()) + targetCount++; + if (target->getBackLeftPt().isValid()) + targetCount++; + if (target->getBackRightPt().isValid()) + targetCount++; + if (!best.isValid() || (targetCount > bestCount) || ((targetCount == bestCount) && (target->getLength() > best->getLength()))) { + best = target; + bestCount = targetCount; + } + } + if (best.isValid()) { + best->setName("target"); + for (targetIterator = target_vector.begin(); targetIterator != target_vector.end(); targetIterator++) { + Shape other_target = *(targetIterator); + if (best != other_target) { + localShS.deleteShape(other_target); + } + } + } +} + +bool Pilot::BuildTarget::getNextPoint(Point *nextPoint) { + if (triesLeft <= 0) { + return true; + } + triesLeft--; + + GET_SHAPE(target, TargetData, localShS); + if (target.isValid()) { + EndPoint &frontLeft = target->getFrontLeftPt(); + EndPoint &frontRight = target->getFrontRightPt(); + EndPoint &backLeft = target->getBackLeftPt(); + EndPoint &backRight = target->getBackRightPt(); + + Point zero(0, 0, 0); + + if (buildFrontLeft && target->isFrontValid() && !frontLeft.isValid() && ((frontLeftPt == zero) || (frontLeftPt != frontLeft))) { + frontLeftPt = frontLeft; + cout << "Looking at front left pt: " << frontLeft << endl; + *nextPoint = frontLeft; + return false; + } + else if (buildFrontRight && target->isFrontValid() && !frontRight.isValid() && ((frontRightPt == zero) || (frontRightPt != frontRight))) { + frontRightPt = frontRight; + cout << "Looking at front right pt: " << frontRight << endl; + *nextPoint = frontRight; + return false; + } + else if (buildBackLeft && target->isBackValid() && !backLeft.isValid() && ((backLeftPt == zero) || (backLeftPt != backLeft))) { + backLeftPt = backLeft; + cout << "Looking at back left pt: " << backLeft << endl; + *nextPoint = backLeft; + return false; + } + else if (buildBackRight && target->isBackValid() && !backRight.isValid() && ((backRightPt == zero) || (backRightPt != backRight))) { + backRightPt = backRight; + cout << "Looking at back right pt: " << backRight << endl; + *nextPoint = backRight; + return false; + } + else if (lookAtCentroid) { + lookAtCentroid = false; + if ((buildFrontLeft || buildFrontRight) && ((centroid == zero) || (centroid != target->getFrontCentroid()))) { + centroid = target->getCentroid(); + cout << "Looking at centroid: " << centroid << endl; + *nextPoint = centroid; + return false; + } + else if (!buildFrontLeft && !buildFrontRight && (buildBackLeft || buildBackRight) && ((centroid == zero) || (centroid != target->getBackCentroid()))) { + centroid = target->getBackCentroid(); + cout << "Looking at back centroid: " << centroid << endl; + *nextPoint = centroid; + return false; + } + } + } + return true; +} + +//================ CreepToShape + +void Pilot::CreepToShape::DoStart() { + WaypointWalkNode::DoStart(); + cout << " >>>>> CreepToShape" << endl; + if ( VRmixin::lookout.busy() ) + cout << "Error: Pilot cannot launch track request because the Lookout is busy!" << endl; + else + VRmixin::lookout.executeRequest(LookoutTrackRequest(VRmixin::pilot.curReq->mapBuilderRequest->worldTargets.front()->targetShape)); + const ShapeRoot &target = VRmixin::pilot.curReq->targetShape; + Point const targetLoc(target->getCentroid()); + getMC()->getWaypointList().clear(); + switch ( target->getRefFrameType() ) { + case unspecified: + case camcentric: + cout << "Pilot: GotoShape target " << target << " has suspect reference frame type; assuming egocentric." << endl; + // fall through to next case + case egocentric: { + // can't creep to egocentric shape because motion invalidates localShS, so try to get there in one trajectory + float distance = targetLoc.xyNorm(); + AngSignPi bearing = atan2(targetLoc.coordY(),targetLoc.coordX()); + cout << "Pilot egocentric creepToShape: rotate by " << float(bearing)*(180.0/M_PI) << " deg., then forward " + << distance << " mm" << endl; + if ( distance >= 200 ) { + getMC()->addEgocentricWaypoint(0,0,bearing,true,0); + getMC()->addEgocentricWaypoint(distance/1000,0,0,true,0.06); // convert distance from mm to meters + VRmixin::mapBuilder.moveAgent(0.0, 0.0, float(bearing)); + VRmixin::mapBuilder.moveAgent(distance, 0.0, 0.0); + } else { + getMC()->addEgocentricWaypoint(distance/1000, 0, VRmixin::theAgent->getOrientation(), false, 0.06); // convert distance from mm to meters + VRmixin::mapBuilder.moveAgent(distance, 0.0, 0.0); + } + break; + } + case allocentric: // this is the normal case + Point const agentLoc = VRmixin::theAgent->getCentroid(); + float const distance = targetLoc.xyDistanceFrom(agentLoc); + if ( distance < 50 ) { + VRmixin::pilot.success(); + return; + } + float const scaleFactor = distance < 200 ? 1.0 : 200/distance; + Point const waypointLoc = agentLoc + (targetLoc-agentLoc)*scaleFactor; // take at most 200 mm steps + cout << "Pilot creepToShape: " + << "current position: " << agentLoc + << " next waypoint: " << waypointLoc + << " target loc: " << targetLoc << endl; + if ( distance > 200 ) + getMC()->addAbsoluteWaypoint(waypointLoc.coordX()/1000, waypointLoc.coordY()/1000, 0, true, 0.06); + else + getMC()->addAbsoluteWaypoint(waypointLoc.coordX()/1000, waypointLoc.coordY()/1000, VRmixin::theAgent->getOrientation(), false, 0.06); + float const heading = atan2(waypointLoc.coordY(),waypointLoc.coordX()); + VRmixin::mapBuilder.setAgent(Point(waypointLoc.coordX(), + waypointLoc.coordY(), + agentLoc.coordZ(), + allocentric), + heading); + break; + } + getMC()->go(); +} + +void Pilot::CreepToShapeStand::DoStop() { + PostureNode::DoStop(); // call parent first so we can override its effects + motman->setPriority(VRmixin::pilot.posture_id,MotionManager::kBackgroundPriority); +} + +void Pilot::CreepToShapeBuildMap::DoStart() { + VisualRoutinesStateNode::DoStart(); + VRmixin::lookout.stopTrack(); + if ( VRmixin::pilot.curReq->mapBuilderRequest ) + VRmixin::mapBuilder.executeRequest(*VRmixin::pilot.curReq->mapBuilderRequest, &mapreq_id); + else if ( VRmixin::pilot.curReq->mapBuilderRequestFn ) { + MapBuilderRequest* mapreq = (*VRmixin::pilot.curReq->mapBuilderRequestFn)(); + VRmixin::mapBuilder.executeRequest(*mapreq, &mapreq_id); + delete mapreq; + } +} + +void Pilot::CreepToShapeLocalize::DoStart() { + StateNode::DoStart(); + cout << " >>>>> CreepToShape Localize" << endl; + if ( VRmixin::pilot.curReq->localizationTest != NULL && + (*VRmixin::pilot.curReq->localizationTest)() == false ) { + VRmixin::pilot.failure(); + return; + } + VRmixin::particleFilter->setMinAcceptableWeight(-3); + for ( int i=0; i<8; i++ ) + VRmixin::particleFilter->update(); + VRmixin::particleFilter->setAgent(); + VRmixin::particleFilter->displayParticles(); + Point const loc = VRmixin::theAgent->getCentroid(); + MMAccessor(VRmixin::pilot.waypointwalk_id)-> + setCurPos(loc.coordX()/1000, loc.coordY()/1000, VRmixin::theAgent->getOrientation()); + // cout << "View world map; then send a text message to continue..." << endl; + // erouter->addListener(this,EventBase::textmsgEGID); + postCompletionEvent(); +} + +void Pilot::CreepToShapeLocalize::processEvent(const EventBase&) { + postCompletionEvent(); +} + +//================ IRCliff +#ifdef TGT_HAS_IR_DISTANCE +#ifdef TGT_ERS7 + +void Pilot::IRCliff::DoStart() { + StateNode::DoStart(); + erouter->addListener(this,EventBase::sensorEGID, SensorSrcID::UpdatedSID, EventBase::statusETID); +} + +void Pilot::IRCliff::processEvent(const EventBase &) { + if ( state->sensors[ChestIRDistOffset] > VRmixin::pilot.curReq->cliffThreshold ) { + cout << "Pilot: cliff detected!" << endl; + VRmixin::pilot.failure(); + } +} +#endif //TGT_ERS7 +#endif //TGT_HAS_IR_DISTANCE + +//================ IRObstacle +#ifdef TGT_HAS_IR_DISTANCE + +inline float getIR() { +#ifdef TGT_ERS7 + if ( state->sensors[FarIRDistOffset] > 400 ) // far IR goes 200-1500; near IR goes 50-500 + return state->sensors[FarIRDistOffset]; + else + return state->sensors[NearIRDistOffset]; +#else + return state->sensors[IRDistOffset]; +#endif +} + +void Pilot::IRObstacle::DoStart() { + StateNode::DoStart(); + erouter->addListener(this,EventBase::sensorEGID, SensorSrcID::UpdatedSID, EventBase::statusETID); +} + +void Pilot::IRObstacle::processEvent(const EventBase &) { + if ( getIR() < VRmixin::pilot.curReq->obstacleThreshold ) { + cout << "Pilot: obstacle detected!" << endl; + VRmixin::pilot.failure(); + } +} +#endif // TGT_HAS_IR_DISTANCE + + +//================ Localize +void Pilot::Localize::DoStart() { + StateNode::DoStart(); + erouter->addTimer(this, 1, VRmixin::pilot.curReq->localizationInterval, true); + if ( VRmixin::pilot.curReq->mapBuilderRequest->immediateRequest() == false ) // see comment "For immediate requests..." below + erouter->addListener(this,EventBase::mapbuilderEGID); +} + +/* For immediate requests, MapBuilder will post a completion event before +executeRequest has returned the request id, so processEvent will not +recognize this as a relevant event. Therefore we will process the map +when executeRequest returns; the completion event will already have been +posted and ignored. */ + +void Pilot::Localize::processEvent(const EventBase& event) { + switch ( event.getGeneratorID() ) { + case EventBase::timerEGID: + mapbuilder_id = VRmixin::mapBuilder.executeRequest(*VRmixin::pilot.curReq->mapBuilderRequest); + if ( VRmixin::pilot.curReq->mapBuilderRequest->immediateRequest() ) + processMap(event.getTimeStamp()); + break; + case EventBase::mapbuilderEGID: + if ( event.getSourceID() == mapbuilder_id && event.getTypeID() == EventBase::deactivateETID ) + processMap(event.getTimeStamp()); + break; + default: + break; + } +} + +void Pilot::Localize::processMap(unsigned int timestamp) { + if ( VRmixin::pilot.curReq->localizationTest == NULL || (*VRmixin::pilot.curReq->localizationTest)() ) { + VRmixin::particleFilter->update(); + VRmixin::particleFilter->setAgent(); + Point loc = VRmixin::theAgent->getCentroid(); + MMAccessor(VRmixin::pilot.waypointwalk_id)-> + setCurPos(loc.coordX()/1000, loc.coordY()/1000, VRmixin::theAgent->getOrientation()); + int const dispInt = VRmixin::pilot.curReq->localizationDisplayInterval; + if ( dispInt > 0 ) + if ( timestamp >= VRmixin::pilot.lastDisplayParticleTime+dispInt ) { + VRmixin::particleFilter->displayParticles(VRmixin::pilot.curReq->localizationDisplayParticles); + VRmixin::pilot.lastDisplayParticleTime = timestamp; + } + } +} + +Pilot::PilotVerbosity_t Pilot::verbosity = -1U; + +unsigned int Pilot::CreepToShapeBuildMap::mapreq_id = 0; + +} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Pilot.h ./DualCoding/Pilot.h --- ../Tekkotsu_3.0/DualCoding/Pilot.h 2006-08-02 17:34:04.000000000 -0400 +++ ./DualCoding/Pilot.h 2007-11-11 18:57:21.000000000 -0500 @@ -2,152 +2,260 @@ #ifndef INCLUDED_Pilot_h_ #define INCLUDED_Pilot_h_ -#include "Behaviors/BehaviorBase.h" +#include + +#include "Behaviors/StateNode.h" +#include "Behaviors/Nodes/PostureNode.h" +#include "Behaviors/Nodes/WaypointWalkNode.h" #include "Motion/MotionManager.h" -class EventBase; +#include "PilotRequest.h" +#include "VisualRoutinesStateNode.h" namespace DualCoding { -class ShapeRoot; +class Pilot : public StateNode { +public: -class PilotRequest { + typedef unsigned int PilotVerbosity_t; + static const PilotVerbosity_t PVstart = 1<<0; + static const PilotVerbosity_t PVevents = 1<<1; + static const PilotVerbosity_t PVexecute = 1<<2; + static const PilotVerbosity_t PVsuccess = 1<<3; + static const PilotVerbosity_t PVfailure = 1<<4; + static const PilotVerbosity_t PVcomplete = 1<<5; + +private: + static PilotVerbosity_t verbosity; public: + static void setVerbosity(PilotVerbosity_t v) { verbosity = v; } + static PilotVerbosity_t getVerbosity() { return verbosity; } - enum requestType_t { - reactiveWalk, - waypointWalk, - gotoShapeWalk, - } requestType; + class Success : public StateNode { + public: + Success() : StateNode("Success") {} + virtual void DoStart(); + }; - typedef struct Motion { - enum PilotMotionType_t { - transX=0, - transY, - rotate, - } type; + class Failure : public StateNode { + public: + Failure() : StateNode("Failure") {} + virtual void DoStart(); + }; - float val; // val of translation(mm/sec)/rotation(rad/sec) - Motion& operator=(const Motion& other) { - if (&other == this) return *this; - type = other.type; - val = other.val; - return *this; - } + class Walk : public WaypointWalkNode { + public: + Walk() : WaypointWalkNode("Walk") {} + virtual void DoStart(); + }; - Motion(const Motion& m) : type(m.type), val(m.val) {} - Motion(PilotMotionType_t t, float s) : type(t), val(s) {} + class VisualSearch : public VisualRoutinesStateNode { + public: + VisualSearch() : VisualRoutinesStateNode("VisualSearch"), mapbuilder_id(0) {} + virtual void DoStart(); + unsigned int mapbuilder_id; }; - typedef struct Constraint { - enum PilotConstraintType_t { - coordX, - coordY, - angle, - distance, - } type; + class VisualSearchHaveMap : public VisualRoutinesStateNode { + public: + VisualSearchHaveMap() : VisualRoutinesStateNode("VisualSearchHaveMap") {} + virtual void DoStart(); + }; - float val; // holds address of constraint - Constraint& operator=(const Constraint& other) { - if (&other == this) return *this; - type = other.type; - val = other.val;//(NULL==other.val) ? NULL : &(*other.val); - return *this; - } - Constraint(PilotConstraintType_t t, float v) : type(t), val(v) {}//&v) {} - Constraint(const Constraint& r) : type(r.type), val(r.val) {} //&(*r.val)) {} + class VisualSearchWalk : public WaypointWalkNode { + public: + VisualSearchWalk() : WaypointWalkNode("VisualSearchWalk"), walk_id(MotionManager::invalid_MC_ID) {} + virtual void DoStart(); + MotionManager::MC_ID walk_id; }; - unsigned int request_id; - vector motions; - vector constraints; + class GotoShape : public WaypointWalkNode { + public: + GotoShape() : WaypointWalkNode("GotoShape") {} + virtual void DoStart(); + }; -private: - PilotRequest(requestType_t _reqType, unsigned int _request_id, - const vector& _motions, const vector& _constraints) - : requestType(_reqType), request_id(_request_id), motions(_motions), constraints(_constraints) - { if (constraints.size() > 2) constraints.resize(2, Constraint(constraints.front())); - if (motions.size() > 2) motions.resize(2, Motion(motions.front())); } - PilotRequest(requestType_t _reqType, unsigned int _request_id, const Motion& _motion, - const vector& _constraints) - : requestType(_reqType), request_id(_request_id), motions(), constraints(_constraints) - { if (constraints.size() > 2) constraints.resize(2, Constraint(constraints.front())); - motions.push_back(_motion); } + class BuildTarget : public VisualRoutinesStateNode { + public: + BuildTarget(bool _buildFrontLeft = true, bool _buildFrontRight = true, bool _buildBackLeft = true, bool _buildBackRight = true, bool _lookAtCentroid = true, int _maxRetries = 10) : + VisualRoutinesStateNode("BuildTarget"), + buildFrontLeft(_buildFrontLeft), buildFrontRight(_buildFrontRight), buildBackLeft(_buildBackLeft), buildBackRight(_buildBackRight), lookAtCentroid(_lookAtCentroid), + frontLeftPt(0, 0, 0), frontRightPt(0, 0, 0), backLeftPt(0, 0, 0), backRightPt(0, 0, 0), centroid(0, 0, 0), + maxRetries(_maxRetries), triesLeft(0), + myState(none) {} + virtual void DoStart(); + virtual void DoStop(); + virtual void processEvent(const EventBase& event); -public: - // reactive walk - static PilotRequest Rotate(unsigned int _request_id, float speed, const vector& _constraints) - { return PilotRequest(reactiveWalk, _request_id, Motion(Motion::rotate,speed), _constraints); } - static PilotRequest translateX(unsigned int _request_id, float speed, const vector& _constraints) - { return PilotRequest(reactiveWalk, _request_id, Motion(Motion::transX,speed), _constraints); } - static PilotRequest translateY(unsigned int _request_id, float speed, const vector& _constraints) - { return PilotRequest(reactiveWalk, _request_id, Motion(Motion::transY,speed), _constraints); } + void setParams(bool _buildFrontLeft = true, bool _buildFrontRight = true, bool _buildBackLeft = true, bool _buildBackRight = true, bool _lookAtCentroid = true, int _maxRetries = 10); + + protected: + void generateMapBuilderRequest(); + void keepBestTarget(); + bool getNextPoint(Point *point); + + bool buildFrontLeft, buildFrontRight, buildBackLeft, buildBackRight, lookAtCentroid; + Point frontLeftPt, frontRightPt, backLeftPt, backRightPt, centroid; + int maxRetries, triesLeft; + enum State {none, build, complete, error} myState; + }; + + class GotoTarget : public WaypointWalkNode { + public: + GotoTarget() : WaypointWalkNode("GotoTarget"), buildTargetNode(NULL) {} + virtual void DoStart(); + + BuildTarget *buildTargetNode; + + protected: + int getNextWaypoint(Point *point, AngSignPi *angle); + void setNextWaypoint(); + Point getPointAtAngle(AngSignPi angle); + + + private: + GotoTarget(const GotoTarget&); //!< do not call + GotoTarget& operator=(const GotoTarget&); //!< do not call +}; + + class PushTarget : public WaypointWalkNode { + public: + PushTarget() : WaypointWalkNode("PushTarget"), buildTargetNode(NULL) {} + virtual void DoStart(); + + BuildTarget *buildTargetNode; + + private: + PushTarget(const PushTarget&); //!< do not call + PushTarget& operator=(const PushTarget&); //!< do not call + }; - // waypoint walk - PilotRequest(unsigned int _request_id, const Motion& _motion) - : requestType(waypointWalk), request_id(_request_id), motions(), constraints() { motions.push_back(_motion); } - static PilotRequest Rotate(unsigned int _request_id, float dest) - { return PilotRequest(_request_id, Motion(Motion::rotate,dest)); } - static PilotRequest translateX(unsigned int _request_id, float dest) - { return PilotRequest(_request_id, Motion(Motion::transX,dest)); } - static PilotRequest translateY(unsigned int _request_id, float dest) - { return PilotRequest(_request_id, Motion(Motion::transY,dest)); } + class CreepToShape : public WaypointWalkNode { + public: + CreepToShape() : WaypointWalkNode("CreepToShape") {} + virtual void DoStart(); + }; - // gotoShape walk - static PilotRequest GotoShape(unsigned int _req_id) - { return PilotRequest(gotoShapeWalk,_req_id,vector(),vector()); } + class CreepToShapeStand : public PostureNode { + public: + CreepToShapeStand() : PostureNode("CreepToShapeStand","walk.pos") {} + virtual void DoStop(); + }; - - PilotRequest& operator=(const PilotRequest& other) { - if (&other == this) return *this; - requestType = other.requestType; - request_id = other.request_id; - motions = other.motions; - constraints = other.constraints; - return *this; - } -}; + class CreepToShapeWait : public StateNode { + public: + CreepToShapeWait() : StateNode("CreepToShapeWait") {} + }; + class CreepToShapeBuildMap : public VisualRoutinesStateNode { + public: + CreepToShapeBuildMap() : VisualRoutinesStateNode("CreepToShapeBuildMap") {} + virtual void DoStart(); + static unsigned int mapreq_id; + }; -class Pilot : public BehaviorBase { -private: - vector requests; - // vector colors; + class CreepToShapeLocalize : public StateNode { + public: + CreepToShapeLocalize() : StateNode("CreepToShapeLocalize") {} + virtual void DoStart(); + virtual void processEvent(const EventBase&); + }; - void removeCurrentRequest() { - if (!requests.empty()) - requests.erase(requests.begin()); - } - void executeRequest() {}//; - /* - void processReactiveWalk(const EventBase& e); - void processWaypointWalk(const EventBase& e); - void processGotoShape(const EventBase& e); - enum RequestIDs { - lookAtID, - trackID, +#ifdef TGT_HAS_IR_DISTANCE +#ifdef TGT_ERS7 + class IRCliff : public StateNode { + public: + IRCliff() : StateNode("IRCliff") {} + virtual void DoStart(); + virtual void processEvent(const EventBase&); }; - */ -public: +#endif // TGT_ERS7 + + class IRObstacle : public StateNode { + public: + IRObstacle() : StateNode("IRObstacle") {} + virtual void DoStart(); + virtual void processEvent(const EventBase&); + }; +#endif // TGT_HAS_IR_DISTANCE + + class Localize : public StateNode { + public: + Localize() : StateNode("Localize"), mapbuilder_id(0) {} + virtual void DoStart(); + virtual void processEvent(const EventBase&); + void processMap(unsigned int timestamp); + unsigned int mapbuilder_id; + }; + + class Dispatch : public VisualRoutinesStateNode { + public: + Dispatch() : + VisualRoutinesStateNode("Dispatch"), successNode(NULL), failureNode(NULL), + walkNode(NULL), visualsearchNode(NULL), gotoshapeNode(NULL), + gotoTargetNode(NULL), pushTargetNode(NULL), + creeptoshapeNode(NULL), +#ifdef TGT_HAS_IR_DISTANCE +#ifdef TGT_ERS7 + ircliffNode(NULL), +#endif + irobstacleNode(NULL), +#endif + localizeNode(NULL) + {} + virtual void setup(); + virtual void DoStart(); + Success *successNode; + Failure *failureNode; + Walk *walkNode; + VisualSearch *visualsearchNode; + GotoShape *gotoshapeNode; + GotoTarget *gotoTargetNode; + PushTarget *pushTargetNode; + CreepToShape *creeptoshapeNode; +#ifdef TGT_HAS_IR_DISTANCE +#ifdef TGT_ERS7 + IRCliff *ircliffNode; +#endif // TGT_ERS7 + IRObstacle *irobstacleNode; +#endif // TGT_HAS_IR_DISTANCE + Localize *localizeNode; + private: + Dispatch(const Dispatch&); + Dispatch& operator=(const Dispatch&); + }; + //! Constructor - Pilot() : BehaviorBase("Pilot"), requests() {} //; + Pilot(); - // virtual void DoStart(); - // virtual void DoStop(); - // virtual void processEvent(const ::EventBase &e); - virtual void executeRequest(const PilotRequest &req) { - if (!requests.empty()) { - cout << "Pilot busy\n"; - return; - } - requests.push_back(req); - executeRequest(); - } - void gotoShape(const ShapeRoot&) {}//; - void turnBy(AngTwoPi){}//; + virtual void DoStart(); + virtual void DoStop(); + virtual void setup(); + unsigned int executeRequest(const PilotRequest& req); + void abort(); //!< Abort current request and empty the request queue + MotionManager::MC_ID getWaypointWalk_MC_ID() { return waypointwalk_id; } + + static const unsigned int invalid_Pilot_ID = (unsigned int)-1; + +protected: + void executeRequest(); + void requestComplete(const bool result=true); + void success() { dispatchNode->successNode->DoStart(); } + void failure() { dispatchNode->failureNode->DoStart(); } + + std::queue requests; + PilotRequest *curReq; + unsigned int idCounter; + MotionManager::MC_ID waypointwalk_id; + MotionManager::MC_ID posture_id; + unsigned int lastDisplayParticleTime; + + Dispatch *dispatchNode; + +private: + Pilot(const Pilot&); //!< do not call + Pilot& operator=(const Pilot&); //!< do not call - // MotionManager::MC_ID walker_id; - // MotionManager::MC_ID waypoint_id; }; } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PilotRequest.cc ./DualCoding/PilotRequest.cc --- ../Tekkotsu_3.0/DualCoding/PilotRequest.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/PilotRequest.cc 2007-04-23 17:44:46.000000000 -0400 @@ -0,0 +1,36 @@ +#include "PilotRequest.h" + +#include "Pilot.h" + +namespace DualCoding { + +PilotRequest::PilotRequest(PilotRequestType_t _type) : + requestType(_type), + dx(0), dy(0), da(0), + mapBuilderRequest(NULL), mapBuilderRequestFn(NULL),searchRotationAngle(0), exitTest(NULL), + targetShape(), + avoidCliffs(false), cliffThreshold(200), avoidObstacles(false), obstacleThreshold(100), + trackRequest(NULL), + localizationInterval(0), localizationTest(NULL), localizationDisplayParticles(100), localizationDisplayInterval(0), + safeDistanceAroundTarget(300), subtendAngle(0.2f), approachAngle(0.1f), + positionRelativeToTarget(200, 0, 0), angleToPushTarget(M_PI), + buildTargetParamsFn(NULL), buildTargetMapBuilderRequestFn(NULL), + requestID(Pilot::invalid_Pilot_ID) {} + +PilotRequest::PilotRequest(const PilotRequest &req) : + requestType(req.requestType), + dx(req.dx), dy(req.dy), da(req.da), + mapBuilderRequest(req.mapBuilderRequest), mapBuilderRequestFn(req.mapBuilderRequestFn), + searchRotationAngle(req.searchRotationAngle), exitTest(req.exitTest), + targetShape(req.targetShape), + avoidCliffs(req.avoidCliffs), cliffThreshold(req.cliffThreshold), + avoidObstacles(req.avoidObstacles), obstacleThreshold(req.obstacleThreshold), + trackRequest(req.trackRequest), + localizationInterval(req.localizationInterval), localizationTest(req.localizationTest), + localizationDisplayParticles(req.localizationDisplayParticles), localizationDisplayInterval(req.localizationDisplayInterval), + safeDistanceAroundTarget(req.safeDistanceAroundTarget), subtendAngle(req.subtendAngle), approachAngle(req.approachAngle), + positionRelativeToTarget(req.positionRelativeToTarget), angleToPushTarget(req.angleToPushTarget), + buildTargetParamsFn(req.buildTargetParamsFn), buildTargetMapBuilderRequestFn(req.buildTargetMapBuilderRequestFn), + requestID(req.requestID) {} + +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PilotRequest.h ./DualCoding/PilotRequest.h --- ../Tekkotsu_3.0/DualCoding/PilotRequest.h 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/PilotRequest.h 2007-04-23 17:44:46.000000000 -0400 @@ -0,0 +1,70 @@ +//-*-c++-*- +#ifndef INCLUDED_PilotRequest_h_ +#define INCLUDED_PilotRequest_h_ + +#include "ShapeRoot.h" + +namespace DualCoding { + +class MapBuilderRequest; +class LookoutTrackRequest; + +//! Request to the @a Pilot for motion or navigation. + +class PilotRequest { + friend class Pilot; + + public: + enum PilotRequestType_t { + walk, + waypointWalk, + visualSearch, + gotoShape, + gotoTarget, + pushTarget, + creepToShape + }; + + //! Constructor + PilotRequest(PilotRequestType_t _type); + + PilotRequest(const PilotRequest &req); + + PilotRequestType_t getRequestType() const { return requestType; } + + PilotRequestType_t requestType; //!< Type of pilot request + float dx; //!< Forward walk distance in mm + float dy; //!< Walking strafe distance in mm + float da; //!< Walking rotation distance in radians + MapBuilderRequest *mapBuilderRequest; //!< MapBuilderRequest to be used for visual search + MapBuilderRequest* (*mapBuilderRequestFn)(); //!< function to return a dynamically-constructed MapBuilderRequest which Pilot will delete + AngSignPi searchRotationAngle; //!< Angle to rotate body to continue a visual search + bool (*exitTest)(); //!< If true, terminate search and post a completion event + ShapeRoot targetShape; //!< Shape to walk to + bool avoidCliffs; //!< If true, use chest IR to avoid walking off a cliff + int cliffThreshold; //!< Maximum tolerable distance to the ground (millimeters) + bool avoidObstacles; //!< If true, use head IR sensors to avoid obstacles + int obstacleThreshold; //!< Minimum tolerable distance to an obstacle (millimeters) + LookoutTrackRequest *trackRequest; //!< Lookout request for tracking objects while walking + int localizationInterval; //!< Time in msec between localization attempts; will execute the mapBuilderRequest, then if localizeTest is true, will call particle filter + bool (*localizationTest)(); //!< If true, local map contains good enough data to try to localize + float localizationDisplayParticles; //!< How many particles to display (number or percentage) + int localizationDisplayInterval; //!< Time in msec between calls to displayParticles() + + float safeDistanceAroundTarget; //!< The distance to stay away from the target while circling + AngSignPi subtendAngle; //!< The angle in which to subtend the target while circling + AngSignPi approachAngle; //!< The angle in which to approach the desired position around the target + Point positionRelativeToTarget; //!< The desired position around the target, relative to the target + AngSignPi angleToPushTarget; //!< The angle in which to push the target + void (*buildTargetParamsFn)(bool *buildFrontLeft, bool *buildFrontRight, bool *buildBackLeft, bool *buildBackRight, bool *lookAtCentroid, int *maxRetries); //!< function to return the parameters to build the target + MapBuilderRequest* (*buildTargetMapBuilderRequestFn)(Point point); //!< function to return a dynamically-constructed MapBuilderRequest, given a point to look at, which BuildTarget will use to build the target + +private: + unsigned int requestID; + + PilotRequest& operator=(const PilotRequest &req); //!< don't call this +}; + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Point.cc ./DualCoding/Point.cc --- ../Tekkotsu_3.0/DualCoding/Point.cc 2006-08-02 17:27:59.000000000 -0400 +++ ./DualCoding/Point.cc 2007-11-18 01:47:02.000000000 -0500 @@ -5,12 +5,14 @@ #include "Shared/Config.h" #include "Motion/Kinematics.h" -#include "Measures.h" +#include "Shared/Measures.h" #include "Point.h" #include "LineData.h" #include "ShapeTypes.h" // for ReferenceFrameType_t #include "VRmixin.h" +using namespace std; + namespace DualCoding { Point::Point(void) : coords(4), refFrameType(unspecified) { @@ -46,6 +48,8 @@ return sqrt(dx*dx+dy*dy); } +float Point::xyNorm() const { return sqrt(coords(1)*coords(1) + coords(2)*coords(2)); } + bool Point::isLeftOf(const Point& other, float distance) const { switch ( refFrameType ) { case camcentric: @@ -84,7 +88,11 @@ //! Apply a transformation matrix to translate and/or rotate the point. -void Point::applyTransform(const NEWMAT::Matrix& Tmat) { coords = Tmat*coords; } +void Point::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + coords = Tmat*coords; + if ( newref != unspecified ) + refFrameType = newref; + } void Point::projectToGround(const NEWMAT::Matrix& camToBase, const NEWMAT::ColumnVector& groundPlane) { @@ -114,10 +122,12 @@ intersect(4)=1; } coords = camToBase*intersect; + refFrameType = egocentric; } void Point::projectToGround(int xres, int yres, const NEWMAT::ColumnVector& ground_plane) { +#ifdef TGT_HAS_CAMERA // Normalize coordinate system to [-1,+1] const float normX = 2*(coordX()/xres) - 1; const float normY = 2*(coordY()/yres) - 1; @@ -134,11 +144,15 @@ coords(1) = ground_point(1) / ground_point(4); coords(2) = ground_point(2) / ground_point(4); coords(3) = ground_point(3) / ground_point(4); +#endif } // Calling point and groundPoint must both have been projectToGround'ed already float Point::getHeightAbovePoint(const Point& groundPoint, const NEWMAT::ColumnVector& groundplane) { +#ifndef TGT_HAS_CAMERA + return groundPoint.coordZ(); +#else float camX, camY, camZ; NEWMAT::Matrix baseToCam = kine->jointToBase(CameraFrameOffset); NEWMAT::ColumnVector camOffset = baseToCam.Column(4); @@ -160,24 +174,30 @@ float dHorizPoint = sqrt(dP.coordX()*dP.coordX() + dP.coordY()*dP.coordY()); return dz*dHorizPoint/dHorizCam; +#endif } - Point Point::operator+ (const Point& b) const { return Point(coords+b.coords,refFrameType); } +Point Point::operator+ (const Point& b) const { return Point(*this) += b; } Point& Point::operator+= (const Point& b) { coords += b.coords; + makeRefFrameCompatible(b); return *this; } - -Point Point::operator- (const Point& b) const { return Point(coords-b.coords,refFrameType); } +Point Point::operator- (const Point& b) const { return Point(*this) -= b; } Point& Point::operator-= (const Point& b) { coords -= b.coords; + makeRefFrameCompatible(b); return *this; } +void Point::makeRefFrameCompatible(const Point &other) { + refFrameType = ( refFrameType == unspecified || refFrameType == other.refFrameType ) ? + other.refFrameType : unspecified; +} Point Point::operator* (float const b) const { return Point(coords*b,refFrameType); } @@ -201,8 +221,22 @@ } std::ostream& operator<< (std::ostream& out, const Point &p) { - out << "(" << p.coordX() << ", " << p.coordY() - << ", " << p.coordZ() << ")"; + switch ( p.refFrameType ) { + case unspecified: + out << "u:"; + break; + case camcentric: + out << "c:"; + break; + case egocentric: + out << "e:"; + break; + case allocentric: + out << "a:"; + break; + } + out << "[" << p.coordX() << ", " << p.coordY() + << ", " << p.coordZ() << "]"; return out; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Point.h ./DualCoding/Point.h --- ../Tekkotsu_3.0/DualCoding/Point.h 2006-08-02 17:27:59.000000000 -0400 +++ ./DualCoding/Point.h 2007-11-11 18:57:21.000000000 -0500 @@ -8,7 +8,7 @@ #include "Shared/newmat/newmat.h" #include "Shared/newmat/newmatio.h" -#include "Measures.h" // coordinate_t, AngPi +#include "Shared/Measures.h" // coordinate_t, AngPi #include "ShapeTypes.h" // ReferenceFrameType_t namespace DualCoding { @@ -44,6 +44,7 @@ coordinate_t coordX() const { return coords(1); } coordinate_t coordY() const { return coords(2); } coordinate_t coordZ() const { return coords(3); } + ReferenceFrameType_t getRefFrameType() const { return refFrameType; } //! Set position. //@{ @@ -57,7 +58,7 @@ //! Euclidean distance from another point to this one float distanceFrom(const Point& other) const; float xyDistanceFrom(const Point& other) const; - + float xyNorm() const; //! These functions need a ShapeSpace argument because left/right depends on reference frame type. //@{ @@ -72,14 +73,14 @@ bool isBetween(const Point& other1, const Point& other2) const; bool isBetween(const Shape& line1, const Shape& line2) const; bool isBetween(const LineData& line1, const LineData& line2) const; - bool isInside(const vector& bound) const; + bool isInside(const std::vector& bound) const; //@} - void applyTransform(const NEWMAT::Matrix& T); - float getHeightAbovePoint(const Point& groundPoint, const NEWMAT::ColumnVector& groundplane); + void applyTransform(const NEWMAT::Matrix& T, const ReferenceFrameType_t newref=unspecified); + //! projects this to ground plane according to camToBase matrix void projectToGround(const NEWMAT::Matrix& camToBase, const NEWMAT::ColumnVector& groundPlane); @@ -113,6 +114,9 @@ friend class EndPoint; +private: + void makeRefFrameCompatible(const Point &other); + }; inline Point& leftMost(Point &pt1, Point &pt2) { return pt1.isLeftOf(pt2) ? pt1 : pt2; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PointData.cc ./DualCoding/PointData.cc --- ../Tekkotsu_3.0/DualCoding/PointData.cc 2006-08-02 17:34:58.000000000 -0400 +++ ./DualCoding/PointData.cc 2007-11-11 18:57:21.000000000 -0500 @@ -17,6 +17,8 @@ #include "PointData.h" #include "ShapePoint.h" +using namespace std; + namespace DualCoding { PointData::PointData(ShapeSpace& _space, const Point &c) @@ -51,7 +53,6 @@ return true; } -//! Print information about this shape. (Virtual in BaseData.) void PointData::printParams() const { cout << "Type = " << getTypeName(); @@ -66,9 +67,8 @@ } -//! Transformations. (Virtual in BaseData.) -void PointData::applyTransform(const NEWMAT::Matrix& Tmat) { - the_point.applyTransform(Tmat); +void PointData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + the_point.applyTransform(Tmat,newref); } void PointData::projectToGround(const NEWMAT::Matrix& camToBase, @@ -96,7 +96,7 @@ Point pt(x,y,0); SkS.applyTmat(pt.getCoords()); Shape new_point_shape(new PointData(ShS,pt)); - new_point_shape->inheritFrom(sketch.rootGetData()); + new_point_shape->inheritFrom(*sketch.rootGetData()); result.push_back(new_point_shape); } return result; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PointData.h ./DualCoding/PointData.h --- ../Tekkotsu_3.0/DualCoding/PointData.h 2006-08-02 17:34:58.000000000 -0400 +++ ./DualCoding/PointData.h 2007-03-28 05:19:18.000000000 -0400 @@ -30,7 +30,7 @@ DATASTUFF_H(PointData); //! Centroid. (Virtual in BaseData.) - Point getCentroid() const { return the_point; } + virtual Point getCentroid() const { return the_point; } BoundingBox getBoundingBox() const { return BoundingBox(the_point.coordX(),the_point.coordY(),the_point.coordX(),the_point.coordY()); @@ -41,15 +41,13 @@ virtual void mergeWith(const ShapeRoot& other); - virtual bool isAdmissible() const { return true; } - virtual bool updateParams(const ShapeRoot& other, bool force=false); //! Print information about this shape. (Virtual in BaseData.) virtual void printParams() const; //! Transformations. (Virtual in BaseData.) - void applyTransform(const NEWMAT::Matrix& Tmat); + virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); //! Project to ground virtual void projectToGround(const NEWMAT::Matrix& camToBase, @@ -66,7 +64,7 @@ private: //! Render into a sketch space and return reference. (Private.) - Sketch* render() const; + virtual Sketch* render() const; //@} }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PolygonData.cc ./DualCoding/PolygonData.cc --- ../Tekkotsu_3.0/DualCoding/PolygonData.cc 2006-08-02 17:27:14.000000000 -0400 +++ ./DualCoding/PolygonData.cc 2007-11-11 18:57:21.000000000 -0500 @@ -9,6 +9,8 @@ #include "PolygonData.h" #include "ShapePolygon.h" +using namespace std; + namespace DualCoding { DATASTUFF_CC(PolygonData); @@ -432,13 +434,13 @@ cout << (*it) << endl; } -void PolygonData::applyTransform(const NEWMAT::Matrix& Tmat) { +void PolygonData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { for (vector::iterator it = edges.begin(); it != edges.end(); it++) - it->applyTransform(Tmat); + it->applyTransform(Tmat,newref); for (vector::iterator it = vertices.begin(); it != vertices.end(); it++) - it->applyTransform(Tmat); + it->applyTransform(Tmat,newref); } void PolygonData::projectToGround(const NEWMAT::Matrix& camToBase, @@ -459,7 +461,7 @@ } -void PolygonData::setColor(rgb new_color) { +void PolygonData::setColor(const rgb &new_color) { color_rgb = new_color; for (vector::iterator it = edges.begin(); it != edges.end(); it++) @@ -467,41 +469,31 @@ deleteRendering(); } +void PolygonData::setColor(const color_index cindex) { + setColor(ProjectInterface::getColorRGB(cindex)); +} + +void PolygonData::setColor(const std::string &color_name) { + setColor(ProjectInterface::getColorRGB(color_name)); +} + // helper function to sort lines from longest to shortest bool PolygonData::isFirstLineLonger(const Shape& ln1,const Shape& ln2) { return ln1->isLongerThan(ln2); } Sketch* PolygonData::render() const { - string const result_name = "render(" + getName() + ")"; - Sketch canvas(space->getDualSpace(), result_name); - canvas = 0; + Sketch *canvas = new Sketch(space->getDualSpace(),""); + (*canvas) = 0; const int width = space->getDualSpace().getWidth(); const int height = space->getDualSpace().getHeight(); float x1, y1, x2, y2; for (vector::const_iterator it = edges.begin(); it != edges.end(); it++) { it->setDrawCoords(x1, y1, x2, y2, width, height); - it->drawline2d(canvas, (int)x1, (int)y1, (int)x2, (int)y2); - } - if (!isClosed()) - return new Sketch(canvas); - NEW_SKETCH_N(borders, bool, visops::zeros(canvas)); - for (int i = 0; i < width; i++) { - borders(i,0) = ! canvas(i,0); - borders(i,height-1) = ! canvas(i,height-1); - } - for (int j = 1; j < height-1; j++) { - borders(0,j) = ! canvas(0,j); - borders(width-1,j) = ! canvas(width-1,j); + it->drawline2d(*canvas, (int)x1, (int)y1, (int)x2, (int)y2); } - usint const not_reached = usint(-1); - NEW_SKETCH_N(bd, usint, visops::bdist(borders, canvas, width*height)); - bd->inheritFrom(*this); - bd->setColorMap(jetMap); - NEW_SKETCH(result, bool, bd == not_reached); - result->setName(result_name); - return new Sketch(result); + return canvas; } //================ Convex Hull ================ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PolygonData.h ./DualCoding/PolygonData.h --- ../Tekkotsu_3.0/DualCoding/PolygonData.h 2006-05-14 12:19:32.000000000 -0400 +++ ./DualCoding/PolygonData.h 2007-11-11 18:57:21.000000000 -0500 @@ -8,7 +8,7 @@ #include "BaseData.h" // superclass #include "LineData.h" // LineData data member -#include "Measures.h" // coordinate_t; AngPi data member +#include "Shared/Measures.h" // coordinate_t; AngPi data member namespace DualCoding { @@ -30,9 +30,9 @@ class PolygonData : public BaseData { protected: - vector edges; // edges which consist this polygon + std::vector edges; // edges which consist this polygon private: - vector vertices; // cache of vertices + std::vector vertices; // cache of vertices public: static ShapeType_t getStaticType() { return polygonDataType; } @@ -42,19 +42,19 @@ //! Constructors PolygonData(const LineData&); - PolygonData(ShapeSpace& space, const vector& pts, bool closed, + PolygonData(ShapeSpace& space, const std::vector& pts, bool closed, bool end1Valid=true, bool end2Valid=true); - PolygonData(const vector& lns) + PolygonData(const std::vector& lns) : BaseData(lns.front()), edges(lns), vertices() { updateVertices(); } PolygonData(const PolygonData& other) : BaseData(other), edges(other.edges), vertices(other.vertices) {} - static vector > extractPolygonEdges(Sketch const& sketch, Sketch const& occluder); //!< extracts then-edges lines + static std::vector > extractPolygonEdges(Sketch const& sketch, Sketch const& occluder); //!< extracts then-edges lines //! forms polygons from lines and existing polygons //! existing polygons may be updated or deleted for which case they are added to deleted vector - static vector formPolygons(const vector&, - vector >& existing, vector& deleted); - static vector formPolygons(const vector&); //!< forms polygons from lines + static std::vector formPolygons(const std::vector&, + std::vector >& existing, std::vector& deleted); + static std::vector formPolygons(const std::vector&); //!< forms polygons from lines //! Edge/Vertex Access Functions //@{ @@ -62,14 +62,14 @@ const LineData& end2Ln() const { return edges.back(); } //!< returns last edge of this polygon const EndPoint& end1Pt() const { return edges.front().end1Pt(); } //!< returns end1Pt of end1Ln const EndPoint& end2Pt() const { return edges.back().end2Pt(); } //!< returns end2Pt of end2Ln - const vector& getVertices() const { return vertices; } //!< returns all vertices of this polygon - const vector& getEdges() const { return edges; } //!< returns all edges of this polygon - vector& getEdgesRW() { return edges; } //!< returns address of edge vector for modification + const std::vector& getVertices() const { return vertices; } //!< returns all vertices of this polygon + const std::vector& getEdges() const { return edges; } //!< returns all edges of this polygon + std::vector& getEdgesRW() { return edges; } //!< returns address of edge vector for modification //@} BoundingBox getBoundingBox() const; - vector updateState(); + std::vector updateState(); bool isClosed() const ; //* render() const; virtual unsigned short getDimension() const { return 2; } //} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PyramidData.cc ./DualCoding/PyramidData.cc --- ../Tekkotsu_3.0/DualCoding/PyramidData.cc 2006-07-21 14:30:57.000000000 -0400 +++ ./DualCoding/PyramidData.cc 2007-11-11 18:57:21.000000000 -0500 @@ -19,6 +19,7 @@ #include "ShapePoint.h" #include "Region.h" +using namespace std; namespace DualCoding { @@ -74,12 +75,12 @@ //! Transformations. (Virtual in BaseData.) - void PyramidData::applyTransform(const NEWMAT::Matrix& Tmat) { - FL.applyTransform(Tmat); - FR.applyTransform(Tmat); - BL.applyTransform(Tmat); - BR.applyTransform(Tmat); - Top.applyTransform(Tmat); + void PyramidData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + FL.applyTransform(Tmat,newref); + FR.applyTransform(Tmat,newref); + BL.applyTransform(Tmat,newref); + BR.applyTransform(Tmat,newref); + Top.applyTransform(Tmat,newref); } /*void PyramidData::projectToGround(const NEWMAT::ColumnVector& groundplane) { @@ -106,13 +107,14 @@ BR.projectToGround(camToBase, groundplane); Point bottomCenter = (FL + FR + BL + BR) / 4.0; + bottomCenter.setRefFrameType(egocentric); float height; Top.projectToGround(camToBase, groundplane); height = Top.getHeightAbovePoint(bottomCenter, groundplane); Top.setCoords(bottomCenter.coordX(), bottomCenter.coordY(), bottomCenter.coordZ() + height); centroid = bottomCenter; centroid.setCoords(centroid.coordX(), centroid.coordY(), centroid.coordZ() + height/5); - std::cout<<"New centroid: ("< extractPyramid(ShapeSpace& space, vector > &blobs); + static Shape extractPyramid(ShapeSpace& space, std::vector > &blobs); - static vector findBoundingTriangle(ShapeSpace& space, Shape blob, + static std::vector findBoundingTriangle(ShapeSpace& space, Shape blob, Point centroid, Shape parallel); private: //! Render into a sketch space and return reference. (Private.) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Region.cc ./DualCoding/Region.cc --- ../Tekkotsu_3.0/DualCoding/Region.cc 2006-07-21 13:57:52.000000000 -0400 +++ ./DualCoding/Region.cc 2007-11-11 18:57:21.000000000 -0500 @@ -3,7 +3,7 @@ #include #include -#include "Measures.h" +#include "Shared/Measures.h" #include "SketchSpace.h" #include "SketchIndices.h" #include "Sketch.h" @@ -35,19 +35,19 @@ memset(&cmoments, NOTCOMPUTED, sizeof(float)*(MAX_MOMENT+1)*(MAX_MOMENT+1)); } -std::list Region::extractRegions(const Sketch& labels, int area_thresh) +std::list Region::extractRegions(const Sketch& labels, uint area_thresh) { size_t length = labels->getNumPixels(); // tally up areas - vector areas(labels->max()+1, 0); // not having +1 may have caused malloc crash + std::vector areas(labels->max()+1, 0); // not having +1 may have caused malloc crash for (size_t i = 0; i < length; i++) if (labels[i] != 0) areas[labels[i]]++; // add unsorted Regions to list std::list regionlist; - for (int r = 0; r < (int)(areas.size()); r++) { + for (uint r = 0; r < (uint)(areas.size()); r++) { if (areas[r] >= area_thresh) { // construct Region and add to list Region cur_reg(labels->getSpace()); @@ -86,23 +86,16 @@ bool Region::operator< (const Region& other) const { return (area > other.area); } - - int Region::findTopBound() { if (topBound != NOTCOMPUTED) // problem if NOTCOMPUTED == 0 return topBound; else { SketchIndices::CI it; - int top = 9999; - int temp = 0; + int top = space.getHeight(); int width = space.getWidth(); - //int width = space.getWidth()+1; for (it = table.begin(); it != table.end(); it++) - if ((*it)/width < top) { - top = (*it)/width; - temp = *it; - } - // cout << "Top bound: " << temp << " / " << width << " = " << top << endl; + if (int((*it)/width) < top) + top = (*it)/width; topBound = top; return top; } @@ -115,10 +108,9 @@ SketchIndices::CI it; int bot = -1; int width = space.getWidth(); - //int width = space.getWidth()+1; for (it = table.begin(); it != table.end(); it++) - if ((*it+1)/width > bot) - bot = (*it)/width; + if (int((*it+1)/width) > bot) + bot = (*it)/width; botBound = bot; return bot; } @@ -132,8 +124,8 @@ int left = 9999; int width = space.getWidth(); for (it = table.begin(); it != table.end(); it++) - if ((*it)%width < left) - left = (*it)%width; + if (int((*it)%width) < left) + left = (*it)%width; leftBound = left; return left; } @@ -147,8 +139,8 @@ int right = -1; int width = space.getWidth(); for (it = table.begin(); it != table.end(); it++) - if ((*it)%width > right) - right = (*it)%width; + if (int((*it)%width) > right) + right = (*it)%width; rightBound = right; return right; } @@ -193,15 +185,15 @@ return Point(x_coord, findYcoordFor(x_coord)); } -bool Region::isContained(const Point& pt, const int max_dist) { - const int x_coord = (int) pt.coordX(); - const int y_coord = (int) pt.coordY(); - const int width = space.getWidth(); +bool Region::isContained(const Point& pt, const uint max_dist) { + const uint x_coord = (uint) pt.coordX(); + const uint y_coord = (uint) pt.coordY(); + const uint width = space.getWidth(); // cout << pt << endl; for (SketchIndices::CI it = table.begin(); it != table.end(); it++) if (((*it)%width <= x_coord+max_dist && (*it)%width >= x_coord-max_dist) - && ((*it)/width <= y_coord+max_dist && (*it)/width >= y_coord-max_dist)) + && ((*it)/width <= y_coord+max_dist && (*it)/width >= y_coord-max_dist)) return true; return false; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Region.h ./DualCoding/Region.h --- ../Tekkotsu_3.0/DualCoding/Region.h 2006-07-21 13:57:53.000000000 -0400 +++ ./DualCoding/Region.h 2007-08-24 21:49:15.000000000 -0400 @@ -4,7 +4,7 @@ #include -#include "Measures.h" +#include "Shared/Measures.h" #include "SketchIndices.h" #include "Point.h" #include "LineData.h" @@ -23,7 +23,7 @@ //! Returns a list of the different Regions in labels, sorted by area //@param labels Each different region in labels should have a different number assigned to it //@param area_thresh Minimum allowed area of a region - static std::list extractRegions(const Sketch& labels, int area_thresh = 10); + static std::list extractRegions(const Sketch& labels, uint area_thresh = 10); //! Return a single region from a sketch static Region extractRegion(const Sketch& sketch); @@ -48,7 +48,7 @@ Point findBotBoundPoint(); Point findLeftBoundPoint(); Point findRightBoundPoint(); - bool isContained(const Point&, const int max_dist=0); + bool isContained(const Point&, const uint max_dist=0); Point mostDistantPtFrom(const LineData&); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeAgent.h ./DualCoding/ShapeAgent.h --- ../Tekkotsu_3.0/DualCoding/ShapeAgent.h 2006-09-23 23:45:20.000000000 -0400 +++ ./DualCoding/ShapeAgent.h 2007-03-28 05:58:09.000000000 -0400 @@ -15,7 +15,7 @@ public: SHAPESTUFF_H(AgentData); - Shape(ShapeSpace &s, Point centerval=Point(0,0,0)) : + Shape(ShapeSpace &s, Point centerval=Point(0,0,0,allocentric)) : ShapeRoot(addShape(new AgentData(s,centerval))) { }; }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeEllipse.h ./DualCoding/ShapeEllipse.h --- ../Tekkotsu_3.0/DualCoding/ShapeEllipse.h 2006-09-23 23:45:20.000000000 -0400 +++ ./DualCoding/ShapeEllipse.h 2007-04-06 22:18:33.000000000 -0400 @@ -11,6 +11,7 @@ class Point; class Region; +//! Smart pointer to an @a EllipseData object template<> class Shape : public ShapeRoot { public: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeFuns.h ./DualCoding/ShapeFuns.h --- ../Tekkotsu_3.0/DualCoding/ShapeFuns.h 2006-08-02 17:33:36.000000000 -0400 +++ ./DualCoding/ShapeFuns.h 2007-11-11 18:57:21.000000000 -0500 @@ -19,7 +19,7 @@ //! Create a new shape and make it visible in the SketchGUI #define NEW_SHAPE(_name, _type, _value) \ - Shape<_type> _name((_value)); \ + DualCoding::Shape<_type> _name((_value)); \ if ( _name.isValid() ) _name->V(#_name); //! Create a new shape but hide it from the SketchGUI @@ -29,96 +29,100 @@ //! Retrieve a shape based on its name #define GET_SHAPE(_name, _type, _shapevec) \ - Shape<_type> _name(find_shape<_type>(_shapevec,#_name)); + DualCoding::Shape<_type> _name(find_shape<_type>(_shapevec,#_name)); + +//! Retrieve a shape based on its name, but bind to a new name +#define GET_RENAMED(_new_name, _old_name, _type, _shapevec) \ + DualCoding::Shape<_type> _new_name(find_shape<_type>(_shapevec,#_old_name)); //! Create a new vector of shapes of the specified type #define NEW_SHAPEVEC(_name, _type, _value) \ - vector > _name((_value)); + std::vector > _name((_value)); //! Create a new vector of shapes of mixed type #define NEW_SHAPEROOTVEC(_name, _value) \ - vector _name((_value)); + std::vector _name((_value)); //! Iterate over the shapes in a vector; _var is the iterator #define SHAPEVEC_ITERATE(_shapesvec,_type,_var) \ - for ( std::vector >::iterator _var##_it = _shapesvec.begin(); \ + for ( std::vector >::iterator _var##_it = _shapesvec.begin(); \ _var##_it != _shapesvec.end(); _var##_it++ ) { \ - Shape<_type> &_var = *_var##_it; + DualCoding::Shape<_type> &_var = *_var##_it; //! Nested iteration over the shapes in a vector; _var2 begins one past _var1 #define SHAPENEXT_ITERATE(_shapesvec,_type,_var1,_var2) \ - for ( std::vector >::iterator _var2##_it = ++std::vector >::iterator(_var1##_it); \ + for ( std::vector >::iterator _var2##_it = ++std::vector >::iterator(_var1##_it); \ _var2##_it != _shapesvec.end(); _var2##_it++ ) { \ - Shape<_type> &_var2 = *_var2##_it; + DualCoding::Shape<_type> &_var2 = *_var2##_it; //! Iterate over a vector for shapes of mixed type #define SHAPEROOTVEC_ITERATE(_shapesvec,_var) \ - for ( std::vector::iterator _var##_it = _shapesvec.begin(); \ + for ( std::vector::iterator _var##_it = _shapesvec.begin(); \ _var##_it != _shapesvec.end(); _var##_it++ ) { \ - ShapeRoot &_var = *_var##_it; + DualCoding::ShapeRoot &_var = *_var##_it; #define END_ITERATE } //! Obsolete: Iterate over the shapes in a vector; _var is the iterator #define DO_SHAPEVEC(_shapesvec,_type,_var,_body) \ - for ( std::vector >::iterator _var##_it = _shapesvec.begin(); \ + for ( std::vector >::iterator _var##_it = _shapesvec.begin(); \ _var##_it != _shapesvec.end(); _var##_it++ ) { \ - Shape<_type> &_var = *_var##_it; \ + DualCoding::Shape<_type> &_var = *_var##_it; \ _body } \ //! Obsolete: nested iteration over the shapes in a vector; _var2 begins one past _var1 #define DO_SHAPENEXT(_shapesvec,_type,_var1,_var2,_body) \ - for ( std::vector >::iterator _var2##_it = ++std::vector >::iterator(_var1##_it); \ + for ( std::vector >::iterator _var2##_it = ++std::vector >::iterator(_var1##_it); \ _var2##_it != _shapesvec.end(); _var2##_it++ ) { \ - Shape<_type> &_var2 = *_var2##_it; \ + DualCoding::Shape<_type> &_var2 = *_var2##_it; \ _body } //! Obsolete: Iterate over a vector for shapes of mixed type #define DO_SHAPEROOTVEC(_shapesvec,_var,_body) \ - for ( std::vector::iterator _var##_it = _shapesvec.begin(); \ + for ( std::vector::iterator _var##_it = _shapesvec.begin(); \ _var##_it != _shapesvec.end(); _var##_it++ ) { \ - ShapeRoot &_var = *_var##_it; \ + DualCoding::ShapeRoot &_var = *_var##_it; \ _body } // ================================================================ //! Unary predicates over ShapeRoot objects -class UnaryShapeRootPred : public unary_function { +class UnaryShapeRootPred : public std::unary_function { public: virtual ~UnaryShapeRootPred() {} //!< virtual destructor to satisfy warning }; //! Binary predicates over ShapeRoot objects -class BinaryShapeRootPred : public binary_function { +class BinaryShapeRootPred : public std::binary_function { public: virtual ~BinaryShapeRootPred() {} //!< virtual destructor to satisfy warning }; //! Unary predicates over Shape objects template -class UnaryShapePred : public unary_function, bool> { +class UnaryShapePred : public std::unary_function, bool> { public: virtual ~UnaryShapePred() {} //!< virtual destructor to satisfy warning }; //! Binary predicates over Shape objects template -class BinaryShapePred : public binary_function, Shape, bool> { +class BinaryShapePred : public std::binary_function, Shape, bool> { public: virtual ~BinaryShapePred() {} //!< virtual destructor to satisfy warning }; // ================ Short-Circuit AND and OR -//! Classes for implementing shortcircuit And and Or predicates. Don't call directly; use andPred and orPred; use not1 for negation. +//! Classes for implementing shortcircuit And and Or predicates. Don't call directly; use AndPred and OrPred; use not1 for negation. //@{ template -class shortcircuit_and : public unary_function { +class shortcircuit_and : public std::unary_function { public: PredType1 p1; PredType2 p2; shortcircuit_and(PredType1 _p1, PredType2 _p2) : - unary_function(), p1(_p1), p2(_p2) {} + std::unary_function(), p1(_p1), p2(_p2) {} bool operator() (const typename PredType1::argument_type &shape) const { if ( p1(shape) ) return p2(shape); @@ -127,12 +131,12 @@ }; template -class shortcircuit_or : public unary_function { +class shortcircuit_or : public std::unary_function { public: PredType1 p1; PredType2 p2; shortcircuit_or(PredType1 _p1, PredType2 _p2) : - unary_function(), p1(_p1), p2(_p2) {} + std::unary_function(), p1(_p1), p2(_p2) {} bool operator() (const typename PredType1::argument_type &shape) const { if ( p1(shape) ) return true; @@ -143,7 +147,7 @@ /*! Templated functions can pick up type information from their arguments, but templated class constructors cannot; they expect type info to be supplied explicitly as template arguments in <>. So we - define andPred() and orPred() templated functions to pick up the + define AndPred() and OrPred() templated functions to pick up the type info and pass it on to the shortcircuit_and and shortcircuit_or constructors as explicit template arguments. The built-in function adaptors not1 and not2 already use this trick for negation. */ @@ -152,13 +156,13 @@ //! Conjunction of two predicates; p2 is called only if p1 returns true template -shortcircuit_and andPred(PredType1 p1, PredType2 p2) { +shortcircuit_and AndPred(PredType1 p1, PredType2 p2) { return shortcircuit_and(p1,p2); } //! Disjunction of two predicates; p2 is called only if p1 returns false template -shortcircuit_or orPred(PredType1 p1, PredType2 p2) { +shortcircuit_or OrPred(PredType1 p1, PredType2 p2) { return shortcircuit_or(p1,p2); } @@ -166,28 +170,28 @@ // ================ Unary ShapeRoot predicates -class isType : public UnaryShapeRootPred { +class IsType : public UnaryShapeRootPred { public: ShapeType_t type; - explicit isType(ShapeType_t _type) : UnaryShapeRootPred(), type(_type) {} + explicit IsType(ShapeType_t _type) : UnaryShapeRootPred(), type(_type) {} bool operator()(const ShapeRoot &shape) const { return shape->getType() == type; } }; -class isColor : public UnaryShapeRootPred { +class IsColor : public UnaryShapeRootPred { public: rgb color; - explicit isColor(int colorIndex) : UnaryShapeRootPred(), color(ProjectInterface::getColorRGB(colorIndex)) {} - explicit isColor(rgb _color) : UnaryShapeRootPred(), color(_color) {} - explicit isColor(std::string const &_colorname) : UnaryShapeRootPred(), color(ProjectInterface::getColorRGB(_colorname)) {} + explicit IsColor(int colorIndex) : UnaryShapeRootPred(), color(ProjectInterface::getColorRGB(colorIndex)) {} + explicit IsColor(rgb _color) : UnaryShapeRootPred(), color(_color) {} + explicit IsColor(std::string const &_colorname) : UnaryShapeRootPred(), color(ProjectInterface::getColorRGB(_colorname)) {} bool operator()(const ShapeRoot &shape) const { return shape->getColor() == color; } }; -class isName : public UnaryShapeRootPred { +class IsName : public UnaryShapeRootPred { public: std::string name; - explicit isName(std::string _name) : UnaryShapeRootPred(), name(_name) {} + explicit IsName(std::string _name) : UnaryShapeRootPred(), name(_name) {} bool operator()(const ShapeRoot &shape) const { // return strcmp(shape->getName().c_str(),name.c_str()) == 0; } return shape->getName() == name; } @@ -195,19 +199,51 @@ // ================ find_if, find_shape, subset, max_element, stable_sort, etc. +//! Find a ShapeRoot satisfying pred +template +ShapeRoot find_if(const std::vector &vec, PredType pred) { + typename std::vector::const_iterator result = find_if(vec.begin(),vec.end(),pred); + if ( result != vec.end() ) + return *result; + else + return ShapeRoot(); +} + +//! Find a Shape in a vector of ShapeRoot satisfying pred template -Shape find_if(const vector > &vec, PredType pred) { - typename vector >::const_iterator result = find_if(vec.begin(),vec.end(),pred); +Shape find_if(const std::vector &vec, PredType pred) { + shortcircuit_and tpred(AndPred(IsType(T::getStaticType()),pred)); + typename std::vector::const_iterator result = find_if(vec.begin(),vec.end(),tpred); + if ( result != vec.end() ) + return ShapeRootTypeConst(*result,T); + else + return Shape(); +} + +//! Find a Shape satisfying pred +template +Shape find_if(const std::vector > &vec, PredType pred) { + typename std::vector >::const_iterator result = find_if(vec.begin(),vec.end(),pred); if ( result != vec.end() ) return *result; else return Shape(); } +//! Find a Shape in a vector of ShapeRoot +template +Shape find_if(const std::vector &vec) { + typename std::vector::const_iterator result = find_if(vec.begin(),vec.end(),IsType(T::getStaticType())); + if ( result != vec.end() ) + return ShapeRootTypeConst(*result,T); + else + return Shape(); +} + //! Return the first ShapeRoot with the specified name, else return an invalid ShapeRoot template -Shape find_shape(const vector &vec, const std::string &name) { - for ( vector::const_iterator it = vec.begin(); +Shape find_shape(const std::vector &vec, const std::string &name) { + for ( std::vector::const_iterator it = vec.begin(); it != vec.end(); it++ ) if ( (*it)->getType() == T::getStaticType() && (*it)->getName() == name ) return ShapeRootTypeConst(*it,T); @@ -219,13 +255,14 @@ std::vector > select_type(std::vector &vec) { std::vector > result(vec.size()); result.clear(); - isType tpred(T::getStaticType()); + IsType tpred(T::getStaticType()); DO_SHAPEROOTVEC(vec, element, { if ( tpred(element) ) result.push_back(reinterpret_cast&>(element)); }); return result; } +//! Find all elements in a vector of Shape satisfying pred template std::vector > subset(const std::vector > &vec, PredType pred) { std::vector > result; @@ -235,21 +272,56 @@ return result; } +//! Find all elements in a vector of ShapeRoot satisfying pred +template +std::vector subset(const std::vector &vec, PredType pred) { + std::vector result; + remove_copy_if(vec.begin(), vec.end(), + std::back_insert_iterator >(result), + not1(pred)); + return result; +} + +//! Find all elements of type T in a vector of ShapeRoot satisfying pred +template +std::vector subset(const std::vector &vec, PredType pred) { + std::vector > result; + shortcircuit_and tpred(AndPred(IsType(T::getStaticType()),pred)); + remove_copy_if(vec.begin(), vec.end(), + std::back_insert_iterator > >(result), + not1(tpred)); + return result; +} + template -Shape max_element(const vector > &vec, ComparisonType comp) { - typename vector >::const_iterator result = max_element(vec.begin(),vec.end(),comp); +Shape max_element(const std::vector > &vec, ComparisonType comp) { + typename std::vector >::const_iterator result = max_element(vec.begin(),vec.end(),comp); if ( result != vec.end() ) return *result; else return Shape(); } +template +ShapeRoot max_element(const std::vector &vec, ComparisonType comp) { + typename std::vector::const_iterator result = max_element(vec.begin(),vec.end(),comp); + if ( result != vec.end() ) + return *result; + else + return ShapeRoot(); +} + template -Shape min_element(const vector > &vec, ComparisonType comp) { +Shape min_element(const std::vector > &vec, ComparisonType comp) { return max_element(vec, not2(comp)); } +template +ShapeRoot min_element(const std::vector &vec, ComparisonType comp) { + return max_element(vec, not2(comp)); +} + template std::vector > stable_sort(const std::vector > &vec, PredType pred) { std::vector > result(vec); @@ -257,11 +329,18 @@ return result; } +template +std::vector stable_sort(const std::vector &vec, PredType pred) { + std::vector result(vec); + stable_sort(result.begin(), result.end(), pred); + return result; +} + // ================ IsLeftOf / IsRightOf / IsAbove / IsBelow // ================ IsLeftOfThis / IsRightOfThis / IsAboveThis / IsBelowThis // -// To enforce consistency, predicates are defined in pairs: isRightOf(x,y) -// is defined as isLeftOf(y,x). +// To enforce consistency, predicates are defined in pairs: IsRightOf(x,y) +// is defined as IsLeftOf(y,x). #define DIRECTION_PAIR(dir, oppdir) \ class Is##dir : public BinaryShapeRootPred { \ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeLine.h ./DualCoding/ShapeLine.h --- ../Tekkotsu_3.0/DualCoding/ShapeLine.h 2006-09-23 23:45:20.000000000 -0400 +++ ./DualCoding/ShapeLine.h 2007-04-06 22:18:33.000000000 -0400 @@ -2,7 +2,7 @@ #ifndef _SHAPELINE_H_ #define _SHAPELINE_H_ -#include "Measures.h" +#include "Shared/Measures.h" #include "ShapeRoot.h" #include "LineData.h" @@ -11,6 +11,7 @@ class ShapeSpace; class Point; +//! Smart pointer to a @a LineData object template<> class Shape : public ShapeRoot { public: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeLocalizationParticle.cc ./DualCoding/ShapeLocalizationParticle.cc --- ../Tekkotsu_3.0/DualCoding/ShapeLocalizationParticle.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/ShapeLocalizationParticle.cc 2007-02-19 06:22:14.000000000 -0500 @@ -0,0 +1,14 @@ +//-*-c++-*- +#include + +using namespace std; + +#include "SketchSpace.h" + +#include "ShapeLocalizationParticle.h" + +namespace DualCoding { + +SHAPESTUFF_CC(LocalizationParticleData); + +} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeLocalizationParticle.h ./DualCoding/ShapeLocalizationParticle.h --- ../Tekkotsu_3.0/DualCoding/ShapeLocalizationParticle.h 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/ShapeLocalizationParticle.h 2007-02-20 19:51:59.000000000 -0500 @@ -0,0 +1,19 @@ +//-*-c++-*- +#ifndef _SHAPELOCALIZATIONPARTICLE_H_ +#define _SHAPELOCALIZATIONPARTICLE_H_ + +#include "ShapeRoot.h" +#include "LocalizationParticleData.h" + +namespace DualCoding { + +template<> +class Shape : public ShapeRoot { +public: + SHAPESTUFF_H(LocalizationParticleData); // defined in ShapeRoot.h + +}; + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeRoot.cc ./DualCoding/ShapeRoot.cc --- ../Tekkotsu_3.0/DualCoding/ShapeRoot.cc 2006-09-23 23:45:21.000000000 -0400 +++ ./DualCoding/ShapeRoot.cc 2007-11-12 23:16:01.000000000 -0500 @@ -8,6 +8,8 @@ #include "BaseData.h" +using namespace std; + namespace DualCoding { ShapeRoot::ShapeRoot(BaseData *p) : id(p->getId()), data(p) { @@ -86,7 +88,7 @@ << r.id << ", data=" << r.data << ")"; } else { - cout << "Shape(id=" << r.getId() << ",data=" << (unsigned int)r.data << ")[invalid]"; + cout << "Shape(id=" << r.getId() << ",data=" << reinterpret_cast(r.data) << ")[invalid]"; } return os; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeRoot.h ./DualCoding/ShapeRoot.h --- ../Tekkotsu_3.0/DualCoding/ShapeRoot.h 2006-09-23 23:45:21.000000000 -0400 +++ ./DualCoding/ShapeRoot.h 2007-04-06 22:18:33.000000000 -0400 @@ -10,10 +10,10 @@ namespace DualCoding { -//! Parent class for all Shape +//! Parent class for all Shape objects /*! Shape points to data objects of type T within a ShapeSpace, e.g., - Shape points to a LineData object. + @a Shape points to a @a LineData object. Creating a Shape registers the data object in the ShapeSpace and sets the refcount to 1. Copying a shape increments the refcount, and deleting diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeSpace.cc ./DualCoding/ShapeSpace.cc --- ../Tekkotsu_3.0/DualCoding/ShapeSpace.cc 2006-09-23 23:45:21.000000000 -0400 +++ ./DualCoding/ShapeSpace.cc 2007-11-11 18:57:21.000000000 -0500 @@ -2,6 +2,8 @@ #include #include #include +#include +#include #include "Shared/newmat/newmat.h" #include "Shared/newmat/newmatio.h" @@ -16,20 +18,23 @@ #include "ShapePolygon.h" #include "ShapeBrick.h" #include "ShapePyramid.h" +#include "ShapeLocalizationParticle.h" #include "BaseData.h" #include "SketchSpace.h" #include "ShapeSpace.h" #include "VRmixin.h" +using namespace std; + namespace DualCoding { -ShapeSpace::ShapeSpace(SketchSpace* dualSkS, int init_id, string const _name, +ShapeSpace::ShapeSpace(SketchSpace* dualSkS, int init_id, std::string const _name, ReferenceFrameType_t _refFrameType) : name(_name.length() == 0 ? dualSkS->name : _name), dualSpace(dualSkS), id_counter(init_id), shapeCache(), refFrameType(_refFrameType) { - shapeCache = vector(30); + shapeCache = std::vector(30); shapeCache.clear(); } @@ -44,8 +49,8 @@ return shapeCache[shapeCache.size()-1]; }; -void ShapeSpace::importShapes(vector& foreign_shapes) { - for (vector::const_iterator it = foreign_shapes.begin(); +void ShapeSpace::importShapes(std::vector& foreign_shapes) { + for (std::vector::const_iterator it = foreign_shapes.begin(); it != foreign_shapes.end(); ++it) importShape(*it); } @@ -62,7 +67,7 @@ void ShapeSpace::deleteShape(ShapeRoot &b) { if ( b.isValid() ) - for ( vector::iterator it = shapeCache.begin(); + for ( std::vector::iterator it = shapeCache.begin(); it != shapeCache.end(); ++it ) { if ( it->id == b.id ) { shapeCache.erase(it); @@ -73,7 +78,7 @@ std::cerr << "ERROR: Attempt to delete an invalid " << b << std::endl; } -void ShapeSpace::deleteShapes(vector& shapes_vec) { +void ShapeSpace::deleteShapes(std::vector& shapes_vec) { for (size_t i=0; i < shapes_vec.size(); i++) deleteShape(shapes_vec[i]); } @@ -84,19 +89,19 @@ shapeCache.push_back(VRmixin::theAgent); } -void ShapeSpace::applyTransform(const NEWMAT::Matrix& Tmat) { - vector allShapes_vec = allShapes(); +void ShapeSpace::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + std::vector allShapes_vec = allShapes(); const size_t nshapes = allShapes_vec.size(); for(size_t i = 0; i < nshapes; i++) - allShapes_vec[i]->applyTransform(Tmat); + allShapes_vec[i]->applyTransform(Tmat,newref); } Point ShapeSpace::getCentroid() { - vector allShapes_vec = allShapes(); + std::vector allShapes_vec = allShapes(); return(getCentroidOfSubset(allShapes_vec)); } -Point ShapeSpace::getCentroidOfSubset(const vector& subsetShapes_vec) { +Point ShapeSpace::getCentroidOfSubset(const std::vector& subsetShapes_vec) { const size_t nshapes = subsetShapes_vec.size(); Point subset_centroid_pt = Point(0,0); for(size_t cur_shape = 0; cur_shape < nshapes; cur_shape++) @@ -124,9 +129,9 @@ return result; } -string ShapeSpace::getShapeListForGUI(void) { - vector &allShapes_vec = allShapes(); - ostringstream liststream; +std::string ShapeSpace::getShapeListForGUI(void) { + std::vector &allShapes_vec = allShapes(); + std::ostringstream liststream; #define writept(x) x.coordX() << " " << x.coordY() << " " << x.coordZ() for(unsigned int i = 0; i < allShapes_vec.size(); i++) { if ( allShapes_vec[i]->isViewable() ) { @@ -135,7 +140,7 @@ liststream << "parentId: " << allShapes_vec[i]->getParentId() << endl; liststream << "name: " << allShapes_vec[i]->getName() << endl; liststream << "shapetype: " << allShapes_vec[i]->getType() << endl; - liststream << "color: " << ProjectInterface::toString(allShapes_vec[i]->getColor()) << endl; + liststream << "color: " << toString(allShapes_vec[i]->getColor()) << endl; liststream << "cxyz: " << writept(allShapes_vec[i]->getCentroid()) << endl; if(allShapes_vec[i]->isType(lineDataType)) { // lineshape @@ -175,7 +180,7 @@ else if (allShapes_vec[i]->isType(polygonDataType)) { // polygonshape const Shape& current = ShapeRootTypeConst(allShapes_vec[i],PolygonData); liststream << "num_vtx: " << current->getVertices().size() << endl; - for (vector::const_iterator vtx_it = current->getVertices().begin(); + for (std::vector::const_iterator vtx_it = current->getVertices().begin(); vtx_it != current->getVertices().end(); vtx_it++) liststream << "vertex: " << writept((*vtx_it)) << endl; liststream << "end1_valid: " << (current->end1Ln().end1Pt().isValid()) << endl; @@ -210,20 +215,24 @@ liststream << "BR: " << writept(current->getBR()) << endl; liststream << "Top: " << writept(current->getTop()) << endl; } - } + else if (allShapes_vec[i]->isType(localizationParticleDataType)) { // localizationparticleshape + const Shape& current = ShapeRootTypeConst(allShapes_vec[i],LocalizationParticleData); + const float weight = current->getWeight(); + liststream << "orient/weight: " << current->getOrientation() + << " " << (!finite(weight) ? (weight>0 ? FLT_MAX : -FLT_MAX) : weight) << endl; + } + } } #undef writept return liststream.str(); } -void -ShapeSpace::printParams() -{ +void ShapeSpace::printParams() { cout << endl; cout << "SHAPE SPACE : PARAMETERS BEGIN" << endl; int cur, num; - vector &allShapes_vec = allShapes(); + std::vector &allShapes_vec = allShapes(); num = (int)(allShapes_vec.size()); for(cur = 0; cur < num; cur++) { @@ -243,17 +252,14 @@ cout << "SHAPE SPACE : PARAMETERS END" << endl; } - - -void -ShapeSpace::printSummary() +void ShapeSpace::printSummary() { // JJW will this cause a memory leak? - vector allShapes_vec = allShapes(); + std::vector allShapes_vec = allShapes(); int cur; int num = (int)(allShapes_vec.size()); cout << "SHAPE SPACE : SUMMARY BEGIN" << endl; - vector shape_counts; + std::vector shape_counts; shape_counts.resize(numDataTypes,0); cout << endl << "Shape Listing:" << endl; @@ -276,4 +282,14 @@ cout << "SHAPE SPACE : SUMMARY END" << endl; } +void ShapeSpace::deleteShapeType(ShapeType_t t) { + std::vector temp; + temp.reserve(shapeCache.size()); + for ( std::vector::const_iterator it = shapeCache.begin(); + it != shapeCache.end(); it++ ) + if ( (*it)->getType() != t ) + temp.push_back(*it); + shapeCache = temp; +} + } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeSpace.h ./DualCoding/ShapeSpace.h --- ../Tekkotsu_3.0/DualCoding/ShapeSpace.h 2006-09-23 23:45:21.000000000 -0400 +++ ./DualCoding/ShapeSpace.h 2007-11-11 18:57:21.000000000 -0500 @@ -8,7 +8,7 @@ #include "Vision/colors.h" #include "Shared/newmat/newmat.h" -#include "Measures.h" +#include "Shared/Measures.h" #include "ShapeTypes.h" namespace DualCoding { @@ -36,19 +36,19 @@ // friend class WorldMapBuilder; public: - string name; //!< Name of the ShapeSpace + std::string name; //!< Name of the ShapeSpace private: SketchSpace* dualSpace; int id_counter; - vector shapeCache; + std::vector shapeCache; ShapeRoot& addShape(BaseData* p); ReferenceFrameType_t refFrameType; public: //! Constructor for ShapeSpace; requires dual SketchSpace. - ShapeSpace(SketchSpace* dualSkS, int init_id=70000, string const _name="", + ShapeSpace(SketchSpace* dualSkS, int init_id=70000, std::string const _name="", ReferenceFrameType_t _refFrameType=camcentric); ~ShapeSpace(void); @@ -61,6 +61,7 @@ void deleteShape(ShapeRoot &b); void deleteShapes(std::vector& shapes_vec); + template void deleteShapes() { deleteShapeType(T::getStaticType()); } void clear(); @@ -82,7 +83,7 @@ //! Transformation and Location Utilities //@{ - void applyTransform(const NEWMAT::Matrix& Tmat); + void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); Point getCentroid(void); @@ -92,6 +93,7 @@ private: ShapeSpace(const ShapeSpace&); //!< never call this ShapeSpace& operator=(const ShapeSpace&); //!< never call this + void deleteShapeType(ShapeType_t type); }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeTarget.cc ./DualCoding/ShapeTarget.cc --- ../Tekkotsu_3.0/DualCoding/ShapeTarget.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/ShapeTarget.cc 2007-04-23 17:44:46.000000000 -0400 @@ -0,0 +1,9 @@ +//-*-c++-*- + +#include "ShapeTarget.h" + +namespace DualCoding { + +SHAPESTUFF_CC(TargetData); // defined in ShapeRoot.h + +} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeTarget.h ./DualCoding/ShapeTarget.h --- ../Tekkotsu_3.0/DualCoding/ShapeTarget.h 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/ShapeTarget.h 2007-04-23 17:44:46.000000000 -0400 @@ -0,0 +1,30 @@ +//-*-c++-*- +#ifndef _SHAPETARGET_H_ +#define _SHAPETARGET_H_ + +#include "ShapeRoot.h" +#include "TargetData.h" + +namespace DualCoding { + +class ShapeSpace; +class Point; +class EndPoint; + +template<> +class Shape : public ShapeRoot { +public: + SHAPESTUFF_H(TargetData); // defined in ShapeRoot.h + + //! Make a target from a point, two end points, and a height + Shape(ShapeSpace &s, const EndPoint &frontLeftPt, const EndPoint &frontRightPt, const EndPoint &backLeftPt, const EndPoint &backRightPt, const EndPoint &frontIntersect, const EndPoint &backIntersect, const float height) + : ShapeRoot(addShape(new TargetData(s, frontLeftPt, frontRightPt, backLeftPt, backRightPt, frontIntersect, backIntersect, height))) {} + + //! Copy constructor. + Shape(const TargetData& newData) : ShapeRoot(addShape(new TargetData(newData))) {} + +}; + +} // namespace + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeTypes.cc ./DualCoding/ShapeTypes.cc --- ../Tekkotsu_3.0/DualCoding/ShapeTypes.cc 2006-07-21 13:57:56.000000000 -0400 +++ ./DualCoding/ShapeTypes.cc 2007-04-23 17:44:46.000000000 -0400 @@ -34,6 +34,12 @@ case pyramidDataType: return("PyramidData"); break; + case localizationParticleDataType: + return("LocalizationParticleData"); + break; + case targetDataType: + return("TargetData"); + break; case unknownDataType: default: return("*Unknown*"); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ShapeTypes.h ./DualCoding/ShapeTypes.h --- ../Tekkotsu_3.0/DualCoding/ShapeTypes.h 2006-08-02 17:36:43.000000000 -0400 +++ ./DualCoding/ShapeTypes.h 2007-04-23 17:44:46.000000000 -0400 @@ -24,6 +24,8 @@ blobDataType, brickDataType, pyramidDataType, + localizationParticleDataType, + targetDataType, // this one must always come last numDataTypes diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Sketch.cc ./DualCoding/Sketch.cc --- ../Tekkotsu_3.0/DualCoding/Sketch.cc 2006-02-22 21:26:33.000000000 -0500 +++ ./DualCoding/Sketch.cc 2007-08-24 21:49:15.000000000 -0400 @@ -37,22 +37,22 @@ // DEF_MATHOPS(bool, bool, bool) disallowed because valarray doesn't provide arithmetic DEF_MATHOPS_CC(bool, uchar, uchar) -DEF_MATHOPS_CC(bool, usint, usint) +DEF_MATHOPS_CC(bool, uint, uint) DEF_MATHOPS_CC(bool, float, float) DEF_MATHOPS_CC(uchar, bool, uchar) DEF_MATHOPS_CC(uchar, uchar, uchar) -DEF_MATHOPS_CC(uchar, usint, usint) +DEF_MATHOPS_CC(uchar, uint, uint) DEF_MATHOPS_CC(uchar, float, float) -DEF_MATHOPS_CC(usint, bool, usint) -DEF_MATHOPS_CC(usint, uchar, usint) -DEF_MATHOPS_CC(usint, usint, usint) -DEF_MATHOPS_CC(usint, float, float) +DEF_MATHOPS_CC(uint, bool, uint) +DEF_MATHOPS_CC(uint, uchar, uint) +DEF_MATHOPS_CC(uint, uint, uint) +DEF_MATHOPS_CC(uint, float, float) DEF_MATHOPS_CC(float, bool, float) DEF_MATHOPS_CC(float, uchar, float) -DEF_MATHOPS_CC(float, usint, float) +DEF_MATHOPS_CC(float, uint, float) DEF_MATHOPS_CC(float, float, float) #undef DEF_MATHOPS_CC @@ -73,7 +73,7 @@ //DEF_MATHOPS_INT(bool, uchar) disallowed because valarray won't mix types DEF_MATHOPS_INT_CC(uchar) -DEF_MATHOPS_INT_CC(usint) +DEF_MATHOPS_INT_CC(uint) DEF_MATHOPS_INT_CC(float) #undef DEF_MATHOPS_INT_CC @@ -133,4 +133,9 @@ return arg1; } +Sketch& operator^= (Sketch& arg1, Sketch const& arg2) { + *(arg1.pixels) ^= *(arg2.pixels); + return arg1; +} + } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Sketch.h ./DualCoding/Sketch.h --- ../Tekkotsu_3.0/DualCoding/Sketch.h 2006-08-10 23:16:57.000000000 -0400 +++ ./DualCoding/Sketch.h 2007-08-24 21:49:15.000000000 -0400 @@ -67,7 +67,7 @@ T& operator[] (size_t idx) { checkValid(); return (*pixels)[idx]; }; const T& operator[] (size_t idx) const { checkValid(); return (*pixels)[idx]; }; //! when passed indirection matrix (e.g. idx_left) returns resampled Sketch - const Sketch operator[] (const Sketch& indirection) const; + const Sketch operator[] (const Sketch& indirection) const; T& operator() (size_t x, size_t y) { checkValid(); return (*pixels)[y*width + x]; }; const T& operator() (size_t x, size_t y) const { checkValid(); return (*pixels)[y*width + x]; }; @@ -108,8 +108,8 @@ //! operator for implicity or explicitly converting to Sketch operator Sketch() const; - //! operator for implicity or explicitly converting to Sketch - operator Sketch() const; + //! operator for implicity or explicitly converting to Sketch + operator Sketch() const; //! operator for implicity or explicitly converting to Sketch operator Sketch() const; @@ -135,7 +135,7 @@ template Sketch::Sketch(SketchSpace &_space, const std::string &_name) : SketchRoot(), width(_space.getWidth()), height(_space.getHeight()), - data(_space.get_pool(*this).get_free_element()), + data(_space.get_pool(*this).getFreeElement()), pixels(&data->pixels) { data->name = _name; @@ -160,10 +160,10 @@ SketchSpace& space = _parent.rootGetSpace(); width = space.getWidth(); height = space.getHeight(); - data = space.get_pool(*this).get_free_element(); + data = space.get_pool(*this).getFreeElement(); data->name = _name; data->id = getNewId(); - data->inheritFrom(_parent.rootGetData()); + data->inheritFrom(*_parent.rootGetData()); data->viewable = false; ++data->refcount; pixels = &data->pixels; @@ -223,7 +223,8 @@ if ( isValid() ) { ++data->refcount; data->setName(name); - data->setViewable(viewable); + if ( viewable ) + data->setViewable(viewable); } } @@ -236,14 +237,12 @@ << " [" << data << "]" << " id=" << getId() << ",parent=" << getParentId() << ",viewable=" << isViewable() - << ",refcount=" << data->refcount; - */ - if ( --data->refcount == 0 && ! data->viewable && data->refreshTag < data->space->getRefreshCounter() ) { - data->clearPending = false; - } - /* - std::cout << ",newrefcount=" << data->refcount << std::endl; + << ",refcount=" << data->refcount << std::endl; */ + --data->refcount; + if ( data->refcount == 0 && ! data->viewable && data->refreshTag < data->space->getRefreshCounter() ) { + data->clearPending = false; + } } } @@ -256,7 +255,7 @@ // Parallel indexed access via operator[] template -const Sketch Sketch::operator[] (const Sketch& indirection) const +const Sketch Sketch::operator[] (const Sketch& indirection) const { checkValid(); Sketch result(*(data->space), "shift("+(*this)->getName()+","+indirection->getName()+")"); @@ -289,9 +288,10 @@ template Sketch& Sketch::operator= (const Sketch& other) { if ( isValid() ) - if ( other.isValid() ) - *pixels = *other.pixels; - else { + if ( other.isValid() ) { + *pixels = *other.pixels; // deep assignment copies the pixels + data->parentId = other.data->parentId; + } else { if ( --data->refcount == 0 && data->refreshTag < data->space->getRefreshCounter() ) { data->setViewable(false); data->clearPending = false; @@ -330,22 +330,22 @@ // DEF_MATHOPS_H(bool, bool, bool) disallowed because valarray doesn't provide arithmetic DEF_MATHOPS_H(bool, uchar, uchar) -DEF_MATHOPS_H(bool, usint, usint) +DEF_MATHOPS_H(bool, uint, uint) DEF_MATHOPS_H(bool, float, float) DEF_MATHOPS_H(uchar, bool, uchar) DEF_MATHOPS_H(uchar, uchar, uchar) -DEF_MATHOPS_H(uchar, usint, usint) +DEF_MATHOPS_H(uchar, uint, uint) DEF_MATHOPS_H(uchar, float, float) -DEF_MATHOPS_H(usint, bool, usint) -DEF_MATHOPS_H(usint, uchar, usint) -DEF_MATHOPS_H(usint, usint, usint) -DEF_MATHOPS_H(usint, float, float) +DEF_MATHOPS_H(uint, bool, uint) +DEF_MATHOPS_H(uint, uchar, uint) +DEF_MATHOPS_H(uint, uint, uint) +DEF_MATHOPS_H(uint, float, float) DEF_MATHOPS_H(float, bool, float) DEF_MATHOPS_H(float, uchar, float) -DEF_MATHOPS_H(float, usint, float) +DEF_MATHOPS_H(float, uint, float) DEF_MATHOPS_H(float, float, float) #undef DEF_MATHOPS_H @@ -362,7 +362,7 @@ //DEF_MATHOPS_INT_H(bool, uchar) disallowed because valarray won't mix types DEF_MATHOPS_INT_H(uchar) -DEF_MATHOPS_INT_H(usint) +DEF_MATHOPS_INT_H(uint) DEF_MATHOPS_INT_H(float) #undef DEF_MATHOPS_INT_H @@ -428,6 +428,7 @@ DEFINE_LOGICAL_OPERATOR( >= ) DEFINE_LOGICAL_OPERATOR( & ) DEFINE_LOGICAL_OPERATOR( | ) + DEFINE_LOGICAL_OPERATOR( ^ ) #undef DEFINE_LOGICAL_OPERATOR //@} @@ -442,6 +443,7 @@ //@{ Sketch& operator&= (Sketch& arg1, Sketch const& arg2); Sketch& operator|= (Sketch& arg1, Sketch const& arg2); +Sketch& operator^= (Sketch& arg1, Sketch const& arg2); //@} template @@ -483,13 +485,13 @@ Sketch::operator Sketch() const; template -Sketch::operator Sketch() const { +Sketch::operator Sketch() const { /* std::cout << "Converting " << this << " '" << getName() << "'" << " id=" << getId() << ",parent=" << getParentId() << ",refcount=" << data->refcount - << " to Sketch\n"; + << " to Sketch\n"; */ - Sketch converted("usint("+(*this)->getName()+")", *this); + Sketch converted("uint("+(*this)->getName()+")", *this); copyPixels(converted, *this); return converted; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchData.h ./DualCoding/SketchData.h --- ../Tekkotsu_3.0/DualCoding/SketchData.h 2006-09-09 00:32:40.000000000 -0400 +++ ./DualCoding/SketchData.h 2007-08-24 21:49:16.000000000 -0400 @@ -117,7 +117,7 @@ template SketchData::SketchData(SketchSpace *_space) : SketchDataRoot(_space), pixels(_space->getNumPixels()+1) { - if ( getType() == sketchUsint || getType() == sketchFloat ) + if ( getType() == sketchUint || getType() == sketchFloat ) colormap = jetMapScaled; else colormap = segMap; @@ -134,7 +134,7 @@ template<> inline SketchType_t SketchData::getType() const { return sketchUchar; } template<> -inline SketchType_t SketchData::getType() const { return sketchUsint; } +inline SketchType_t SketchData::getType() const { return sketchUint; } template<> inline SketchType_t SketchData::getType() const { return sketchFloat; } @@ -284,8 +284,8 @@ unsigned int used=0; SKETCHDATA_ENCODE("TekkotsuImage"); - SKETCHDATA_ENCODE(Config::vision_config::ENCODE_SINGLE_CHANNEL); - SKETCHDATA_ENCODE(Config::vision_config::COMPRESS_NONE); + SKETCHDATA_ENCODE(Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL); + SKETCHDATA_ENCODE(Config::vision_config::RawCamConfig::COMPRESS_NONE); SKETCHDATA_ENCODE(getWidth()); SKETCHDATA_ENCODE(getHeight()); SKETCHDATA_ENCODE(get_time()); // is this what should be used for time stamp? @@ -303,7 +303,7 @@ SKETCHDATA_ENCODE((unsigned char)getType()); const unsigned int imglength = savePixels(buf,avail); if(imglength==0) - return 0; // savePixels should have already reported the error + return 0; // savePixels should have already reported the error avail-=imglength; buf+=imglength; @@ -316,10 +316,10 @@ template unsigned int SketchData::savePixels(char buf[], unsigned int avail) const { - const unsigned int imglength = getWidth() * getHeight() * sizeof(T); - ASSERTRETVAL(imglength inline unsigned int SketchData::savePixels(char buf[], unsigned int avail) const { - const unsigned int imglength = getWidth() * getHeight() * sizeof(char); - ASSERTRETVAL(imglength& indirection) const { +const SketchIndices SketchIndices::operator[] (const Sketch& indirection) const { SketchIndices redir; for (CI it = table.begin(); it != table.end(); ++it) redir.table.insert(indirection[*it]); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchIndices.h ./DualCoding/SketchIndices.h --- ../Tekkotsu_3.0/DualCoding/SketchIndices.h 2006-04-27 18:53:10.000000000 -0400 +++ ./DualCoding/SketchIndices.h 2007-11-11 18:57:21.000000000 -0500 @@ -3,9 +3,7 @@ #define INCLUDED_SketchIndices_h #include // forward declaration for ostream - #include -using namespace __gnu_cxx; // is this safe? seems to be needed for hash_set #include "SketchTypes.h" @@ -17,7 +15,7 @@ //! Table of indices of sketch elements; parent of the Region class class SketchIndices { public: - typedef hash_set, equal_to > SketchIndicesTable; + typedef __gnu_cxx::hash_set, std::equal_to > SketchIndicesTable; typedef SketchIndicesTable::const_iterator CI; SketchIndicesTable table; @@ -30,7 +28,7 @@ //! Operator for indirection based on passed in Sketch. //! Returns a new SketchIndices based on applying the indirection. - const SketchIndices operator[] (const Sketch& indirection) const; + const SketchIndices operator[] (const Sketch& indirection) const; //! Returns the result of adding the elements of another SketchIndices //! to the current SketchIndices diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchPool.h ./DualCoding/SketchPool.h --- ../Tekkotsu_3.0/DualCoding/SketchPool.h 2006-07-23 05:40:31.000000000 -0400 +++ ./DualCoding/SketchPool.h 2007-11-11 18:57:21.000000000 -0500 @@ -6,8 +6,6 @@ #include #include // for ostringstream -#include "Shared/ProjectInterface.h" - #include "SketchPoolRoot.h" #include "Macrodefs.h" @@ -25,14 +23,19 @@ //! this is made public so VisualRoutinesBehavior can access std::vector*> elements; - SketchPool(SketchSpace *_space, int poolsize = 0); + //! Constructor + SketchPool(SketchSpace *_space, const std::string& _name, int poolsize = 0); + //! Destructor ~SketchPool(); - //! called by SketchPool to clear out non-static Viewable Sketch's + //! Delete all sketches in the pool; commplain if refcount nonzero. Used by destructor and by SketchSpace::resize() + void deleteElements(); + + //! Make all sketches non-viewable, hence reclaimable when refcount drops to zero void clear(); - SketchData* get_free_element(void); + SketchData* getFreeElement(void); SketchData* findSketchData(const std::string &name); @@ -55,9 +58,9 @@ // **************** Implementation **************** template -SketchPool::SketchPool(SketchSpace *_space, int poolsize) : - SketchPoolRoot(_space), - elements(std::vector*>(poolsize)) +SketchPool::SketchPool(SketchSpace *_space, const std::string& _name, int poolsize) : + SketchPoolRoot(_space,_name), + elements(std::vector*>(poolsize)) { for (int i=0; i(space); @@ -66,13 +69,18 @@ template SketchPool::~SketchPool() { - for (unsigned int i = 0; i < elements.size(); i++) { + deleteElements(); +} + +template +void SketchPool::deleteElements() { + for (unsigned int i = 0; i < elements.size(); i++) if(elements[i]->refcount > 0) printf("ERROR in ~SketchPool: Element %d [%p] has ref_count == %d != 0\n", - i,elements[i],elements[i]->refcount); + i,elements[i],elements[i]->refcount); else delete elements[i]; - } + elements.clear(); } template @@ -86,20 +94,19 @@ << " viewable=" << (*it)->viewable << " clrpend=" << (*it)->clearPending << endl; */ - if ( (*it)->refcount == 0 && (*it)->refreshTag < getRefreshCounter() ) { - (*it)->setViewable(false); + (*it)->setViewable(false); + if ( (*it)->refreshTag < getRefreshCounter() ) (*it)->clearPending = false; - } else (*it)->clearPending = true; } } template -SketchData* SketchPool::get_free_element(void) +SketchData* SketchPool::getFreeElement(void) { for (CI it = elements.begin(); it != elements.end(); it++ ) { - if ( (*it)->refcount == 0 && (*it)->viewable == false ) + if ( (*it)->refcount == 0 && (*it)->viewable == false && (*it)->clearPending == false ) return *it; else if ( (*it)->refcount < 0 ) std::cerr << "PROBLEM: negative refcount" << std::endl; @@ -110,9 +117,9 @@ } template -SketchData* SketchPool::findSketchData(const std::string &name) { +SketchData* SketchPool::findSketchData(const std::string &sketchname) { for (CI it = elements.begin(); it != elements.end(); it++ ) - if ( (*it)->name == name ) + if ( (*it)->refcount > 0 && (*it)->name == sketchname ) return *it; return NULL; } @@ -134,7 +141,7 @@ liststream << "parentId:" << (elements[i])->parentId << std::endl; liststream << "name:" << (elements[i])->name << std::endl; liststream << "sketchtype:" << elements[i]->getType() << std::endl; - liststream << "color:" << ProjectInterface::toString(elements[i]->color) << std::endl; + liststream << "color:" << toString(elements[i]->color) << std::endl; liststream << "colormap:" << elements[i]->colormap << std::endl; } } @@ -151,15 +158,19 @@ } template -void SketchPool::dumpPool() const -{ - printf("%4s %2s %4s %4s\n", "num", "rf", "id", "pid"); - for(unsigned int i = 0; i < elements.size(); i++) { - if((elements[i])->refcount > 0) { - printf("%4d %2d %4d %4d\n", i, (elements[i])->refcount, - (elements[i])->id, (elements[i])->parentId); - } - } +void SketchPool::dumpPool() const { + printf("%4s %2s %4s %5s %3s %2s (%s)\n", + "num", "rf", "id", "pid","vis","cp", + (getSpaceName()+"."+getName()).c_str()); + for(unsigned int i = 0; i < elements.size(); i++) + printf("%4d %2d %4d %5d %1c %1c %s\n", + i, + (elements[i])->refcount, + (elements[i])->id, + (elements[i])->parentId, + (elements[i])->viewable ? 'y' : 'n', + (elements[i])->clearPending ? 'y' : 'n', + (elements[i])->name.c_str()); } } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchPoolRoot.cc ./DualCoding/SketchPoolRoot.cc --- ../Tekkotsu_3.0/DualCoding/SketchPoolRoot.cc 2006-05-09 18:37:56.000000000 -0400 +++ ./DualCoding/SketchPoolRoot.cc 2007-11-11 18:57:21.000000000 -0500 @@ -2,12 +2,18 @@ #include "SketchSpace.h" +using namespace std; + namespace DualCoding { SketchPoolRoot::~SketchPoolRoot() {} -int SketchPoolRoot::getRefreshCounter() { - return space->getRefreshCounter(); +int SketchPoolRoot::getRefreshCounter() const { + return space->getRefreshCounter(); +} + +const std::string& SketchPoolRoot::getSpaceName() const { + return space->name; } } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchPoolRoot.h ./DualCoding/SketchPoolRoot.h --- ../Tekkotsu_3.0/DualCoding/SketchPoolRoot.h 2006-05-09 13:07:53.000000000 -0400 +++ ./DualCoding/SketchPoolRoot.h 2007-11-11 18:57:21.000000000 -0500 @@ -9,20 +9,24 @@ //! Non-templated parent class of SketchPool. /*! SketchPoolRoot is the non-templated parent class of SketchPool. It is needed in order to reference components of SketchSpace. We - can't #include SketchSpace.h from SketchPool.h because of circular + can't \#include SketchSpace.h from SketchPool.h because of circular dependencies, but we can safely include it from SketchPoolRoot.cc. */ class SketchPoolRoot { protected: SketchSpace *space; + std::string name; - int getRefreshCounter(); + int getRefreshCounter() const; public: - SketchPoolRoot(SketchSpace* _space) : space(_space) {} + SketchPoolRoot(SketchSpace* _space, const std::string& _name) : space(_space), name(_name) {} + + const std::string& getName() const { return name; } + const std::string& getSpaceName() const; - virtual ~SketchPoolRoot()=0; //!< used as a base class, but never directly instantiated, so has an virtual abstract destructor + virtual ~SketchPoolRoot()=0; //!< used as a base class, but never directly instantiated, so has a virtual abstract destructor SketchPoolRoot(const SketchPoolRoot&); //!< never call diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchRoot.cc ./DualCoding/SketchRoot.cc --- ../Tekkotsu_3.0/DualCoding/SketchRoot.cc 2006-08-10 23:11:04.000000000 -0400 +++ ./DualCoding/SketchRoot.cc 2007-02-05 02:16:48.000000000 -0500 @@ -10,17 +10,20 @@ return *(faker.data->space); } -const SketchDataRoot& SketchRoot::rootGetData() const { - const Sketch& faker = *reinterpret_cast*>(this); - return *(faker.data); +const SketchDataRoot* SketchRoot::rootGetData() const { + const Sketch* faker = reinterpret_cast*>(this); + return reinterpret_cast(faker->data); } int SketchRoot::idCounter = 0; std::ostream& operator<<(std::ostream &os, const SketchRoot &r) { - const SketchDataRoot& data = r.rootGetData(); - os << "Sketch<" << SketchTypeNames[data.getType()] << ">(\"" - << data.getName() << "\",id=" << data.getId() << ")"; + const SketchDataRoot* data = r.rootGetData(); + if ( data != NULL ) + os << "Sketch<" << SketchTypeNames[data->getType()] << ">(\"" + << data->getName() << "\",id=" << data->getId() << ")"; + else + os << "Sketch()"; return os; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchRoot.h ./DualCoding/SketchRoot.h --- ../Tekkotsu_3.0/DualCoding/SketchRoot.h 2006-04-22 01:37:50.000000000 -0400 +++ ./DualCoding/SketchRoot.h 2007-02-05 02:16:48.000000000 -0500 @@ -16,7 +16,7 @@ virtual ~SketchRoot() {} SketchSpace& rootGetSpace() const; - const SketchDataRoot& rootGetData() const; + const SketchDataRoot* rootGetData() const; int getNewId() { return ++idCounter; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchSpace.cc ./DualCoding/SketchSpace.cc --- ../Tekkotsu_3.0/DualCoding/SketchSpace.cc 2006-09-12 17:39:45.000000000 -0400 +++ ./DualCoding/SketchSpace.cc 2007-11-11 18:57:22.000000000 -0500 @@ -8,16 +8,18 @@ #include "BaseData.h" #include "ViewerConnection.h" +using namespace std; + namespace DualCoding { -SketchSpace::SketchSpace(string const _name, ReferenceFrameType_t _refFrameType, +SketchSpace::SketchSpace(std::string const _name, ReferenceFrameType_t _refFrameType, int const init_id, size_t const _width, size_t const _height) : name(_name), width(_width), height(_height), numPixels(_width*_height), Tmat(NEWMAT::IdentityMatrix(4)), Tmatinv(NEWMAT::IdentityMatrix(4)), idCounter(1), refreshCounter(1), dualSpace(new ShapeSpace(this,init_id,_name,_refFrameType)), - boolPool(this,0), ucharPool(this,0), usintPool(this,0), floatPool(this,0), - dummy(width*height), idx(NULL), + boolPool(this,"bool"), ucharPool(this,"uchar"), uintPool(this,"uint"), floatPool(this,"float"), + dummy(numPixels), idx(NULL), idxN(NULL), idxS(NULL), idxE(NULL), idxW(NULL), idxNE(NULL), idxNW(NULL), idxSE(NULL), idxSW(NULL), viewer(new ViewerConnection) @@ -25,25 +27,21 @@ } void SketchSpace::requireIdx() { - if(idx!=NULL) - return; - idx=new Sketch(*this, "idx"); - int i = 0; - for (size_t y = 0; y < height; y++) { - for (size_t x = 0; x < width; x++) { - setIdx(*idx, x, y, i); - i++; - } - } - // idx->setViewable(true); + if ( idx == NULL ) { + idx = new Sketch(*this, "idx"); + uint i = 0; + for (size_t y = 0; y < height; y++) + for (size_t x = 0; x < width; x++) + setIdx(*idx, x, y, i++); + } } void SketchSpace::requireIdx4way() { if ( idxN == NULL) { - idxN = new Sketch(*this,"idN"); - idxS = new Sketch(*this,"idS"); - idxE = new Sketch(*this,"idE"); - idxW = new Sketch(*this,"idW"); + idxN = new Sketch(*this,"idN"); + idxS = new Sketch(*this,"idS"); + idxE = new Sketch(*this,"idE"); + idxW = new Sketch(*this,"idW"); int i = 0; for (size_t y = 0; y < height; y++) { for (size_t x = 0; x < width; x++) { @@ -60,10 +58,10 @@ void SketchSpace::requireIdx8way() { requireIdx4way(); if ( idxNE == NULL) { - idxNE = new Sketch(*this,"idNE"); - idxNW = new Sketch(*this,"idNW"); - idxSE = new Sketch(*this,"idSE"); - idxSW = new Sketch(*this,"idSW"); + idxNE = new Sketch(*this,"idNE"); + idxNW = new Sketch(*this,"idNW"); + idxSE = new Sketch(*this,"idSE"); + idxSW = new Sketch(*this,"idSW"); int i = 0; for (size_t y = 0; y < height; y++) { for (size_t x = 0; x < width; x++) { @@ -87,6 +85,20 @@ } +void SketchSpace::resize(const size_t new_width, const size_t new_height) { + // delete all the old stuff + freeIndexes(); + boolPool.deleteElements(); + ucharPool.deleteElements(); + uintPool.deleteElements(); + floatPool.deleteElements(); + // now set the new dimensions + width = new_width; + height = new_height; + numPixels = new_width * new_height; + dummy = numPixels; +} + SketchSpace::~SketchSpace() { delete dualSpace; //printf("Destroying SketchSpace %s at 0x%p\n",name.c_str(),this); @@ -98,14 +110,14 @@ void SketchSpace::dumpSpace() const { boolPool.dumpPool(); ucharPool.dumpPool(); - usintPool.dumpPool(); + uintPool.dumpPool(); floatPool.dumpPool(); } void SketchSpace::clear() { boolPool.clear(); ucharPool.clear(); - usintPool.clear(); + uintPool.clear(); floatPool.clear(); } @@ -142,13 +154,12 @@ vec = vec / vec(4); } -void SketchSpace::setIdx(Sketch& indices, int x, int y, int shift_i) { - int shift_x = shift_i % width; - int shift_y = shift_i / width; - if (shift_x < 0 || shift_y < 0 || shift_x >= (int)width || shift_y >= (int)height - || abs(shift_x-x)+1 == (int)width) // loop-around check - shift_i = dummy; - indices(x,y) = shift_i; +void SketchSpace::setIdx(Sketch& indices, int const x, int const y, int const indexval) { + int const indexval_x = indexval % width; + int const indexval_y = indexval / width; + indices(x,y) = (indexval_x < 0 || indexval_y < 0 || indexval_x >= (int)width || indexval_y >= (int)height + || abs(indexval_x-x)+1 == (int)width) // loop-around check + ? dummy : indexval; } std::string SketchSpace::getTmatForGUI() { @@ -166,19 +177,19 @@ std::string sketchlist; sketchlist += boolPool.getSketchListForGUI(); sketchlist += ucharPool.getSketchListForGUI(); - sketchlist += usintPool.getSketchListForGUI(); + sketchlist += uintPool.getSketchListForGUI(); sketchlist += floatPool.getSketchListForGUI(); return sketchlist; } -SketchDataRoot* SketchSpace::retrieveSketch(int id) { +SketchDataRoot* SketchSpace::retrieveSketch(int const id) { SketchDataRoot* sketchp; // Try each pool in turn until we find it. sketchp = boolPool.retrieveSketch(id); if(sketchp) return sketchp; sketchp = ucharPool.retrieveSketch(id); if(sketchp) return sketchp; - sketchp = usintPool.retrieveSketch(id); + sketchp = uintPool.retrieveSketch(id); if(sketchp) return sketchp; sketchp = floatPool.retrieveSketch(id); return sketchp; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchSpace.h ./DualCoding/SketchSpace.h --- ../Tekkotsu_3.0/DualCoding/SketchSpace.h 2006-09-06 20:44:39.000000000 -0400 +++ ./DualCoding/SketchSpace.h 2007-08-24 21:49:16.000000000 -0400 @@ -42,9 +42,9 @@ //! Pool for one of the SketchData classes //@{ - SketchPool boolPool; + SketchPool boolPool; SketchPool ucharPool; - SketchPool usintPool; + SketchPool uintPool; SketchPool floatPool; //@} @@ -54,15 +54,15 @@ //!@name Pre-generated indices for different directions //@{ - Sketch *idx; - Sketch *idxN; - Sketch *idxS; - Sketch *idxE; - Sketch *idxW; - Sketch *idxNE; - Sketch *idxNW; - Sketch *idxSE; - Sketch *idxSW; + Sketch *idx; + Sketch *idxN; + Sketch *idxS; + Sketch *idxE; + Sketch *idxW; + Sketch *idxNE; + Sketch *idxNW; + Sketch *idxSE; + Sketch *idxSW; //@} SketchSpace(std::string const _name, ReferenceFrameType_t _refFrameType, @@ -78,9 +78,6 @@ //! Clears out viewable Sketches. void clear(); - //! returns a new integer ID to assign to a newly created Sketch - //int getNewId(); - //! returns the width of contained images, in pixels size_t getWidth() const { return width; } //! returns the height of contained images, in pixels @@ -103,6 +100,9 @@ //! frees the idx members void freeIndexes(); + //! change the size of sketches in this sketch space (discards all existing sketches) + void resize(const size_t new_width, const size_t new_height); + //! return the ShapeSpace-to-SketchSpace coordinate transformation matrix NEWMAT::Matrix& getTmat() { return Tmat; } @@ -126,7 +126,7 @@ //@{ SketchPool& get_pool(const Sketch&) { return boolPool; } SketchPool& get_pool(const Sketch&) { return ucharPool; } - SketchPool& get_pool(const Sketch&) { return usintPool; } + SketchPool& get_pool(const Sketch&) { return uintPool; } SketchPool& get_pool(const Sketch&) { return floatPool; } //@} @@ -144,12 +144,12 @@ std::string getSketchListForGUI(); //! Returns a pointer to the sketch with specified ID number; null if not found - SketchDataRoot* retrieveSketch(int id); + SketchDataRoot* retrieveSketch(int const id); //@} protected: //! helper function to ensure indices of idx Sketches are proper - void setIdx(Sketch& indices, int x, int y, int shift_i); + void setIdx(Sketch& indices, int const x, int const y, int const indexval); // We don't want clients accidentally copying or assigning SketchSpace. SketchSpace(const SketchSpace&); //!< never call this diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchTypes.h ./DualCoding/SketchTypes.h --- ../Tekkotsu_3.0/DualCoding/SketchTypes.h 2006-04-26 16:50:00.000000000 -0400 +++ ./DualCoding/SketchTypes.h 2007-08-24 21:49:16.000000000 -0400 @@ -9,15 +9,22 @@ typedef unsigned char uchar; typedef unsigned short int usint; +#if defined(TGT_ERS7) || defined(TGT_ERS2xx) || defined(TGT_ERS210) || defined(TGT_ERS220) + typedef unsigned short int uint; +#else + typedef unsigned int uint; +#endif + + enum SketchType_t { sketchUnknown = 0, sketchBool, sketchUchar, - sketchUsint, + sketchUint, sketchFloat }; -const std::string SketchTypeNames[] = {"unknown","bool","uchar","usint","float"}; +const std::string SketchTypeNames[] = {"unknown","bool","uchar","uint","float"}; enum ColorMapType_t { segMap = 0, // use the color segmentation table (default) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SphereData.cc ./DualCoding/SphereData.cc --- ../Tekkotsu_3.0/DualCoding/SphereData.cc 2006-07-19 17:54:12.000000000 -0400 +++ ./DualCoding/SphereData.cc 2007-11-18 01:47:02.000000000 -0500 @@ -15,6 +15,8 @@ #include "SphereData.h" #include "ShapeSphere.h" +using namespace std; + namespace DualCoding { SphereData::SphereData(ShapeSpace& _space, const Point &c) @@ -65,14 +67,14 @@ cout << "radius = " << getRadius() << endl; printf("color = %d %d %d\n",getColor().red,getColor().green,getColor().blue); - cout << "mobile = " << isMobile() << endl; + cout << "mobile = " << getMobile() << endl; cout << "viewable = " << isViewable() << endl; } //! Transformations. (Virtual in BaseData.) -void SphereData::applyTransform(const NEWMAT::Matrix& Tmat) { - centroid.applyTransform(Tmat); +void SphereData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + centroid.applyTransform(Tmat,newref); } bool SphereData::isInside(const Point& pt) const { @@ -83,7 +85,12 @@ void SphereData::projectToGround(const NEWMAT::Matrix& camToBase, const NEWMAT::ColumnVector& groundplane) { +#ifdef TGT_HAS_CAMERA NEWMAT::ColumnVector cam_pos = (kine->jointToBase(CameraFrameOffset)).SubMatrix(1,4,4,4); +#else + // shouldn't we do it this way regardless of TGT_HAS_CAMERA? + NEWMAT::ColumnVector cam_pos = camToBase.SubMatrix(1,4,4,4); +#endif cout << "cam position (" << (cam_pos(1)/cam_pos(4)) << "," << (cam_pos(2)/cam_pos(4)) << "," << (cam_pos(3)/cam_pos(4)) << ")" << endl; Point tangent_pt(centroid.coordX(),centroid.coordY()+radius, centroid.coordZ()); // pick a tangent point from cam point. @@ -137,6 +144,7 @@ const float y = (cc_abc_xy[2]-cc_abc_xy[0]*x) / cc_abc_xy[1]; centroid.setCoords(x,y,z); + centroid.setRefFrameType(egocentric); radius = z-ground; cout << " => (" << x << "," << y << "," << z << "); radius: " << radius << endl; @@ -156,13 +164,13 @@ //! Extraction. //{ -std::vector SphereData::extractSpheres(const Sketch& sketch) +std::vector > SphereData::extractSpheres(const Sketch& sketch) { const float AREA_TOLERANCE = 0.5; const int REGION_THRESH = 25; - NEW_SKETCH_N(labels,usint,visops::oldlabelcc(sketch,visops::EightWayConnect)); + NEW_SKETCH_N(labels,uint,visops::oldlabelcc(sketch,visops::EightWayConnect)); list regionlist = Region::extractRegions(labels,REGION_THRESH); - std::vector spheres; + std::vector > spheres; if(regionlist.empty()) return spheres; @@ -174,24 +182,25 @@ && (it->findArea() > M_PI*2.0*(it->findSemiMajorAxisLength()) *2.0*(it->findSemiMinorAxisLength())*AREA_TOLERANCE/4.0)) { Shape temp_sphere(*it); - temp_sphere->setParentId(sketch->getViewableId()); - temp_sphere->setColor(sketch->getColor()); + temp_sphere->inheritFrom(*sketch.operator->()); + // temp_sphere->setParentId(sketch->getViewableId()); + // temp_sphere->setColor(sketch->getColor()); spheres.push_back(Shape(temp_sphere)); }; } return spheres; } -std::vector SphereData::get_spheres(const Sketch& cam) { +std::vector > SphereData::get_spheres(const Sketch& cam) { //! Declare all colors as valid. std::vector Valid_Colors; Valid_Colors.resize(ProjectInterface::getNumColors(),true); return(get_spheres(cam,Valid_Colors)); } -std::vector SphereData::get_spheres(const Sketch& cam, +std::vector > SphereData::get_spheres(const Sketch& cam, std::vector& Valid_Colors) { - std::vector spheres_vec; + std::vector > spheres_vec; uchar cur_color; uchar num_colors = (uchar)Valid_Colors.size(); char *pmask_name_chr = (char *)malloc(128*sizeof(char)); @@ -202,18 +211,18 @@ if(Valid_Colors[cur_color] == true) { // Segment color pixels. - NEW_SKETCH_N(pmask, bool, cam == cur_color); + NEW_SKETCH_N(pmask, bool, visops::colormask(cam,cur_color)); sprintf(pmask_name_chr, "pmask_%d",cur_color); pmask->setName(pmask_name_chr); // Extract spheres. - std::vector spheresList = SphereData::extractSpheres(pmask); + std::vector > spheresList = SphereData::extractSpheres(pmask); int num_spheres = (int)spheresList.size(); int cur_sphere; for(cur_sphere = 0; cur_sphere < num_spheres; cur_sphere++) { - spheresList[cur_sphere]->setColor(ProjectInterface::getColorRGB(cur_color)); + // spheresList[cur_sphere]->setColor(ProjectInterface::getColorRGB(cur_color)); spheres_vec.push_back(spheresList[cur_sphere]); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SphereData.h ./DualCoding/SphereData.h --- ../Tekkotsu_3.0/DualCoding/SphereData.h 2006-05-09 18:37:56.000000000 -0400 +++ ./DualCoding/SphereData.h 2007-11-11 02:57:26.000000000 -0500 @@ -56,7 +56,7 @@ virtual void printParams() const; //! Transformations. (Virtual in BaseData.) - void applyTransform(const NEWMAT::Matrix& Tmat); + void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); //! Project to ground virtual void projectToGround(const NEWMAT::Matrix& camToBase, @@ -86,10 +86,10 @@ //! Extraction. //@{ - static std::vector extractSpheres(const Sketch& sketch); - static std::vector get_spheres(const Sketch& cam); - static std::vector get_spheres(const Sketch& cam, - vector& Valid_Colors); + static std::vector > extractSpheres(const Sketch& sketch); + static std::vector > get_spheres(const Sketch& cam); + static std::vector > get_spheres(const Sketch& cam, + std::vector& Valid_Colors); //@} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/TargetData.cc ./DualCoding/TargetData.cc --- ../Tekkotsu_3.0/DualCoding/TargetData.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/TargetData.cc 2007-11-11 18:57:22.000000000 -0500 @@ -0,0 +1,614 @@ +//-*-c++-*- + +#include "BaseData.h" // superclass +#include "Point.h" // Point data member +#include "ShapeTypes.h" // TargetDataType + +#include "SketchSpace.h" +#include "Sketch.h" +#include "visops.h" + +#include "ShapeSpace.h" // required by DATASTUFF_CC +#include "ShapeRoot.h" // required by DATASTUFF_CC + +#include "TargetData.h" +#include "ShapeTarget.h" + +#include "BlobData.h" +#include "ShapeBlob.h" +#include "VRmixin.h" + +using namespace std; + +namespace DualCoding { + +TargetData::TargetData(ShapeSpace& _space, const EndPoint &_frontLeftPt, const EndPoint &_frontRightPt, const EndPoint &_backLeftPt, const EndPoint &_backRightPt, const EndPoint &_frontIntersect, const EndPoint &_backIntersect, const float _height) + : BaseData(_space, getStaticType()), + frontLine(_space, _frontLeftPt, _frontRightPt), + backLine(_space, _backLeftPt, _backRightPt), + frontValid((_frontLeftPt != Point(0, 0, 0)) && (_frontRightPt != Point(0, 0, 0))), + backValid((_backLeftPt != Point(0, 0, 0)) && (_backRightPt != Point(0, 0, 0))), + frontIntersect(_frontIntersect), + backIntersect(_backIntersect), + orientation(0.0), + length(0.0), + width(0.0), + height(_height) { + update_derived_properties(); +} + +DATASTUFF_CC(TargetData); + +BoundingBox TargetData::getBoundingBox() const { + return BoundingBox(frontLine.getBoundingBox(), backLine.getBoundingBox()); +} + +bool TargetData::isMatchFor(const ShapeRoot& other) const { + if (!(isSameTypeAs(other) && isSameColorAs(other))) { + return false; + } + else { + const Shape& other_target = ShapeRootTypeConst(other,TargetData); + return isMatchFor(other_target.getData()); + } +} + +bool TargetData::isMatchFor(const TargetData& other_target) const { + // 2 targets match if either of their lines match + if (frontValid && !frontLine.isMatchFor(other_target.frontLine) && backValid && !backLine.isMatchFor(other_target.backLine)) + return false; + return true; +} + +void TargetData::update_derived_properties() { + EndPoint &frontLeftPt = getFrontLeftPt(); + EndPoint &frontRightPt = getFrontRightPt(); + EndPoint &backLeftPt = getBackLeftPt(); + EndPoint &backRightPt = getBackRightPt(); + + // Determine if the front and back lines are valid + frontValid = true; + backValid = true; + if ((frontLeftPt == Point(0, 0, 0)) || (frontRightPt == Point(0, 0, 0))) { + frontValid = false; + } + if ((backLeftPt == Point(0, 0, 0)) || (backRightPt == Point(0, 0, 0))) { + backValid = false; + } + if (frontValid && backValid && (getRefFrameType() != camcentric)) { + // Lines should not be in the negative z plane + if (frontLine.getCentroid().coordZ() < 0) { + frontValid = false; + } + if (backLine.getCentroid().coordZ() < 0) { + backValid = false; + } + // Remove short lines if the other line is long + if ((frontLine.getLength() < 50.0f) && backValid && (backLine.getLength() > 50.0f)) { + frontValid = false; + } + else if ((backLine.getLength() < 50.0f) && frontValid && (frontLine.getLength() > 50.0f)) { + backValid = false; + } + } + + // Reset the front/back lines if they are invalid + if (!frontValid) { + frontLeftPt = Point(0, 0, 0); + frontRightPt = Point(0, 0, 0); + frontLeftPt.setValid(false); + frontRightPt.setValid(false); + frontLine.update_derived_properties(); + + frontIntersect = Point(0, 0, 0); + frontIntersect.setValid(false); + } + if (!backValid) { + backLeftPt = Point(0, 0, 0); + backRightPt = Point(0, 0, 0); + backLeftPt.setValid(false); + backRightPt.setValid(false); + backLine.update_derived_properties(); + + backIntersect = Point(0, 0, 0); + backIntersect.setValid(false); + } + + // Determine if the front/back intersection points are valid + if (frontIntersect == Point(0, 0, 0)) { + frontIntersect.setValid(false); + } + if (backIntersect == Point(0, 0, 0)) { + backIntersect.setValid(false); + } + + // Check left/right points based on intersection points + if (frontIntersect.isValid() || backIntersect.isValid()) { + if (frontIntersect.isValid()) { + bool swap = false; + + // The right point will be closer to the intersection if both points are valid/invalid + if (frontValid && (frontLeftPt.isValid() == frontRightPt.isValid()) + && (frontLeftPt.distanceFrom(frontIntersect) < frontRightPt.distanceFrom(frontIntersect))) { + swap = true; + } + // Assumption: the right point will be the valid point otherwise + else if (frontValid && frontLeftPt.isValid() && !frontRightPt.isValid()) { + swap = true; + } + + + if (swap) { + // Front left and right are reversed + EndPoint temp = frontLeftPt; + frontLeftPt = frontRightPt; + frontRightPt = temp; + frontLine.update_derived_properties(); + } + + // If back intersection is invalid, then determine back left/right based on distance from front left/right + if (backValid && !backIntersect.isValid()) { + float leftMax = max(frontLeftPt.distanceFrom(backLeftPt), frontRightPt.distanceFrom(backLeftPt)); + float rightMax = max(frontLeftPt.distanceFrom(backRightPt), frontRightPt.distanceFrom(backRightPt)); + + // Look at the point that's further away + swap = false; + if (leftMax > rightMax) { + if (frontLeftPt.distanceFrom(backLeftPt) > frontRightPt.distanceFrom(backLeftPt)) { + swap = true; + } + } + else { + if (frontRightPt.distanceFrom(backRightPt) > frontLeftPt.distanceFrom(backRightPt)) { + swap = true; + } + } + + if (swap) { + // Back left and right are reversed + EndPoint temp = backLeftPt; + backLeftPt = backRightPt; + backRightPt = temp; + backLine.update_derived_properties(); + } + } + } + if (backIntersect.isValid()) { + bool swap = false; + + // The right point will be closer to the intersection if both points are valid/invalid + if (backValid && (backLeftPt.isValid() == backRightPt.isValid()) + && (backLeftPt.distanceFrom(backIntersect) < backRightPt.distanceFrom(backIntersect))) { + swap = true; + } + // Assumption: the right point will be the valid point otherwise + else if (backValid && backLeftPt.isValid() && !backRightPt.isValid()) { + swap = true; + } + + + if (swap) { + // Back left and right are reversed + EndPoint temp = backLeftPt; + backLeftPt = backRightPt; + backRightPt = temp; + backLine.update_derived_properties(); + } + + // If front intersection is invalid, then determine front left/right based on distance from back left/right + if (frontValid && !frontIntersect.isValid()) { + float leftMax = max(backLeftPt.distanceFrom(frontLeftPt), backRightPt.distanceFrom(frontLeftPt)); + float rightMax = max(backLeftPt.distanceFrom(frontRightPt), backRightPt.distanceFrom(frontRightPt)); + + // Look at the point that's further away + swap = false; + if (leftMax > rightMax) { + if (backLeftPt.distanceFrom(frontLeftPt) > backRightPt.distanceFrom(frontLeftPt)) { + swap = true; + } + } + else { + if (backRightPt.distanceFrom(frontRightPt) > backLeftPt.distanceFrom(frontRightPt)) { + swap = true; + } + } + + if (swap) { + // Front left and right are reversed + EndPoint temp = frontLeftPt; + frontLeftPt = frontRightPt; + frontRightPt = temp; + frontLine.update_derived_properties(); + } + } + } + } + + float front_dx = frontRightPt.coordX() - frontLeftPt.coordX(); + float front_dy = frontRightPt.coordY() - frontLeftPt.coordY(); + float back_dx = backRightPt.coordX() - backLeftPt.coordX(); + float back_dy = backRightPt.coordY() - backLeftPt.coordY(); + + if (frontValid && backValid) { + // Calculate the length/width + length = max(frontLine.getLength(), backLine.getLength()); + width = max(frontLine.perpendicularDistanceFrom( backLine.getCentroid() ), backLine.perpendicularDistanceFrom( frontLine.getCentroid() )); + + // Calculate the orientation based on the front and back line + AngSignPi front_orientation = AngSignPi(atan2(front_dy, front_dx) + M_PI / 2); + AngSignPi back_orientation = AngSignPi(atan2(back_dy, back_dx) + M_PI / 2); + + // Check left/right of line by coming up with a point that's 1000mm away, + // and if the point is closer to the other line, then orientation should be flipped + float dist = 1000.0f; + Point frontPt( getCentroid().coordX() + dist * cos(front_orientation), getCentroid().coordY() + dist * sin(front_orientation), getCentroid().coordZ() ); + if ((width > 50.0f) && (frontLine.perpendicularDistanceFrom( frontPt ) > backLine.perpendicularDistanceFrom( frontPt ))) { + // Front left and right are reversed + EndPoint temp = frontLeftPt; + frontLeftPt = frontRightPt; + frontRightPt = temp; + frontLine.update_derived_properties(); + + front_dx = frontRightPt.coordX() - frontLeftPt.coordX(); + front_dy = frontRightPt.coordY() - frontLeftPt.coordY(); + front_orientation = AngSignPi(atan2(front_dy, front_dx) + M_PI / 2); + } + + Point backPt( getBackCentroid().coordX() - dist * cos(back_orientation), getBackCentroid().coordY() - dist * sin(back_orientation), getBackCentroid().coordZ() ); + if ((width > 50.0f) && (backLine.perpendicularDistanceFrom( backPt ) > frontLine.perpendicularDistanceFrom( backPt ))) { + // Back left and right are reversed + EndPoint temp = backLeftPt; + backLeftPt = backRightPt; + backRightPt = temp; + backLine.update_derived_properties(); + + back_dx = backRightPt.coordX() - backLeftPt.coordX(); + back_dy = backRightPt.coordY() - backLeftPt.coordY(); + back_orientation = AngSignPi(atan2(back_dy, back_dx) + M_PI / 2); + } + + // Use the orientation of the line with most valid points + int frontValidCount = 0, backValidCount = 0; + if (frontLeftPt.isValid()) frontValidCount++; + if (frontRightPt.isValid()) frontValidCount++; + if (backLeftPt.isValid()) backValidCount++; + if (backRightPt.isValid()) backValidCount++; + + if (frontValidCount == backValidCount) { + // Take the average of the 2 orientations + orientation = AngSignPi(atan2(sin(front_orientation) + sin(back_orientation), cos(front_orientation) + cos(back_orientation))); + } + else if (frontValidCount > backValidCount) { + orientation = front_orientation; + } + else { + orientation = back_orientation; + } + } + // If only one line is valid, obtain the length/orientation from it + else if (frontValid) { + length = frontLine.getLength(); + width = 0; + orientation = AngSignPi(atan2(front_dy, front_dx) + M_PI / 2); + } + else if (backValid) { + length = backLine.getLength(); + width = 0; + orientation = AngSignPi(atan2(back_dy, back_dx) + M_PI / 2); + } + else { + length = 0; + width = 0; + orientation = 0; + } + +} + +bool TargetData::updateParams(const ShapeRoot& other, bool force) { + const Shape& other_target = ShapeRootTypeConst(other,TargetData); + if (other_target->confidence <= 0) + return false; + + const int other_conf = other_target->confidence; + confidence += other_conf; + + height = (height*confidence + other_target->getHeight()*other_conf) / (confidence+other_conf); + + // Update front line + EndPoint &frontLeftPt = getFrontLeftPt(); + EndPoint &frontRightPt = getFrontRightPt(); + if (!frontValid) { + frontLeftPt = other_target->getFrontLeftPt(); + frontRightPt = other_target->getFrontRightPt(); + } + else if (other_target->isFrontValid()) { + NEW_SHAPE(otherFrontLine, LineData, other_target->frontLine); + frontLine.updateParams(otherFrontLine, force); + otherFrontLine.getSpace().deleteShape(otherFrontLine); + } + + // Update back line + EndPoint &backLeftPt = getBackLeftPt(); + EndPoint &backRightPt = getBackRightPt(); + if (!backValid) { + backLeftPt = other_target->getBackLeftPt(); + backRightPt = other_target->getBackRightPt(); + } + else if (other_target->isBackValid()) { + NEW_SHAPE(otherBackLine, LineData, other_target->backLine); + backLine.updateParams(otherBackLine, force); + otherBackLine.getSpace().deleteShape(otherBackLine); + } + + // Update front intersection point + if (frontIntersect == Point(0, 0, 0)) { + frontIntersect = other_target->getFrontIntersect(); + } + else if (other_target->getFrontIntersect() != Point(0, 0, 0)) { + if (frontIntersect.isValid() == other_target->getFrontIntersect().isValid()) { + frontIntersect.updateParams(other_target->getFrontIntersect()); + } + else if (other_target->getFrontIntersect().isValid()) { + frontIntersect = other_target->getFrontIntersect(); + } + } + + // Update back intersection point + if (backIntersect == Point(0, 0, 0)) { + backIntersect = other_target->getBackIntersect(); + } + else if (other_target->getBackIntersect() != Point(0, 0, 0)) { + if (backIntersect.isValid() == other_target->getBackIntersect().isValid()) { + backIntersect.updateParams(other_target->getBackIntersect()); + } + else if (other_target->getBackIntersect().isValid()) { + backIntersect = other_target->getBackIntersect(); + } + } + + update_derived_properties(); + + return true; +} + +void TargetData::mergeWith(const ShapeRoot& other) { + const Shape& other_target = ShapeRootTypeConst(other,TargetData); + if (other_target->confidence <= 0) + return; + const int other_conf = other_target->confidence; + confidence += other_conf; + + height = (height*confidence + other_target->height*other_conf) / (confidence+other_conf); + NEW_SHAPE(otherFrontLine, LineData, other_target->frontLine); + NEW_SHAPE(otherBackLine, LineData, other_target->backLine); + frontLine.mergeWith(otherFrontLine); + backLine.mergeWith(otherBackLine); + otherFrontLine.getSpace().deleteShape(otherFrontLine); + otherBackLine.getSpace().deleteShape(otherBackLine); + + frontIntersect.updateParams(other_target->getFrontIntersect()); + backIntersect.updateParams(other_target->getBackIntersect()); + + update_derived_properties(); +} + +void TargetData::printParams() const { + cout << "Type = " << getTypeName() << endl; + cout << "Shape ID = " << getId() << endl; + cout << "Parent ID = " << getParentId() << endl; + + // Print all parameters. + const EndPoint frontLeftPt = getFrontLeftPt(); + const EndPoint frontRightPt = getFrontRightPt(); + const EndPoint backLeftPt = getBackLeftPt(); + const EndPoint backRightPt = getBackRightPt(); + const Point centroid = getCentroid(); + + cout << endl; + cout << "centroid = (" << centroid.coordX() << ", " << centroid.coordY() << ", " << centroid.coordZ() << ")" << endl; + cout << "front left pt = (" << frontLeftPt.coordX() << ", " << frontLeftPt.coordY() << ", " << frontLeftPt.coordZ() << "), valid = " << frontLeftPt.isValid() << endl; + cout << "front right pt = (" << frontRightPt.coordX() << ", " << frontRightPt.coordY() << ", " << frontRightPt.coordZ() << "), valid = " << frontRightPt.isValid() << endl; + cout << "back left pt = (" << backLeftPt.coordX() << ", " << backLeftPt.coordY() << ", " << backLeftPt.coordZ() << "), valid = " << backLeftPt.isValid() << endl; + cout << "back right pt = (" << backRightPt.coordX() << ", " << backRightPt.coordY() << ", " << backRightPt.coordZ() << "), valid = " << backRightPt.isValid() << endl; + cout << "front intersect = (" << frontIntersect.coordX() << ", " << frontIntersect.coordY() << ", " << frontIntersect.coordZ() << "), valid = " << frontIntersect.isValid() << endl; + cout << "back intersect = (" << backIntersect.coordX() << ", " << backIntersect.coordY() << ", " << backIntersect.coordZ() << "), valid = " << backIntersect.isValid() << endl; + cout << "front valid = " << frontValid << endl; + cout << "back valid = " << backValid << endl; + cout << "orientation = " << (float)orientation * 180.0 / M_PI << " deg" << endl; + cout << "length = " << length << endl; + cout << "width = " << width << endl; + cout << "height = " << height << endl; +} + +void TargetData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) { + if (frontValid) + frontLine.applyTransform(Tmat, newref); + if (backValid) + backLine.applyTransform(Tmat, newref); + if (frontIntersect != Point(0, 0, 0)) + frontIntersect.applyTransform(Tmat, newref); + if (backIntersect != Point(0, 0, 0)) + backIntersect.applyTransform(Tmat, newref); + update_derived_properties(); +} + +void TargetData::projectToGround(const NEWMAT::Matrix& camToBase, const NEWMAT::ColumnVector& groundplane) { + // project the lines to elevated ground space + NEWMAT::ColumnVector target_plane = groundplane; + float displacement = height * sqrt(target_plane(1) * target_plane(1) + target_plane(2) * target_plane(2) + target_plane(3) * target_plane(3)); + target_plane(4) += target_plane(3) >= 0 ? displacement : -displacement; + + if (frontValid) + frontLine.projectToGround(camToBase, target_plane); + if (backValid) + backLine.projectToGround(camToBase, target_plane); + if (frontIntersect != Point(0, 0, 0)) + frontIntersect.projectToGround(camToBase, target_plane); + if (backIntersect != Point(0, 0, 0)) + backIntersect.projectToGround(camToBase, target_plane); + update_derived_properties(); +} + +// Doesn't actually render a target to sketch space +Sketch* TargetData::render() const { + SketchSpace &SkS = space->getDualSpace(); + + Sketch& draw_result = + *new Sketch(SkS, "render("+getName()+")"); + draw_result->setParentId(getViewableId()); + draw_result->setColor(getColor()); + + NEWMAT::ColumnVector ctr(getCentroid().getCoords()); + SkS.applyTmat(ctr); + int const cx = int(ctr(1)); + int const cy = int(ctr(2)); + draw_result = false; + draw_result(cx, cy) = true; + return &draw_result; +} + +TargetData& TargetData::operator=(const TargetData& other) { + if (&other == this) + return *this; + BaseData::operator=(other); + + frontLine = other.frontLine; + backLine = other.backLine; + frontValid = other.frontValid; + backValid = other.backValid; + frontIntersect = other.frontIntersect; + backIntersect = other.backIntersect; + orientation = other.orientation; + length = other.length; + width = other.width; + height = other.height; + + return *this; +} + +float TargetData::perpendicularDistanceFrom(Point point) { + if (frontValid && backValid) + return min(frontLine.perpendicularDistanceFrom(point), backLine.perpendicularDistanceFrom(point)); + else if (frontValid) + return frontLine.perpendicularDistanceFrom(point); + else if (backValid) + return backLine.perpendicularDistanceFrom(point); + else + return 0; +} + +Shape TargetData::extractLineTarget(std::string frontColor, std::string backColor, std::string rightColor, std::string occluderColor, const float height) { + // get the front, back and right stuff + NEW_SKETCH(camFrame, uchar, VRmixin::sketchFromSeg()); + NEW_SKETCH(frontStuff, bool, visops::colormask(camFrame, frontColor)); + NEW_SKETCH(backStuff, bool, visops::colormask(camFrame, backColor)); + NEW_SKETCH(rightStuff, bool, visops::colormask(camFrame, rightColor)); + NEW_SKETCH(occluders, bool, visops::colormask(camFrame, occluderColor)); + + NEW_SHAPEVEC(frontBlobs, BlobData, BlobData::extractBlobs(frontStuff, 100)); + NEW_SHAPEVEC(backBlobs, BlobData, BlobData::extractBlobs(backStuff, 100)); + NEW_SHAPEVEC(rightBlobs, BlobData, BlobData::extractBlobs(rightStuff, 100)); + + // assume the biggest blob forms the front line + NEW_SKETCH(frontSketch, bool, frontBlobs.size() > 0 ? frontBlobs[0]->getRendering() : visops::zeros(camFrame)); + // assume the biggest blob forms the back line + NEW_SKETCH(backSketch, bool, backBlobs.size() > 0 ? backBlobs[0]->getRendering() : visops::zeros(camFrame)); + // assume the biggest blob forms the right line + NEW_SKETCH(rightSketch, bool, rightBlobs.size() > 0 ? rightBlobs[0]->getRendering() : visops::zeros(camFrame)); + + Shape result = extractLineTarget(frontSketch, backSketch, rightSketch, occluders, height); + + // delete temporary camera shapes + //camShS.deleteShapes(horBlobs); + //camShS.deleteShapes(vertBlobs); + + return result; +} + +Shape TargetData::extractLineTarget(Sketch& frontSketch, Sketch& backSketch, Sketch& rightSketch, Sketch& occluders, const float height) { + NEW_SHAPE(frontLine, LineData, LineData::extractLine(frontSketch, occluders | rightSketch)); + NEW_SHAPE(backLine, LineData, LineData::extractLine(backSketch, occluders | rightSketch)); + NEW_SHAPE(rightLine, LineData, LineData::extractLine(rightSketch, occluders)); + + Shape result = extractLineTarget(frontLine, backLine, rightLine, frontSketch->getColor(), height); + + // delete temporary camera shapes + if (frontLine.isValid()) + frontLine.getSpace().deleteShape(frontLine); + if (backLine.isValid()) + backLine.getSpace().deleteShape(backLine); + if (rightLine.isValid()) + rightLine.getSpace().deleteShape(rightLine); + + return result; +} + +Shape TargetData::extractLineTarget(Shape& frontLine, Shape& backLine, Shape& rightLine, rgb color, const float height) { + + // create the target using the front and back lines + if (frontLine.isValid() && backLine.isValid()) { + EndPoint frontIntersect = Point(0, 0, 0); + EndPoint backIntersect = Point(0, 0, 0); + if (rightLine.isValid()) { + frontIntersect = frontLine->intersectionWithLine(rightLine); + backIntersect = backLine->intersectionWithLine(rightLine); + frontIntersect.setValid(frontLine->pointOnLine(frontIntersect)); + backIntersect.setValid(backLine->pointOnLine(backIntersect)); + } + else { + frontIntersect.setValid(false); + backIntersect.setValid(false); + } + + Shape result(frontLine.getSpace(), frontLine->leftPt(), frontLine->rightPt(), backLine->leftPt(), backLine->rightPt(), frontIntersect, backIntersect, height); + result->setColor(color); + return result; + } + else if (frontLine.isValid()) { + EndPoint left = Point(0, 0, 0); + EndPoint right = Point(0, 0, 0); + left.setValid(false); + right.setValid(false); + + EndPoint frontIntersect = Point(0, 0, 0); + EndPoint backIntersect = Point(0, 0, 0); + frontIntersect.setValid(false); + backIntersect.setValid(false); + + if (rightLine.isValid()) { + frontIntersect = frontLine->intersectionWithLine(rightLine); + frontIntersect.setValid(frontLine->pointOnLine(frontIntersect)); + } + + Shape result(frontLine.getSpace(), frontLine->rightPt(), frontLine->leftPt(), right, left, frontIntersect, backIntersect, height); + result->setColor(color); + return result; + } + else if (backLine.isValid()) { + EndPoint left = Point(0, 0, 0); + EndPoint right = Point(0, 0, 0); + left.setValid(false); + right.setValid(false); + + EndPoint frontIntersect = Point(0, 0, 0); + EndPoint backIntersect = Point(0, 0, 0); + frontIntersect.setValid(false); + backIntersect.setValid(false); + + if (rightLine.isValid()) { + backIntersect = backLine->intersectionWithLine(rightLine); + backIntersect.setValid(backLine->pointOnLine(backIntersect)); + } + + Shape result(backLine.getSpace(), right, left, backLine->rightPt(), backLine->leftPt(), frontIntersect, backIntersect, height); + result->setColor(color); + return result; + } + else { + ShapeRoot invalid; // need to define a named variable to avoid warning on next line + return ShapeRootType(invalid, TargetData); + } + +} + +} // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/TargetData.h ./DualCoding/TargetData.h --- ../Tekkotsu_3.0/DualCoding/TargetData.h 1969-12-31 19:00:00.000000000 -0500 +++ ./DualCoding/TargetData.h 2007-04-23 17:44:46.000000000 -0400 @@ -0,0 +1,114 @@ +//-*-c++-*- +#ifndef _TARGETDATA_H_ +#define _TARGETDATA_H_ + +#include "BaseData.h" // superclass +#include "LineData.h" +#include "Point.h" // Point data member +#include "EndPoint.h" // EndPoint data member +#include "ShapeTypes.h" // TargetDataType + +namespace DualCoding { + +class ShapeRoot; +class SketchSpace; +template class Sketch; + +class TargetData : public BaseData { +protected: + LineData frontLine, backLine; + bool frontValid, backValid; + EndPoint frontIntersect, backIntersect; + AngSignPi orientation; + float length, width, height; + +public: + //! Constructor + TargetData(ShapeSpace& _space, const EndPoint &_frontLeftPt, const EndPoint &_frontRightPt, const EndPoint &_backLeftPt, const EndPoint &_backRightPt, const EndPoint &_frontIntersect, const EndPoint &_backIntersect, const float _height); + + //! Copy constructor + TargetData(const TargetData& other) + : BaseData(other), + frontLine(other.frontLine), backLine(other.backLine), + frontValid(other.frontValid), backValid(other.backValid), + frontIntersect(other.frontIntersect), backIntersect(other.backIntersect), + orientation(other.orientation), length(other.length), width(other.width), height(other.height) {} + + static ShapeType_t getStaticType() { return targetDataType; } + + DATASTUFF_H(TargetData); + + //! Centroid. (Virtual in BaseData.) + Point getFrontCentroid() const { return frontValid ? frontLine.getCentroid() : backLine.getCentroid(); } + Point getBackCentroid() const { return backValid ? backLine.getCentroid() : frontLine.getCentroid(); } + Point getCentroid() const { return (frontValid && backValid) ? (frontLine.getCentroid() + backLine.getCentroid()) / 2: getFrontCentroid(); } + + BoundingBox getBoundingBox() const; + + //! Match points based on their parameters. (Virtual in BaseData.) + virtual bool isMatchFor(const ShapeRoot& other) const; + bool isMatchFor(const TargetData& other_target) const; + + //! minimum length of a target + virtual bool isAdmissible() const { return length > 10.0; } + + //! updates orientation and length from feature points + void update_derived_properties(); + + virtual bool updateParams(const ShapeRoot& other, bool force=false); + + virtual void mergeWith(const ShapeRoot& other); + + //! Print information about this shape. (Virtual in BaseData.) + virtual void printParams() const; + + //! Transformations. (Virtual in BaseData.) + void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified); + + //! Project the Target onto the target plane (ground plane lifted up by height) + virtual void projectToGround(const NEWMAT::Matrix& camToBase, const NEWMAT::ColumnVector& groundplane); + + virtual unsigned short getDimension() const { return 3; } + + EndPoint& getFrontLeftPt() { return frontLine.end1Pt(); } + EndPoint& getFrontRightPt() { return frontLine.end2Pt(); } + const EndPoint& getFrontLeftPt() const { return frontLine.end1Pt(); } + const EndPoint& getFrontRightPt() const { return frontLine.end2Pt(); } + + EndPoint& getBackLeftPt() { return backLine.end1Pt(); } + EndPoint& getBackRightPt() { return backLine.end2Pt(); } + const EndPoint& getBackLeftPt() const { return backLine.end1Pt(); } + const EndPoint& getBackRightPt() const { return backLine.end2Pt(); } + + EndPoint &getFrontIntersect() { return frontIntersect; } + EndPoint &getBackIntersect() { return backIntersect; } + const EndPoint &getFrontIntersect() const { return frontIntersect; } + const EndPoint &getBackIntersect() const { return backIntersect; } + + bool isFrontValid() { return frontValid; } + bool isBackValid() { return backValid; } + + AngSignPi getOrientation() { return orientation; } + float getLength() { return length; } + float getWidth() { return width; } + float getHeight() { return height; } + + TargetData& operator=(const TargetData&); + + float perpendicularDistanceFrom(Point point); + + static Shape extractLineTarget(std::string frontColor = "yellow", std::string backColor = "pink", std::string rightColor = "blue", std::string occluderColor = "orange", const float height = 90.0f); + static Shape extractLineTarget(Sketch& frontSketch, Sketch& backSketch, Sketch& rightSketch, Sketch& occluderSketch, const float height = 90.0f); + static Shape extractLineTarget(Shape& camFrontLine, Shape& camBackLine, Shape& camRightLine, rgb color, const float height = 90.0f); + +private: + //! Render into a sketch space and return reference. (Private.) + Sketch* render() const; + //@} + +}; + +} // namespace + +#endif + diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/VRmixin.cc ./DualCoding/VRmixin.cc --- ../Tekkotsu_3.0/DualCoding/VRmixin.cc 2006-09-06 20:44:39.000000000 -0400 +++ ./DualCoding/VRmixin.cc 2007-11-19 02:35:24.000000000 -0500 @@ -11,12 +11,13 @@ #include "Lookout.h" #include "MapBuilder.h" -#include "ParticleFilter.h" #include "Pilot.h" #include "ViewerConnection.h" // for port numbers and buffer sizes #include "VRmixin.h" +using namespace std; + namespace DualCoding { //---------------------------------------------------------------- @@ -45,11 +46,6 @@ return ShS; } -MapBuilder& VRmixin::getMapBuilder() { - static MapBuilder mapbuilder; - return mapbuilder; -} - SketchSpace& VRmixin::camSkS=VRmixin::getCamSkS(); ShapeSpace& VRmixin::camShS=VRmixin::getCamSkS().getDualSpace(); @@ -70,21 +66,36 @@ Socket *VRmixin::worldDialogSock=NULL; Socket *VRmixin::worldRleSock=NULL; -MapBuilder& VRmixin::mapBuilder=VRmixin::getMapBuilder(); -Pilot VRmixin::pilot; -Lookout VRmixin::lookout; -ParticleFilter VRmixin::filter(VRmixin::getLocalSkS().getDualSpace(),VRmixin::getWorldSkS().getDualSpace()); +MapBuilder& VRmixin::getMapBuilder() { + static MapBuilder mapbuilderInstance; + return mapbuilderInstance; +} +MapBuilder& VRmixin::mapBuilder = VRmixin::getMapBuilder(); +Lookout& VRmixin::getLookout() { + static Lookout lookoutInstance; + return lookoutInstance; +} +Lookout& VRmixin::lookout = VRmixin::getLookout(); -unsigned int VRmixin::instanceCount=0; -unsigned int VRmixin::crewCount=0; +Pilot& VRmixin::getPilot() { + static Pilot pilotInstance; + return pilotInstance; +} +Pilot& VRmixin::pilot = VRmixin::getPilot(); + +PFShapeLocalization* VRmixin::particleFilter = NULL; // will be set by startCrew + +unsigned int VRmixin::instanceCount = 0; +unsigned int VRmixin::crewCount = 0; VRmixin::VRmixin() { if(instanceCount++==0) { // only want to do the following once //cout << "Initializing VRmixin statics" << endl; if (theOne != NULL) { - cerr << "VRmixin statics already constructed!?!?!" << endl; + if ( ! mapBuilder.isRetained() ) + cerr << "VRmixin statics already constructed!?!?!" << endl; return; } theOne=this; @@ -92,12 +103,12 @@ localSkS.requireIdx(); worldSkS.requireIdx(); - camDialogSock=wireless->socket(SocketNS::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE); - camRleSock=wireless->socket(SocketNS::SOCK_STREAM, 1024, RLE_BUFFER_SIZE); - worldDialogSock=wireless->socket(SocketNS::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE); - worldRleSock=wireless->socket(SocketNS::SOCK_STREAM, 1024, RLE_BUFFER_SIZE); - localDialogSock=wireless->socket(SocketNS::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE); - localRleSock=wireless->socket(SocketNS::SOCK_STREAM, 1024, RLE_BUFFER_SIZE); + camDialogSock=wireless->socket(Socket::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE); + camRleSock=wireless->socket(Socket::SOCK_STREAM, 1024, RLE_BUFFER_SIZE); + worldDialogSock=wireless->socket(Socket::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE); + worldRleSock=wireless->socket(Socket::SOCK_STREAM, 1024, RLE_BUFFER_SIZE); + localDialogSock=wireless->socket(Socket::SOCK_STREAM, 1024, DIALOG_BUFFER_SIZE); + localRleSock=wireless->socket(Socket::SOCK_STREAM, 1024, RLE_BUFFER_SIZE); wireless->setReceiver(camDialogSock->sock, &camDialogSockCallback); wireless->setReceiver(worldDialogSock->sock, &worldDialogSockCallback); @@ -124,7 +135,8 @@ worldSkS.viewer->setDialogSocket(worldDialogSock, WORLD_DIALOG_PORT); worldSkS.viewer->setRleSocket(worldRleSock, WORLD_RLE_PORT); - theAgent = Shape(worldShS,Point()); + theAgent = Shape(worldShS); + theAgent->setColor(rgb(0,0,255)); mapBuilder.SetAutoDelete(false); pilot.SetAutoDelete(false); @@ -134,6 +146,7 @@ VRmixin::~VRmixin() { if(--instanceCount==0) { + if ( mapBuilder.isRetained() ) return; // cout << "Destructing VRmixin statics" << endl; if (theOne == NULL) { cerr << "VRmixin statics already destructed!?!?!" << endl; @@ -165,12 +178,11 @@ localSkS.bumpRefreshCounter(); // release visible sketches localSkS.clear(); + theAgent = Shape(); worldShS.clear(); worldSkS.bumpRefreshCounter(); // release visible sketches worldSkS.clear(); - filter.reinitialize(); - camSkS.freeIndexes(); localSkS.freeIndexes(); worldSkS.freeIndexes(); @@ -178,7 +190,7 @@ } void VRmixin::startCrew() { - if(crewCount++==0) { + if ( crewCount++ == 0 ) { //cout << "Starting crew" << endl; mapBuilder.SetAutoDelete(false); mapBuilder.DoStart(); @@ -186,15 +198,19 @@ lookout.DoStart(); pilot.SetAutoDelete(false); pilot.DoStart(); + if ( particleFilter == NULL ) + particleFilter = new PFShapeLocalization(localShS,worldShS); } } void VRmixin::stopCrew() { - if(--crewCount==0) { + if ( --crewCount == 0 ) { //cout << "Stopping crew" << endl; pilot.DoStop(); lookout.DoStop(); mapBuilder.DoStop(); + delete particleFilter; + particleFilter = NULL; } } @@ -267,15 +283,15 @@ } //! Import channel n as a Sketch -Sketch VRmixin::sketchFromChannel(RawCameraGenerator::channel_id_t chan) { - if ( chan < 0 || chan >= RawCameraGenerator::NUM_CHANNELS) - chan = RawCameraGenerator::CHAN_Y; +Sketch VRmixin::sketchFromChannel(const RawCameraGenerator::channel_id_t chan) { + const RawCameraGenerator::channel_id_t the_chan = + (chan >= 0 && chan < RawCameraGenerator::NUM_CHANNELS) ? chan : RawCameraGenerator::CHAN_Y; Sketch cam(camSkS,"sketchFromChannel"); cam->setColorMap(grayMap); uchar* campixels = cam->getRawPixels(); int const incr = ProjectInterface::defRawCameraGenerator->getIncrement(CAM_LAYER); int const skip = ProjectInterface::defRawCameraGenerator->getSkip(CAM_LAYER); - uchar* chan_ptr = ProjectInterface::defRawCameraGenerator->getImage(CAM_LAYER,chan); + uchar* chan_ptr = ProjectInterface::defRawCameraGenerator->getImage(CAM_LAYER,the_chan); if(chan_ptr==NULL) { for (unsigned int row = 0; row < cam->getHeight(); row++) for (unsigned int col = 0; col < cam->getWidth(); col++) @@ -298,8 +314,11 @@ //! Import the results of the region generator as a vector of Shape vector > -VRmixin::getBlobsFromRegionGenerator(int color, int minarea, - BlobData::BlobOrientation_t orient, int maxblobs) { +VRmixin::getBlobsFromRegionGenerator(const color_index color, + const int minarea, + const BlobData::BlobOrientation_t orient, + const coordinate_t height, + const int maxblobs) { vector > result; const CMVision::run *rle_buffer = reinterpret_cast*> (ProjectInterface::defRLEGenerator->getImage(CAM_LAYER,CAM_CHANNEL)); @@ -310,7 +329,7 @@ const rgb rgbvalue = ProjectInterface::getColorRGB(color); const CMVision::region* list_head = ccs[color].list; for (int i=0; list_head!=NULL && iarea >= minarea; list_head = list_head->next, i++) { - BlobData* blobdat = BlobData::new_blob(camShS,*list_head, rle_buffer, orient, rgbvalue); + BlobData* blobdat = BlobData::new_blob(camShS,*list_head, rle_buffer, orient, height, rgbvalue); result.push_back(Shape(blobdat)); } return result; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/VRmixin.h ./DualCoding/VRmixin.h --- ../Tekkotsu_3.0/DualCoding/VRmixin.h 2006-05-10 19:21:57.000000000 -0400 +++ ./DualCoding/VRmixin.h 2007-11-18 01:47:02.000000000 -0500 @@ -12,10 +12,12 @@ #include "Vision/cmv_types.h" // needed for 'run' type? #include "Wireless/Wireless.h" #include "Shared/Config.h" +#include "Shared/RobotInfo.h" #include "Shared/get_time.h" // needed for time stamp, for serialization #include "ShapeAgent.h" #include "BlobData.h" +#include "PFShapeSLAM.h" #include "SketchRoot.h" namespace DualCoding { @@ -25,15 +27,14 @@ class SketchDataRoot; class SketchSpace; class MapBuilder; -class ParticleFilter; typedef unsigned char cmap_t; //! Mix-in for the BehaviorBase or StateNode class to give access to VisualRoutinesBehavior variables. class VRmixin { protected: - static unsigned int instanceCount; //!< count of NewVRmixin instances -- when this hits zero, free sketch spaces - static unsigned int crewCount; //!< count of "crew" (pilot, lookout, map builders) users -- stop these when no one is using them + static unsigned int instanceCount; //!< count of NewVRmixin instances -- when this hits zero, free sketch spaces + static unsigned int crewCount; //!< count of "crew" (pilot, lookout, map builders) users -- stop these when no one is using them public: //! returns reference to the global space instances, call there from global constructors instead of accessing #camSkS, which might not be initialized yet @@ -42,9 +43,6 @@ static SketchSpace& getWorldSkS(); static ShapeSpace& getGroundShS(); - //! returns reference to the global WorldMapBuilder instance, call this from global constructors instead of accessing #worldmap or #localmap, which might not be initialized yet - static MapBuilder& getMapBuilder(); - static SketchSpace& camSkS; //!< The camera sketch space static ShapeSpace& camShS; //!< The camera shape space @@ -57,11 +55,18 @@ static ShapeSpace& worldShS; //!< The worldmap sketch space (WorldMapBuilder::localShS) static Shape theAgent; //!< The robot (usually lives in worldShS) + //! returns reference to the global WorldMapBuilder instance, call this from global constructors instead of accessing #worldSkS/#localSkS/#groundShS/etc., which might not be initialized yet + static MapBuilder& getMapBuilder(); static MapBuilder& mapBuilder; //!< the global world mapbuilder instance - static Pilot pilot; //!< the global Pilot instance - static Lookout lookout; //!< the global Lookout instance - static ParticleFilter filter; //!< particle filter for localization + + static Lookout& getLookout(); + static Lookout &lookout; //!< the global Lookout instance + static Pilot& getPilot(); + static Pilot& pilot; //!< the global Pilot instance + + static PFShapeLocalization *particleFilter; //!< the global particle filter instance + private: static Socket *camDialogSock; //!< socket to talk with cam-space sketch viewer static Socket *camRleSock; //!< socket for transmitting RLE images to cam-space sketch viewer @@ -79,7 +84,7 @@ static void startCrew(); //!< starts map builders, pilot, and lookout static void stopCrew(); //!< stops map builders, pilot, and lookout - + // serialize the specified Sketch; should use RLE encoding later static bool rleEncodeSketch(const SketchDataRoot& image); @@ -87,16 +92,17 @@ static Sketch sketchFromSeg(); //! Import channel n image as a Sketch - static Sketch sketchFromChannel(RawCameraGenerator::channel_id_t chan); + static Sketch sketchFromChannel(const RawCameraGenerator::channel_id_t chan); //! Import the current y-channel camera image as a Sketch static Sketch sketchFromRawY(); //! Import blobs from the current region list as a vector of Shape static std::vector > - getBlobsFromRegionGenerator(int color, int minarea=0, - BlobData::BlobOrientation_t orient=BlobData::groundplane, - int maxblobs=50); + getBlobsFromRegionGenerator(const color_index color, int minarea=25, + const BlobData::BlobOrientation_t orient=BlobData::groundplane, + const coordinate_t height=0, + const int maxblobs=50); //! processes a single line of input for a Sketch request static void processSketchRequest(const std::string &line, @@ -104,8 +110,14 @@ ShapeSpace &shapes); //! project shapes from cam space to ground space +#ifdef TGT_HAS_CAMERA static void projectToGround(const NEWMAT::Matrix& camToBase = kine->jointToBase(CameraFrameOffset), const NEWMAT::ColumnVector& ground_plane = kine->calculateGroundPlane()); +#else + // no camera, require they provide the camToBase parameter... + static void projectToGround(const NEWMAT::Matrix& camToBase, + const NEWMAT::ColumnVector& ground_plane = kine->calculateGroundPlane()); +#endif private: //! used so static member functions can access non-static members diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ViewerConnection.h ./DualCoding/ViewerConnection.h --- ../Tekkotsu_3.0/DualCoding/ViewerConnection.h 2006-04-14 00:49:24.000000000 -0400 +++ ./DualCoding/ViewerConnection.h 2007-08-24 21:49:16.000000000 -0400 @@ -9,12 +9,16 @@ namespace DualCoding { -static const unsigned int DIALOG_BUFFER_SIZE=20000; // was 200000 from RawCamBehavior, but malloc sometimes failed -static const unsigned int RLE_BUFFER_SIZE=80000; // was 200000 from RawCamBehavior, but malloc sometimes failed - // Raised to 80000 for sketch +static const unsigned int DIALOG_BUFFER_SIZE=20000; + +#if defined(TGT_ERS7) || defined(TGT_ERS2xx) || defined(TGT_ERS210) || defined(TGT_ERS220) +static const unsigned int RLE_BUFFER_SIZE=70000; // Raised to 120000 for sketch in world space; then lowered to 70000 due to memory shortage +#else +static const unsigned int RLE_BUFFER_SIZE=500000; +#endif static const unsigned int CAM_LAYER=ProjectInterface::fullLayer; //!< the full resolution layer in the filter bank -static const unsigned int CAM_CHANNEL=0; //!< corresponds to appropriate thresholding listed in tekkotsu.cfg +static const unsigned int CAM_CHANNEL=0; //!< corresponds to appropriate thresholding listed in tekkotsu.xml static const unsigned int WORLD_WIDTH=225; static const unsigned int WORLD_HEIGHT=225; @@ -25,9 +29,6 @@ static const unsigned short WORLD_DIALOG_PORT = 5804; static const unsigned short WORLD_RLE_PORT = 5805; -#define CAM_WIDTH ProjectInterface::defSegmentedColorGenerator->getWidth(CAM_LAYER) -#define CAM_HEIGHT ProjectInterface::defSegmentedColorGenerator->getHeight(CAM_LAYER) - class ViewerConnection { private: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/VisualRoutinesBehavior.cc ./DualCoding/VisualRoutinesBehavior.cc --- ../Tekkotsu_3.0/DualCoding/VisualRoutinesBehavior.cc 2006-05-08 18:27:38.000000000 -0400 +++ ./DualCoding/VisualRoutinesBehavior.cc 2007-02-26 02:59:48.000000000 -0500 @@ -5,13 +5,17 @@ //---------------------------------------------------------------- void VisualRoutinesBehavior::DoStart() { - BehaviorBase::DoStart(); - startCrew(); + if ( !started ) { + BehaviorBase::DoStart(); + startCrew(); + } } void VisualRoutinesBehavior::DoStop() { - stopCrew(); - BehaviorBase::DoStop(); + if ( started ) { + stopCrew(); + BehaviorBase::DoStop(); + } } } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/VisualRoutinesStateNode.cc ./DualCoding/VisualRoutinesStateNode.cc --- ../Tekkotsu_3.0/DualCoding/VisualRoutinesStateNode.cc 2006-02-21 00:27:13.000000000 -0500 +++ ./DualCoding/VisualRoutinesStateNode.cc 2007-02-26 02:59:49.000000000 -0500 @@ -5,13 +5,17 @@ //---------------------------------------------------------------- void VisualRoutinesStateNode::DoStart() { - StateNode::DoStart(); - startCrew(); + if ( !started ) { + StateNode::DoStart(); + startCrew(); + } } void VisualRoutinesStateNode::DoStop() { - stopCrew(); - StateNode::DoStop(); + if ( started ) { + stopCrew(); + StateNode::DoStop(); + } } } // namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/visops.cc ./DualCoding/visops.cc --- ../Tekkotsu_3.0/DualCoding/visops.cc 2006-08-10 23:09:36.000000000 -0400 +++ ./DualCoding/visops.cc 2007-11-11 18:57:22.000000000 -0500 @@ -22,34 +22,34 @@ return result; } -Sketch colormask(const Sketch& src, std::string colorname) { +Sketch colormask(const Sketch& src, const std::string &colorname) { return colormask(src, ProjectInterface::getColorIndex(colorname)); } -Sketch colormask(const Sketch& src, int color_idx) { - Sketch result(src == color_idx); - result->setColor(ProjectInterface::getColorRGB(color_idx)); +Sketch colormask(const Sketch& src, color_index cindex) { + Sketch result(src == cindex); + result->setColor(ProjectInterface::getColorRGB(cindex)); return result; } -Sketch bdist(const Sketch& dest, +Sketch bdist(const Sketch& dest, const Sketch& obst, - const int maxdist) { + const uint maxdist) { SketchSpace &space = dest->getSpace(); space.requireIdx4way(); - Sketch result("bdist("+dest->getName()+","+obst->getName()+")", dest); - result = (usint)-1; // 99999999;//FP_INFINITE; // if FP_INFINITE, means dist not calc'd yet for pixel + Sketch result("bdist("+dest->getName()+","+obst->getName()+")", dest); + result = maxdist; result->setColorMap(jetMapScaled); - // want to start at the target, and iteratively expand out the frontier + // Start at the target and iteratively expand out the frontier SketchIndices frontier; frontier.addIndices(dest); result.setIndices(frontier, 0); SketchIndices obstInds; obstInds.addIndices(obst); SketchIndices newFrontier, oldFrontier; - - for (float dist = 1; dist < maxdist; dist++) { + + for (uint dist = 1; dist < maxdist; dist++) { // newFrontier should become all values adjacent to frontier, not // actually in the frontier, not a boundary, or in oldFrontier newFrontier = frontier[*space.idxN] + frontier[*space.idxS] @@ -67,14 +67,14 @@ return result; } -Sketch edist(const Sketch& target) { +Sketch edist(const Sketch& target) { SketchSpace &space = target->getSpace(); const int width = space.getWidth(); const int height = space.getHeight(); - const usint maxdist = width + height + 1; + const uint maxdist = width + height + 1; // at the moment doing 4-pass linear Manhattan distance, but should // probably use linear-time Euclidean algorithm described in - Sketch dist("edist("+target->getName()+")", target); + Sketch dist("edist("+target->getName()+")", target); dist = maxdist; dist->setColorMap(jetMapScaled); @@ -82,16 +82,16 @@ for (int j = 0; j < height; j++) { for (int i = 0, cur_dist = maxdist; i < width; i++) { if (target(i,j) == 1) - dist(i,j) = cur_dist = 0; - else if (dist(i,j) < cur_dist) - cur_dist = dist(i,j); + dist(i,j) = cur_dist = 0; + else if (dist(i,j) < (uint)cur_dist) + cur_dist = dist(i,j); else dist(i,j) = cur_dist; cur_dist++; } for (int i = width-1, cur_dist = maxdist; i >= 0; i--) { if (target(i,j) == true) dist(i,j) = cur_dist = 0; - else if (dist(i,j) < cur_dist) + else if (dist(i,j) < (uint)cur_dist) cur_dist = dist(i,j); else dist(i,j) = cur_dist; @@ -102,27 +102,27 @@ for (int i = 0; i < width; i++) { for (int j = 0, cur_dist = maxdist; j < height; j++) { if (target(i,j) == 1) - dist(i,j) = cur_dist = 0; - else if (dist(i,j) < cur_dist) - cur_dist = dist(i,j); + dist(i,j) = cur_dist = 0; + else if (dist(i,j) < (uint)cur_dist) + cur_dist = dist(i,j); else - dist(i,j) = cur_dist; + dist(i,j) = cur_dist; cur_dist++; } for (int j = height-1, cur_dist = maxdist; j >= 0; j--) { if (target(i,j) == 1) - dist(i,j) = cur_dist = 0; - else if (dist(i,j) < cur_dist) - cur_dist = dist(i,j); + dist(i,j) = cur_dist = 0; + else if (dist(i,j) < (uint)cur_dist) + cur_dist = dist(i,j); else - dist(i,j) = cur_dist; + dist(i,j) = cur_dist; cur_dist++; } } return dist; } -Sketch labelcc(const Sketch& sketch, int minarea) { +Sketch labelcc(const Sketch& sketch, int minarea) { Sketch temp; uchar *pixels; if ( sizeof(bool) == sizeof(uchar) ) @@ -149,7 +149,7 @@ CMVision::MergeRegions(ccs, numColors, rle_buffer); // extract regions from region list - NEW_SKETCH(result, usint, visops::zeros(sketch)); + NEW_SKETCH_N(result, uint, visops::zeros(sketch)); result->setColorMap(jetMapScaled); const CMVision::region* list_head = ccs[1].list; if ( list_head != NULL ) { @@ -174,19 +174,19 @@ } // written with guidance from this page: http://www.dai.ed.ac.uk/HIPR2/label.htm -Sketch oldlabelcc(const Sketch& source, Connectivity_t connectivity) +Sketch oldlabelcc(const Sketch& source, Connectivity_t connectivity) { bool conn8 = (connectivity == EightWayConnect); const int width = source.width; const int height = source.height; - Sketch labels("oldlabelcc("+source->getName()+")",source); + Sketch labels("oldlabelcc("+source->getName()+")",source); labels = 0; labels->setColorMap(jetMapScaled); // First scan: Give initial labels and sort connected label classes // into equivalence classes using UNION-FIND // Doing something similar to tree-based UNION-FIND, without the tree - vector eq_classes(500); // vector of equivalence classes for union-find + std::vector eq_classes(500); // vector of equivalence classes for union-find eq_classes.clear(); eq_classes.push_back(0); // added just so that indices match up with labels int highest_label = 0; @@ -280,25 +280,25 @@ return labels; } -Sketch areacc(const Sketch& source, Connectivity_t connectivity) { - NEW_SKETCH_N(labels, usint, visops::oldlabelcc(source,connectivity)); +Sketch areacc(const Sketch& source, Connectivity_t connectivity) { + NEW_SKETCH_N(labels, uint, visops::oldlabelcc(source,connectivity)); return visops::areacc(labels); } -Sketch areacc(const Sketch& labels) { - vector areas(1+labels->max(), 0); - for (usint i = 0; igetNumPixels(); i++) +Sketch areacc(const Sketch& labels) { + std::vector areas(1+labels->max(), 0); + for (uint i = 0; igetNumPixels(); i++) ++areas[labels[i]]; areas[0] = 0; - Sketch result("areacc("+labels->getName()+")",labels); - for (usint i = 0; igetNumPixels(); i++) + Sketch result("areacc("+labels->getName()+")",labels); + for (uint i = 0; igetNumPixels(); i++) result[i] = areas[labels[i]]; return result; } Sketch minArea(const Sketch& sketch, int minval) { - NEW_SKETCH_N(labels, usint, visops::labelcc(sketch)); - NEW_SKETCH_N(areas, usint, visops::areacc(labels)); + NEW_SKETCH_N(labels, uint, visops::labelcc(sketch)); + NEW_SKETCH_N(areas, uint, visops::areacc(labels)); NEW_SKETCH_N(result, bool, areas >= minval); return result; } @@ -314,15 +314,17 @@ Sketch result("neighborSum("+im->getName()+")", im); result->setColorMap(jetMapScaled); - result = im[*space.idxN]; - result += im[*space.idxS]; - result += im[*space.idxW]; - result += im[*space.idxE]; - if (connectivity == EightWayConnect) { - result += im[*space.idxNW]; - result += im[*space.idxNE]; - result += im[*space.idxSW]; - result += im[*space.idxSE]; + for ( unsigned int i = 0; i < im->getNumPixels(); i++ ) { + uchar cnt = (uchar)im[(*space.idxN)[i]] + + (uchar)im[(*space.idxS)[i]] + + (uchar)im[(*space.idxE)[i]] + + (uchar)im[(*space.idxW)[i]]; + if (connectivity == EightWayConnect) + cnt += (uchar)im[(*space.idxNE)[i]] + + (uchar)im[(*space.idxNW)[i]] + + (uchar)im[(*space.idxSE)[i]] + + (uchar)im[(*space.idxSW)[i]]; + result[i] = cnt; } return result; } @@ -442,21 +444,50 @@ } */ -Sketch skel(const Sketch& im) -{ +Sketch skel(const Sketch& im) { NEW_SKETCH_N(result, bool, horsym(im) | versym(im)); result->setName("skel("+im->getName()+")"); return result; } -Sketch seedfill(const Sketch& borders, size_t index) -{ +Sketch seedfill(const Sketch& borders, size_t index) { // use four-way connect so thin diagonal line can function as a boundary - NEW_SKETCH_N(regions, usint, oldlabelcc(! borders, visops::FourWayConnect)); + NEW_SKETCH_N(regions, uint, oldlabelcc(! borders, visops::FourWayConnect)); NEW_SKETCH_N(result, bool, regions == regions->at(index)); // use at() to do bounds checking return result; } +// helper function called only inside visops::fillExterior +void fillExteriorHelper(const Sketch ®ions, Sketch &result, std::vector &processed, + const int x, const int y) { + const uint c = regions(x,y); + if ( c > 0 && !processed[c] ) { + result |= (regions == c); + processed[c] = true; + } +} + +Sketch fillExterior(const Sketch& borders) { + // use four-way connect so thin diagonal line can function as a boundary + NEW_SKETCH_N(regions, uint, oldlabelcc(! borders, visops::FourWayConnect)); + const uint numreg = regions->max(); + std::vector processed(numreg+1,false); + NEW_SKETCH_N(result, bool, visops::zeros(borders)); + for ( int x = 0; x < result.width; x++ ) { + fillExteriorHelper(regions,result,processed,x,0); + fillExteriorHelper(regions,result,processed,x,result.height-1); + } + for ( int y = 0; y < result.height; y++ ) { + fillExteriorHelper(regions,result,processed,0,y); + fillExteriorHelper(regions,result,processed,result.width-1,y); + } + return result; +} + +Sketch fillInterior(const Sketch& borders) { + return ! (borders | fillExterior(borders)); +} + Sketch leftHalfPlane(const Shape &ln) { SketchSpace &SkS = ln->getSpace().getDualSpace(); //! @todo **** THIS visops::leftHalfPlane CODE NEEDS TO CHECK THE SketchSpace ReferenceFrameType **** BECAUSE "left" MEANS DIFFERENT THINGS IN DIFFERENT FRAMES @@ -471,8 +502,10 @@ seed = ( x1 <= 0 ) ? -1 : 0; else if ( ln->getOrientation() > M_PI/2 ) seed = ( b <= 0) ? -1 : 0; - else - seed = ( b < (int)SkS.getHeight() - 1 ) ? (*SkS.idx)(0,SkS.getHeight()-1) : -1; + else { + int const lim = SkS.getHeight() - 1; + seed = ( b < lim ) ? (int)(*SkS.idx)(0,lim) : -1; + } if ( seed == -1 ) { NEW_SKETCH_N(result, bool, visops::zeros(SkS)); result->inheritFrom(ln); @@ -508,8 +541,10 @@ seed = ( y1 <= 0 ) ? -1 : 0; else if ( ln->getOrientation() > M_PI/2 ) seed = ( b <= 0) ? -1 : 0; - else - seed = ( int(m*(SkS.getWidth()-1)+b) > 0 ) ? (*SkS.idx)(SkS.getWidth()-1,0) : -1; + else { + int const lim = SkS.getWidth() - 1; + seed = ( int(m*lim+b) > 0 ) ? (int)(*SkS.idx)(lim,0) : -1; + } if ( seed == -1 ) { NEW_SKETCH_N(result, bool, visops::zeros(SkS)); result->inheritFrom(ln); @@ -604,9 +639,9 @@ return result; } -Sketch convolve(const Sketch &sketch, Sketch &kernel, +Sketch convolve(const Sketch &sketch, Sketch &kernel, int istart, int jstart, int width, int height) { - Sketch result("convolve("+sketch->getName()+")",sketch); + Sketch result("convolve("+sketch->getName()+")",sketch); result->setColorMap(jetMapScaled); int const di = - (int)(width/2); int const dj = - (int)(height/2); @@ -617,15 +652,15 @@ for (int kj=0; kj= 0 && si+di+ki < sketch.width && sj+dj+kj >= 0 && sj+dj+kj < sketch.height ) - sum += (usint)sketch(si+di+ki,sj+dj+kj) * (usint)kernel(istart+ki,jstart+kj); + sum += (uint)sketch(si+di+ki,sj+dj+kj) * (uint)kernel(istart+ki,jstart+kj); result(si,sj) = sum/(width*height); } return result; } -Sketch templateMatch(const Sketch &sketch, Sketch &kernel, +Sketch templateMatch(const Sketch &sketch, Sketch &kernel, int istart, int jstart, int width, int height) { - Sketch result("convolve0("+sketch->getName()+")",sketch); + Sketch result("convolve0("+sketch->getName()+")",sketch); result->setColorMap(jetMapScaled); int const npix = width * height; int const di = - (int)(width/2); @@ -644,7 +679,7 @@ else sum += k_pix * k_pix; } - result(si,sj) = 65535 - usint(sqrt(sum/float(npix))); + result(si,sj) = 65535 - uint(sqrt(sum/float(npix))); } result = result - result->min(); return result; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/visops.h ./DualCoding/visops.h --- ../Tekkotsu_3.0/DualCoding/visops.h 2006-09-15 03:09:49.000000000 -0400 +++ ./DualCoding/visops.h 2007-11-11 18:57:22.000000000 -0500 @@ -8,14 +8,15 @@ #include "ShapeLine.h" -using namespace DualCoding; -using DualCoding::uchar; - class DualCoding::SketchIndices; //! Visual routines operators, used in DualCoding. namespace visops { - + + using namespace DualCoding; + using DualCoding::uchar; + using DualCoding::uint; + //! Connectivity used by oldlabelcc and neighborsum. enum Connectivity_t { FourWayConnect, EightWayConnect }; @@ -28,13 +29,11 @@ //! Returns an all-zero Sketch of same size as parent @a sketch Sketch zeros(const SketchRoot& sketch); - //! Returns a copy of the sketch. + //! Returns a deep copy of the sketch: actually copies the pixels template Sketch copy(const Sketch& other) { - Sketch result("copy("+other->getName()+")", other); + Sketch result("copy("+other->getName()+")", other); // will inherit from parent *result.pixels = *other.pixels; // valarray assignment - result->setColor(other->getColor()); - result->setColorMap(other->getColorMap()); return result; } @@ -48,7 +47,7 @@ Sketch max(const Sketch& src, const T value) { Sketch result("max(const)",src); for ( unsigned int i = 0; i < src.pixels->size()-1; i++ ) - (*result.pixels)[i] = ::max((*src.pixels)[i],value); + (*result.pixels)[i] = std::max((*src.pixels)[i],value); return result; } @@ -62,9 +61,9 @@ //! Pixel-wise max of two sketches template Sketch max(const Sketch& arg1, const Sketch& arg2) { - Sketch result("max("+arg1->getName()+","+arg2->getName+")",arg1); + Sketch result("max("+arg1->getName()+","+arg2->getName()+")",arg1); for ( unsigned int i = 0; i < arg1.pixels->size()-1; i++ ) - (*result.pixels)[i] = ::max((*arg1.pixels)[i],(*arg2.pixels)[i]); + (*result.pixels)[i] = std::max((*arg1.pixels)[i],(*arg2.pixels)[i]); return result; } @@ -73,7 +72,7 @@ Sketch min(const Sketch& src, const T value) { Sketch result("min(const)",src); for ( unsigned int i = 0; i < src.pixels->size()-1; i++ ) - (*result.pixels)[i] = ::min((*src.pixels)[i],value); + (*result.pixels)[i] = std::min((*src.pixels)[i],value); return result; } @@ -86,25 +85,36 @@ //! Pixel-wise min of two sketches template Sketch min(const Sketch& arg1, const Sketch& arg2) { - Sketch result("min("+arg1->getName()+","+arg2->getName+")",arg1); + Sketch result("min("+arg1->getName()+","+arg2->getName()+")",arg1); for ( unsigned int i = 0; i < arg1.pixels->size()-1; i++ ) - (*result.pixels)[i] = ::min((*arg1.pixels)[i],(*arg2.pixels)[i]); + (*result.pixels)[i] = std::min((*arg1.pixels)[i],(*arg2.pixels)[i]); return result; } //@} + //!@name Region filling + //@{ + + //! Fills a region bounded by borders, starting at position given by index + Sketch seedfill(const Sketch& borders, size_t index); + + //! Fills the exterior of region bounded by borders, starting from the edges of the sketch; border pixels are not filled + Sketch fillExterior(const Sketch& borders); + + //! Fills the interior of region bounded by borders, i.e., pixels not reachable from the edges of the sketch; border pixels are not filled + Sketch fillInterior(const Sketch& borders); + + //@} + //!@name Miscellaneous functions //@{ //! Returns all the pixels of the named color. - Sketch colormask(const Sketch& src, const std::string colorname); + Sketch colormask(const Sketch& src, const std::string &colorname); //! Returns all the pixels with the specified color index. - Sketch colormask(const Sketch& src, int color_idx); - - //! Fills a region bounded by borders, starting at position given by index - Sketch seedfill(const Sketch& borders, size_t index); + Sketch colormask(const Sketch& src, color_index cindex); //! For each pixel, calculate the sum of its neighbors. /*! @param im Sketch to use as input. @@ -127,41 +137,56 @@ //@{ /*! @brief Calculates the distance from each pixel in the image to the closest - true pixel in dest, using the wavefront algorithm. - Obstacles indicated by true values in pixels of obst. */ - Sketch bdist(const Sketch &dest, const Sketch &obst, - const int maxdist=100); + true pixel in destination @a dest, using the wavefront algorithm. + Obstacles indicated by true values in pixels of @a obst. Note: use maxdist=width+height + if you want the result to be viewable with the jetMapScaled colormap. + */ + Sketch bdist(const Sketch &dest, const Sketch &obst, + const uint maxdist=(uint)-1); //! Euclidean distance to the nearest true pixel in @a dest /*! Should calculate the Euclidean distance from each pixel in the image * to the closest true pixel in dest, using a linear-time algorithm. * Currently calculates Manhattan distance, which is good enough. * Should be used instead of bdist if not concerned about obstacles. */ - Sketch edist(const Sketch &dest); + Sketch edist(const Sketch &dest); //! Connected components labeling using CMVision. Components numbered sequentially from 1. - Sketch labelcc(const Sketch& source, int minarea=1); + Sketch labelcc(const Sketch& source, int minarea=1); //! Old connected-components code written using pure sketch primitives. /*! Returns a connected-components labeling of the foreground. Each different foreground region will contain a unique positive integer. No guarantees on the integer values. */ - Sketch oldlabelcc(const Sketch& source, + Sketch oldlabelcc(const Sketch& source, Connectivity_t connectivity=EightWayConnect); //! Each pixel of the result is the area of that connected component. - Sketch areacc(const Sketch& source, Connectivity_t connectivity=EightWayConnect); + Sketch areacc(const Sketch& source, Connectivity_t connectivity=EightWayConnect); //! Each pixel of the result is the area of that connected component. - Sketch areacc(const Sketch& labels); + Sketch areacc(const Sketch& labels); //! Low-pass filter by eliminating small regions Sketch minArea(const Sketch& sketch, int minval=5); //@} - //! @name Conditional assignment + //! @name Masking and conditional assignment //@{ + //! Returns pixels of @a A masked by bool sketch @a B + template + Sketch mask(const Sketch &A, const Sketch &B) { + Sketch result("mask("+A->getName()+","+B->getName()+")", A); + T* Aptr = &(*A.pixels)[0]; + T* Rptr = &(*result.pixels)[0]; + T* Rend = &(*result.pixels)[result->getNumPixels()]; + unsigned int idx = 0; + while ( Rptr != Rend ) + *Rptr++ = B[idx++] * (*Aptr++); + return result; + } + //! Result holds non-zero pixels of @a A, with zero pixels filled in by @a B. /*! Equivalent to writing maskedAssign(A,A==0,B) */ template @@ -255,6 +280,7 @@ Sketch topHalfPlane(const Shape &ln); Sketch bottomHalfPlane(const Shape &ln); + //@} //! Returns a copy of im except that its pixels within offset from boundaries are removed Sketch non_bounds(const Sketch& im, int offset); @@ -269,11 +295,11 @@ Sketch susan_edge_points(const Sketch& im, int brightness); //! Convolves a kernel with an image. - Sketch convolve(const Sketch &sketch, Sketch &kernel, + Sketch convolve(const Sketch &sketch, Sketch &kernel, int i, int j, int width, int height); //! Convolves a kernel with an image, normalizing the kernel to zero mean. - Sketch templateMatch(const Sketch &sketch, Sketch &kernel, + Sketch templateMatch(const Sketch &sketch, Sketch &kernel, int i, int j, int width, int height); //@} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/DataEvent.h ./Events/DataEvent.h --- ../Tekkotsu_3.0/Events/DataEvent.h 2005-06-29 18:03:34.000000000 -0400 +++ ./Events/DataEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -5,14 +5,14 @@ #include "Events/EventBase.h" //! for passing around data (or pointers to data) -template +template class DataEvent : public EventBase { public: //!@name Constructors //! - DataEvent() : EventBase() {} - DataEvent(const T& d, EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur=0) : EventBase(gid,sid,tid,dur), data(d) {} - DataEvent(const T& d, EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) : EventBase(gid,sid,tid,dur,n,mag), data(d) {} + DataEvent() : EventBase(), data() {} + DataEvent(const T& d, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur=0) : EventBase(gid,sid,tid,dur), data(d) {} + DataEvent(const T& d, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) : EventBase(gid,sid,tid,dur,n,mag), data(d) {} //! copy constructor DataEvent(const DataEvent& evt) : EventBase(evt), data(evt.data) {} @@ -27,10 +27,29 @@ const T& getData() const { return data; } //!< returns #data T& getData() { return data; } //!< returns #data + virtual classTypeID_t getClassTypeID() const { return autoRegisterDataEvent; } + protected: T data; //!< the data being communicated + + //! this silliness is to work around parsing issue in gcc 3.3 branch + static EventBase::classTypeID_t registerDataType(EventBase::classTypeID_t classid) { +#if !defined(__GNUC__) || __GNUC__>3 || __GNUC__==3 && __GNUC_MINOR__>3 + // if here, using gcc 3.4 or later... + // gcc 3.3 won't let me call this templated member function?!?! + return getTypeRegistry().registerType< DataEvent >(classid); +#else // using gcc 3.3.x or prior + // instead I have to wind up registering my own instance instead of using the FamilyFactory's instance generation + return getTypeRegistry().registerFactory(classid,new EventBase::registry_t::FactoryType< DataEvent >); +#endif + } + static const EventBase::classTypeID_t autoRegisterDataEvent; //!< causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) }; +template +const EventBase::classTypeID_t DataEvent::autoRegisterDataEvent=DataEvent::registerDataType(makeClassTypeID("DATA")+(TID<0?getTypeRegistry().getNumTypes():TID)); + + /*! @file * @brief Defines DataEvent, for passing around data (or pointers to data) * @author ejt (Creator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventBase.cc ./Events/EventBase.cc --- ../Tekkotsu_3.0/Events/EventBase.cc 2006-09-21 17:26:07.000000000 -0400 +++ ./Events/EventBase.cc 2007-11-12 23:16:02.000000000 -0500 @@ -1,14 +1,24 @@ #include "EventBase.h" +#include "EventRouter.h" #include #include #include #include "Shared/debuget.h" +#include "Events/RemoteRouter.h" + +// just to give linkage for the auto register: +const EventBase::classTypeID_t EventBase::autoRegisterEventBase=getTypeRegistry().registerType(makeClassTypeID("BASE")); +#include "FilterBankEvent.h" +const EventBase::classTypeID_t FilterBankEvent::autoRegisterFilterBankEvent=getTypeRegistry().registerType(makeClassTypeID("FBKE")); +#include "SegmentedColorFilterBankEvent.h" +const EventBase::classTypeID_t SegmentedColorFilterBankEvent::autoRegisterSegmentedColorFilterBankEvent=getTypeRegistry().registerType(makeClassTypeID("SFBK")); const char* const EventBase::EventGeneratorNames[numEGIDs] = { "unknownEGID", "aiEGID", "audioEGID", "buttonEGID", + "cameraResolutionEGID", "erouterEGID", "estopEGID", "locomotionEGID", @@ -38,6 +48,7 @@ "visObjEGID", "wmVarEGID", "worldModelEGID", + "remoteStateEGID" }; const char* const EventBase::EventTypeNames[numETIDs] = { @@ -48,14 +59,21 @@ const char* const EventBase::EventTypeAbbr[numETIDs] = { "A", "S", "D" }; +EventBase::registry_t& EventBase::getTypeRegistry() { + static registry_t typeRegistry; + return typeRegistry; +} + EventBase::EventBase() - : XMLLoadSave(), stim_id(), magnitude(0), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(unknownEGID), typeID(statusETID), sourceID((unsigned int)-1), duration(0) + : XMLLoadSave(), stim_id(), magnitude(0), timestamp(get_time()), saveFormat(XML), + nameisgen(true), genID(unknownEGID), typeID(statusETID), sourceID((size_t)-1), + hostID(-1), duration(0) { genName(); } -EventBase::EventBase(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur) - : XMLLoadSave(), stim_id(), magnitude(0), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(gid), typeID(tid), sourceID(sid), duration(dur) +EventBase::EventBase(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur) + : XMLLoadSave(), stim_id(), magnitude(0), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(gid), typeID(tid), sourceID(sid), hostID(-1), duration(dur) { genName(); if(tid==deactivateETID) @@ -64,8 +82,8 @@ setMagnitude(1.0); } -EventBase::EventBase(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n) - : XMLLoadSave(), stim_id(), magnitude(0), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(gid), typeID(tid), sourceID(sid), duration(dur) +EventBase::EventBase(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n) + : XMLLoadSave(), stim_id(), magnitude(0), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(gid), typeID(tid), sourceID(sid), hostID(-1), duration(dur) { setName(n); if(tid==deactivateETID) @@ -74,8 +92,8 @@ setMagnitude(1.0); } -EventBase::EventBase(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) - : XMLLoadSave(), stim_id(), magnitude(mag), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(gid), typeID(tid), sourceID(sid), duration(dur) +EventBase::EventBase(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) + : XMLLoadSave(), stim_id(), magnitude(mag), timestamp(get_time()), saveFormat(XML), nameisgen(true), genID(gid), typeID(tid), sourceID(sid), hostID(-1), duration(dur) { setName(n); } @@ -95,6 +113,12 @@ stim_id+=sourcename; stim_id+=','; stim_id+=EventTypeAbbr[getTypeID()]; + + if (hostID != -1) { + stim_id += ','; + stim_id += EventRouter::intToStringIP(hostID); + } + stim_id+=')'; nameisgen=false; return *this; @@ -126,6 +150,7 @@ used+=getSerializedSize(); //genID is an enum, override to char used+=getSerializedSize(); //typeID is an enum, override to char used+=getSerializedSize(sourceID); + used+=getSerializedSize(hostID); used+=getSerializedSize(duration); return used; } @@ -144,7 +169,10 @@ if(!decodeInc(tmp,buf,len)) return 0; typeID=(EventTypeID_t)tmp; if(!decodeInc(sourceID,buf,len)) return 0; + if(!decodeInc(hostID,buf,len)) return 0; if(!decodeInc(duration,buf,len)) return 0; + + genName(); return origlen-len; } @@ -159,6 +187,7 @@ if(!encodeInc((char)genID,buf,len)) return 0; if(!encodeInc((char)typeID,buf,len)) return 0; if(!encodeInc(sourceID,buf,len)) return 0; + if(!encodeInc(hostID,buf,len)) return 0; if(!encodeInc(duration,buf,len)) return 0; return origlen-len; } @@ -178,11 +207,19 @@ if(i==numEGIDs) throw bad_format(node,"bad event generator name"); genID=static_cast(i); + str = xmlGetProp(node,(const xmlChar*)"sid"); if(str==NULL) throw bad_format(node,"missing source id"); - sourceID=atoi((const char*)str); + std::stringstream((const char*)str) >> sourceID; + xmlFree(str); + + str = xmlGetProp(node,(const xmlChar*)"hid"); + if(str==NULL) + throw bad_format(node,"missing host id"); + hostID=atoi((const char*)str); xmlFree(str); + str = xmlGetProp(node,(const xmlChar*)"etid"); if(str==NULL) throw bad_format(node,"missing type id"); @@ -222,8 +259,13 @@ xmlNodeSetName(node,(const xmlChar*)"event"); xmlSetProp(node,(const xmlChar*)"egid",(const xmlChar*)EventGeneratorNames[genID]); char buf[20]; + snprintf(buf,20,"%lu",static_cast(sourceID)); xmlSetProp(node,(const xmlChar*)"sid",(const xmlChar*)buf); + + snprintf(buf,20,"%lu",static_cast(hostID)); + xmlSetProp(node,(const xmlChar*)"hid",(const xmlChar*)buf); + xmlSetProp(node,(const xmlChar*)"etid",(const xmlChar*)EventTypeAbbr[typeID]); snprintf(buf,20,"%u",timestamp); xmlSetProp(node,(const xmlChar*)"time",(const xmlChar*)buf); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventBase.h ./Events/EventBase.h --- ../Tekkotsu_3.0/Events/EventBase.h 2006-10-03 19:19:23.000000000 -0400 +++ ./Events/EventBase.h 2007-11-12 23:16:02.000000000 -0500 @@ -4,6 +4,7 @@ #include "Shared/get_time.h" #include "Shared/XMLLoadSave.h" +#include "Shared/FamilyFactory.h" #include //! Forms the basis of communication between modules/behaviors in the framework @@ -30,7 +31,7 @@ * When the generator doesn't have groups of activity with a 'begin' or 'end', it will use #statusETID * for all of its events. (in other words, not all generators necessarily have to use activate or deactivate) * For example, sensor updates are continuously occuring, so you will only ever see - *
(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID)
+ *
(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID)
* * The #duration field is also generator specific - some may refer to * the time since the last activation event (e.g. button events) @@ -82,6 +83,7 @@ aiEGID, //!< not being used, yet (might use this when AI makes decisions?) audioEGID, //!< Sends an event when a sound starts/ends playback, status events as chained sounds end; SID is SoundManager::Play_ID; duration is playtime buttonEGID, //!< Sends activate event for button down, deactivate for button up. Status events only for when pressure sensitive buttons' reading changes. (on sensorEGID updates); SIDs are from ButtonOffset_t in the namespace of the target model (e.g. ERS210Info::ButtonOffset_t); duration is button down time + cameraResolutionEGID, //!< Sends a status event whenever the camera's resolution changes, such as a different camera than predicted by RobotInfo is being used, or a camera is hotswapped. SID corresponds to the visOFbkEGID for that camera. erouterEGID, //!< Sends activate event on first listener, deactivate on last listener, and status on other listener changes.; SID is the generator ID affected estopEGID, //!< Sends an event when the estop is turned on or off; SID is the MotionManager::MC_ID of the EmergencyStopMC; duration is length of estop activation locomotionEGID, //!< Sends events regarding transportation in the world; you can/should assume these will all be LocomotionEvent classes; SID is MotionManager::MC_ID of posting MotionCommand; duration is the time since last velocity change of that MC. (You could generate these for things other than walking...) @@ -93,8 +95,8 @@ micPitchEGID, //!< Sends a PitchEvent when a particular frequency is detected; SID is a pointer to the PitchDetector, magnitude is product of amplitude and confidence motmanEGID, //!< Sends events when a MotionCommand is added or removed, SID is is the MotionManager::MC_ID, duration is always 0; individual MotionCommands may throw status events to signal intermediary status pilotEGID, //!< Sends events when position of agent is updated or pilot request is completed - powerEGID, //!< Sends events for low power warnings, temperature, etc. see PowerSourceID::PowerSourceID_t - sensorEGID, //!< Sends a status event when new sensor readings are available. see SensorSourceID::SensorSourceID_t + powerEGID, //!< Sends events for low power warnings, temperature, etc. see PowerSrcID::PowerSourceID_t + sensorEGID, //!< Sends a status event when new sensor readings are available. see SensorSrcID::SensorSourceID_t stateMachineEGID, //!< Sends an event upon entering and leaving a StateNode; SID is pointer to the StateNode; duration is always 0; some state will throw a status event when they have completed their task and are now idling stateSignalEGID, //!< Sends a DataEvent that can be monitored by a SignalTrans for triggering a state transition stateTransitionEGID, //!< Sends an event each time a transition is triggered; SID is a pointer to the transition; type is always status, duration is always 0; guaranteed to occur immediately *before* the transition actually occurs @@ -111,6 +113,7 @@ visObjEGID, //!< Sends VisionObjectEvents for objects detected in camera images; SID is whatever value you gave during setup (typically in StartupBehavior_SetupVision.cc), duration is always 0 wmVarEGID, //!< Sends an event when a watched memory is changed; source id is pointer to WMEntry worldModelEGID, //!< not being used, yet (for when objects are detected/lost?) + remoteStateEGID, //!< Sent when remote state is updated numEGIDs //!< the number of generators available }; @@ -130,14 +133,23 @@ //! holds abbreviated string versions of EventTypeID_t static const char* const EventTypeAbbr[numETIDs]; + + //! type used for class ids in the type registry (see getTypeRegistry()) + typedef unsigned int classTypeID_t; + + //! type used for the type registry + typedef FamilyFactory registry_t; + //! returns a FamilyFactory with which you can look up classTypeID_t's to make new instances from serialized data + static registry_t& getTypeRegistry(); + /*! @name Constructors/Destructors */ //! constructor /*! @see EventRouter::postEvent() */ EventBase(); - EventBase(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur=0); - EventBase(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n); - EventBase(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag); + EventBase(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur=0); + EventBase(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n); + EventBase(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag); virtual ~EventBase() {} //!< destructor //! allows a copy to be made of an event, supporting polymorphism @@ -163,12 +175,16 @@ virtual EventGeneratorID_t getGeneratorID() const { return genID; } /*!< @brief gets the generator ID for this event @see EventGeneratorID_t */ virtual EventBase& setGeneratorID(EventGeneratorID_t gid) { genID=gid; genName(); return *this; } /*!< @brief sets the generator ID for this event @see EventGeneratorID_t */ - virtual unsigned int getSourceID() const { return sourceID; } /*!< @brief gets the source ID for this event @see sourceID */ - virtual EventBase& setSourceID(unsigned int sid) { sourceID=sid; genName(); return *this; } /*!< @brief sets the source ID for this event @see sourceID */ + virtual size_t getSourceID() const { return sourceID; } /*!< @brief gets the source ID for this event @see sourceID */ + virtual EventBase& setSourceID(size_t sid) { sourceID=sid; genName(); return *this; } /*!< @brief sets the source ID for this event @see sourceID */ virtual EventTypeID_t getTypeID() const { return typeID; } /*!< @brief gets the type ID @see EventTypeID_t */ virtual EventBase& setTypeID(EventTypeID_t tid) { typeID=tid; unsigned int n=strlen(EventTypeAbbr[typeID]); stim_id.replace(stim_id.size()-n-1,n,EventTypeAbbr[typeID]); return *this; } /*!< @brief sets the type ID @see EventTypeID_t */ + + virtual int getHostID() const { return hostID; } + virtual EventBase& setHostID(int host) { hostID = host; genName(); return *this; } + virtual unsigned int getDuration() const { return duration; } /*!< @brief gets the time since the beginning of this sequence (the timestamp of the activate event) @see duration */ virtual EventBase& setDuration(unsigned int d) { duration = d; return *this; }/*!< @brief sets the time since the beginning of this sequence (the timestamp of the activate event) @see duration */ @@ -210,7 +226,7 @@ * framework expansion. (Thus, user subclasses should contain at least one * lower-case letter.) This code can be used when serializing to allow quick * identification of the class type by the receiver. */ - virtual unsigned int getClassTypeID() const { return makeClassTypeID("BASE"); } + virtual classTypeID_t getClassTypeID() const { return autoRegisterEventBase; } virtual unsigned int getBinSize() const; //!< should return the minimum size needed if using binary format (i.e. not XML) virtual unsigned int loadBinaryBuffer(const char buf[], unsigned int len); //!< load from binary format @@ -256,10 +272,15 @@ protected: //! converts the first 4 characters of @a str to an unsigned int, should ensure consistent byte ordering across platforms - /*! The numeric value may differ between platforms, but it will be consistent - * with the IDs on that platform, which is the real key since we aren't doing - * math, just equality */ - static unsigned int makeClassTypeID(const char* str) { return *reinterpret_cast(str); } + static unsigned int makeClassTypeID(const char* str) { +#if LOADSAVE_SWAPBYTES + unsigned int x; + byteswap(x,*reinterpret_cast(str)); + return x; +#else + return *reinterpret_cast(str); +#endif + } std::string stim_id; //!< the name of the event, use the same name consistently or else will be seen as different stimuli float magnitude; //!< the current "strength" of the event/stimuli... MAKE SURE this gets set to ZERO IF event is DEACTIVATE @@ -276,10 +297,14 @@ * Source IDs are defined by the generator that made it. This should * give authors flexibility to design their modules without having to * worry about ID space collision */ + int hostID; unsigned int duration; /*!< @brief the time since this sequence started (like, how long the * button has been pressed); not all generators will set this; * Typically, this would be 0 for activate, * (activate.timestamp-::get_time()) for status and deactivate */ + + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterEventBase; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventGeneratorBase.cc ./Events/EventGeneratorBase.cc --- ../Tekkotsu_3.0/Events/EventGeneratorBase.cc 2006-09-22 18:29:02.000000000 -0400 +++ ./Events/EventGeneratorBase.cc 2007-11-12 23:16:02.000000000 -0500 @@ -50,7 +50,7 @@ } void -EventGeneratorBase::setAutoListen(EventBase::EventGeneratorID_t gid, unsigned int sid) { +EventGeneratorBase::setAutoListen(EventBase::EventGeneratorID_t gid, size_t sid) { removeSrcListener(); autoListen=true; srcGenID=gid; @@ -67,7 +67,7 @@ } void -EventGeneratorBase::setAutoListen(EventBase::EventGeneratorID_t gid, unsigned int sid, EventBase::EventTypeID_t tid) { +EventGeneratorBase::setAutoListen(EventBase::EventGeneratorID_t gid, size_t sid, EventBase::EventTypeID_t tid) { removeSrcListener(); autoListen=true; srcGenID=gid; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventGeneratorBase.h ./Events/EventGeneratorBase.h --- ../Tekkotsu_3.0/Events/EventGeneratorBase.h 2005-08-07 00:11:03.000000000 -0400 +++ ./Events/EventGeneratorBase.h 2007-11-12 23:16:02.000000000 -0500 @@ -47,9 +47,9 @@ virtual void setGeneratorID(EventBase::EventGeneratorID_t gid) { myGenID=gid; } //! return the source ID that will be broadcast on - virtual unsigned int getSourceID() const { return mySourceID; } + virtual size_t getSourceID() const { return mySourceID; } //! set the source ID that will be broadcast on - virtual void setSourceID(unsigned int sid) { mySourceID=sid; } + virtual void setSourceID(size_t sid) { mySourceID=sid; } //! return true if this generator has listeners virtual bool hasListeners() const; @@ -71,16 +71,16 @@ //! turns on auto listening to make it easier to set up dependancies between vision filters virtual void setAutoListen(EventBase::EventGeneratorID_t gid); //! turns on auto listening to make it easier to set up dependancies between vision filters - virtual void setAutoListen(EventBase::EventGeneratorID_t gid, unsigned int sid); + virtual void setAutoListen(EventBase::EventGeneratorID_t gid, size_t sid); //! turns on auto listening to make it easier to set up dependancies between vision filters - virtual void setAutoListen(EventBase::EventGeneratorID_t gid, unsigned int sid, EventBase::EventTypeID_t tid); + virtual void setAutoListen(EventBase::EventGeneratorID_t gid, size_t sid, EventBase::EventTypeID_t tid); //! turns off auto listening virtual void unsetAutoListen(); //! returns the generator ID that will be listened for (not the generator of the FilterBankEvent to be created - that depends on the subclass) virtual EventBase::EventGeneratorID_t getListenGeneratorID() const { return srcGenID; } //! returns the source ID that will be listened for (not the source of the FilterBankEvent to be created - that depends on the subclass) - virtual unsigned int getListenSourceID() const { return srcSourceID; } + virtual size_t getListenSourceID() const { return srcSourceID; } //! returns the type ID that will be listened for (not the type of the FilterBankEvent to be created - that depends on the subclass) virtual EventBase::EventTypeID_t getListenTypeID() const { return srcTypeID; } @@ -89,16 +89,16 @@ protected: //!@name Constructors //! - EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, unsigned int msid) + EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, size_t msid) : BehaviorBase(classname,instancename), myGenID(mgid), mySourceID(msid), autoListen(false), isListening(false), srcGenID(EventBase::numEGIDs), srcSourceID(), srcTypeID(), specificity() {} - EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, unsigned int msid,EventBase::EventGeneratorID_t srcgid) + EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, size_t msid,EventBase::EventGeneratorID_t srcgid) : BehaviorBase(classname,instancename), myGenID(mgid), mySourceID(msid), autoListen(srcgid!=EventBase::numEGIDs), isListening(false), srcGenID(srcgid), srcSourceID(), srcTypeID(), specificity(GENERATOR) {} - EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, unsigned int msid,EventBase::EventGeneratorID_t srcgid, unsigned int srcsid) + EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, size_t msid,EventBase::EventGeneratorID_t srcgid, size_t srcsid) : BehaviorBase(classname,instancename), myGenID(mgid), mySourceID(msid), autoListen(srcgid!=EventBase::numEGIDs), isListening(false), srcGenID(srcgid), srcSourceID(srcsid), srcTypeID(), specificity(SOURCE) {} - EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, unsigned int msid,EventBase::EventGeneratorID_t srcgid, unsigned int srcsid, EventBase::EventTypeID_t srctype) + EventGeneratorBase(const std::string& classname, const std::string& instancename, EventBase::EventGeneratorID_t mgid, size_t msid,EventBase::EventGeneratorID_t srcgid, size_t srcsid, EventBase::EventTypeID_t srctype) : BehaviorBase(classname,instancename), myGenID(mgid), mySourceID(msid), autoListen(srcgid!=EventBase::numEGIDs), isListening(false), srcGenID(srcgid), srcSourceID(srcsid), srcTypeID(srctype), specificity(TYPE) {} //@} @@ -110,11 +110,11 @@ virtual void removeSrcListener(); EventBase::EventGeneratorID_t myGenID; //!< the generator ID to broadcast on - unsigned int mySourceID; //!< the source ID to broadcast on + size_t mySourceID; //!< the source ID to broadcast on bool autoListen; //!< if true, will automatically start listening for EventBase(genID,sourceID) events bool isListening; //!< true if listening triggered by autoListen EventBase::EventGeneratorID_t srcGenID; //!< the generator ID to listen for (typically the source that this filter works on) - unsigned int srcSourceID; //!< the source ID to listen for + size_t srcSourceID; //!< the source ID to listen for EventBase::EventTypeID_t srcTypeID; //!< the type ID to listen for specificity_t specificity; //!< the level of event specificity that is being listened for, so when #autoListen is triggered, we can subscribe to the right level of event stream }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventProxy.cc ./Events/EventProxy.cc --- ../Tekkotsu_3.0/Events/EventProxy.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/EventProxy.cc 2007-10-16 13:37:21.000000000 -0400 @@ -0,0 +1,204 @@ +#include "Events/EventProxy.h" +#include "Shared/WorldState.h" +#include "Events/RemoteRouter.h" +#include "Events/EventRouter.h" + +using namespace std; + +EventProxy::EventProxy(int port) : RemoteEvents(), listening(true) { + sck = wireless->socket(Socket::SOCK_STREAM, 4096, 4096); + wireless->setReceiver(sck, this); + wireless->setDaemon(sck, true); + wireless->listen(sck, port); + + cout << "Adding timer" << endl; +} + +EventProxy::~EventProxy() { + //For some reason this causes a crash, so it's commented out for now + + if (isConnected()) + wireless->close(sck); +} + +bool EventProxy::isActive() { + return listening || isConnected(); +} + +int EventProxy::processData(char *data, int bytes) { + listening = false; + while (bytes) { + if (bufType == Invalid) { + //Get the buffer type + if (!readType(data, bytes)) { + cout << "Error reading buffer type" << endl; + } + } else if (!sizeLeft) { + //Get the size + if (!readSize(data, bytes)) { + cout << "Error reading buffer size" << endl; + } + } else { + //Read some data + if (readData(data, bytes)) { + //Dispatch the chunk of data + switch(bufType) { + case RequestData: + //Dispatch the data + handleRemoteRequest((RemoteRequest *)&vecbuf[0]); + break; + case Invalid: + cout << "Error: invalid data. This should never happen." << endl; + return -1; + default: + cout << "Error: data came in that wasn't expected" << endl; + return -1; + } + bufType = Invalid; + } + } + } + + return 0; +} + +/* Encodes and sends the received event */ +void EventProxy::processEvent(const EventBase &event) { + + if (event.getGeneratorID() != EventBase::timerEGID) { + if (!isConnected()) { + cout << "Got an event but not connected!" << endl; + return; + } + + //Send Event to connected robot + + int esize = 0; + byte *ebuf = new byte[defaultBufferSize]; + + if ( (esize = event.saveBinaryBuffer((char *)ebuf, defaultBufferSize)) ) { + NetworkBuffer nBuf; + nBuf.addItem(EventData); + nBuf.addBuffer(ebuf, esize); + + if (!nBuf.send(sck)) { + cout << "Error sending event to remote dog" << endl; + return; + } + } else { + cout << "Unable to save event to a buffer, aborting transmission" << endl; + } + + delete[] ebuf; + } else { + //Send state information + sendState((RemoteState::StateType)event.getSourceID()); + } +} + +void EventProxy::handleRemoteRequest(RemoteRequest *info) { + switch (info->type) { + case EventListenerRequest: + cout << "Adding remote event listener request: " << info->numElements + << " for host " << remoteIPString() << endl; + + switch (info->numElements) { + case 1: + erouter->addListener(this, info->egid); + break; + + case 2: + erouter->addListener(this, info->egid, info->sid); + break; + + case 3: + erouter->addListener(this, info->egid, info->sid, info->etid); + break; + + default: + cout << "Invalid number of elements in event listener request." << endl; + break; + } + break; + + + case RemoveEventListenerRequest: + cout << "Removing remote event listener: " << info->numElements + << " for host " << remoteIPString() << endl; + + switch (info->numElements) { + case 1: + erouter->removeListener(this, info->egid); + break; + + case 2: + erouter->removeListener(this, info->egid, info->sid); + break; + + case 3: + erouter->removeListener(this, info->egid, info->sid, info->etid); + break; + + default: + cout << "Invalid number of elements in event listener removal request." + << endl; + break; + } + break; + + + case StateUpdateRequest: + cout << "Adding remote state update request for host " + << remoteIPString() << endl; + + erouter->addTimer(this, info->sType, info->interval, true); + break; + + case StopStateUpdateRequest: + cout << "Removing remote state update request" << endl; + + erouter->removeTimer(this, info->sType); + break; + + } +} + +/* Encodes and sends the requested state info */ +void EventProxy::sendState(RemoteState::StateType stype) { + if (!isConnected()) { + cout << "Got a request to send state data but not connected!" << endl; + return; + } + + float *src = NULL; + int size = RemoteState::sizes[stype]; + + /* Get the source of the data */ + switch (stype) { + case RemoteState::OutputState: + src = state->outputs; + break; + + case RemoteState::ButtonState: + src = state->buttons; + break; + + case RemoteState::SensorState: + src = state->sensors; + break; + + default: + cout << "Unrecognized state type, aborting" << endl; + return; + } + + NetworkBuffer nBuf; + nBuf.addItem(StateData); + nBuf.addItem(size + 2*sizeof(int)); + nBuf.addItem(stype); + nBuf.addBuffer((byte *)src, size); + + if (!nBuf.send(sck)) { + cout << "Error sending state buffer" << endl; + } +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventProxy.h ./Events/EventProxy.h --- ../Tekkotsu_3.0/Events/EventProxy.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/EventProxy.h 2007-10-16 13:37:21.000000000 -0400 @@ -0,0 +1,42 @@ +#ifndef EVENTPROXY_H_ +#define EVENTPROXY_H_ +#include "Wireless/Socket.h" +#include "Wireless/Wireless.h" +#include "Events/EventListener.h" +#include "Shared/RemoteState.h" +#include "Events/RemoteEvents.h" + +/*! This class serves as the host for subscribing to remote events. It + * should never be directly manipulated by the user; all interaction + * with this class is handled by EventRouter + */ +class EventProxy : public EventListener, public RemoteEvents { + public: + EventProxy(int port); //!< EventProxy constructor, takes a port to listen on + virtual ~EventProxy(); //!< EventProxy destructor + + //! Returns true if the EventProxy is still waiting for a connection or is connected + bool isActive(); + + //! Sends the requested state information to the client robot + void sendState(RemoteState::StateType dtype); + + //! Forwards any recieved events on to the client robot + void processEvent(const EventBase& event); + + //! Handles any incoming requests from the client robot + int processData(char *data, int bytes); + + protected: + + //! Called by processData, handles an oncoming data request packet + void handleRemoteRequest(RemoteRequest *info); + + + bool listening; + + EventProxy(EventProxy&); + EventProxy &operator=(const EventProxy&); +}; + +#endif /*EVENTPROXY_H_*/ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventRouter.cc ./Events/EventRouter.cc --- ../Tekkotsu_3.0/Events/EventRouter.cc 2006-09-27 17:15:51.000000000 -0400 +++ ./Events/EventRouter.cc 2007-11-12 23:16:02.000000000 -0500 @@ -4,12 +4,47 @@ #include "Shared/ProjectInterface.h" #include #include "Events/TimerEvent.h" +#include "EventTranslator.h" +#include "Events/RemoteRouter.h" +#include "Events/EventProxy.h" + +#include + +#ifndef PLATFORM_APERIOS +# include "IPC/Thread.h" +# include "Shared/MarkScope.h" +#endif EventRouter * erouter=NULL; EventRouter::EventRouter() - : timers(), trappers(), listeners(), postings() -{} + : proxies(), rrouters(), sck(NULL), nextProxyPort(defaultPort+1), + timers(), trappers(), listeners(), postings() +{ + for(unsigned int i=0; i::iterator pi = proxies.begin(); pi != proxies.end(); pi++) + delete *pi; + + //Delete the remote routers + for (std::map::iterator mi = rrouters.begin(); mi != rrouters.end(); mi++) + delete (*mi).second; + +} void EventRouter::postEvent(EventBase* e) { processEvent(*e); delete e; } @@ -71,7 +106,7 @@ * @param sid the source ID to use on that event (if you need to send more info, send a pointer to a struct of your devising, typecasted as int) * @param delay the delay between the first (and future) calls * @param repeat set to true if you want to keep receiving this event, otherwise it will only send once */ -void EventRouter::addTimer(EventListener* el, unsigned int sid, unsigned int delay, bool repeat) { +void EventRouter::addTimer(EventListener* el, size_t sid, unsigned int delay, bool repeat) { if(delay==-1U) { removeTimer(el,sid); return; @@ -101,7 +136,7 @@ timers.erase(std::remove(timers.begin(),timers.end(),(const TimerEntry*)NULL),timers.end()); } -void EventRouter::removeTimer(EventListener* el, unsigned int sid) { +void EventRouter::removeTimer(EventListener* el, size_t sid) { for(timer_it_t it=timers.begin(); it!=timers.end(); it++) if((*it)->el==el && (*it)->sid==sid) { delete *it; @@ -124,7 +159,7 @@ else postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1)); } -void EventRouter::addListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid) { +void EventRouter::addListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid) { bool hadListener=hasListeners(egid); for(unsigned int et=0; et> 24 & 0xff) << '.' << (ip >> 16 & 0xff) << '.' + << (ip >> 8 & 0xff) << '.' << (ip >> 0 & 0xff); + return ret.str(); +} + +int EventRouter::stringToIntIP(std::string ip_str) { + std::istringstream sstr; + sstr.str(ip_str); + int ip = 0, b; + char c; + + sstr >> b >> c; + ip |= b << 24; + + sstr >> b >> c; + ip |= b << 16; + + sstr >> b >> c; + ip |= b << 8; + + sstr >> b; + ip |= b << 0; + + return ip; +} + +/* This is called in MMCombo.cc on startup. */ +bool EventRouter::serveRemoteEventRequests() { + if (sck) + return false; + sck = wireless->socket(Socket::SOCK_STREAM); + wireless->setReceiver(sck, this); + wireless->setDaemon(sck, true); + wireless->listen(sck, EventRouter::defaultPort); + return true; +} + +int EventRouter::processData(char* /* data*/, int bytes) { + if (bytes != sizeof(int)) { + std::cerr << "Unknown data received" << std::endl; + return -1; + } + + int nextPort = nextProxyPort++; + std::cout << "Starting EventProxy on port " << nextPort + << " for host " << intToStringIP(sck->getPeerAddress()) << std::endl; + proxies.push_back(new EventProxy(nextPort)); + + //Send the port to the RemoteRouter + sck->write((byte *)&nextPort, sizeof(int)); + + //Start listening again + wireless->close(sck); + + return 0; +} + +//End of remote event code + void EventRouter::removeListener(EventListener* el) { for(unsigned int eg=0; egtrapEvent(e)) + return; + } + +#ifndef PLATFORM_APERIOS + static ThreadNS::Lock lk; + MarkScope autolock(lk); +#endif PostingStatus ps(trappers,listeners,e); postings.push(&ps); while(postings.size()>0) { #ifdef DEBUG - unsigned int presize=postings.size(); + size_t presize=postings.size(); postings.front()->process(); ASSERT(postings.size()==0 || postings.size()==presize,"partial queue completion?"); #else @@ -367,13 +558,13 @@ filteredevents[eg][et]=NULL; } -void EventRouter::EventMapper::addMapping(void* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) { +void EventRouter::EventMapper::addMapping(void* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) { if(filteredevents[egid][etid]==NULL) //if this is the first subscriber to this EGID and ETID filteredevents[egid][etid]=new SIDtoListenerVectorMap_t(); SIDtoListenerVectorMap_t::iterator it=filteredevents[egid][etid]->find(sid); // now find subscribers to the source id as well std::vector* elv=NULL; if(it==filteredevents[egid][etid]->end()) { // if this is the first subscriber to the source ID - std::pair > p(sid,std::vector()); + std::pair > p(sid,std::vector()); // p.first=sid; //p.second is a vector, only needs to be constructed filteredevents[egid][etid]->insert(p); elv=&(*filteredevents[egid][etid]->find(sid)).second; @@ -385,7 +576,7 @@ bool EventRouter::EventMapper::removeMapping(void* el, EventBase::EventGeneratorID_t egid) { // remove listener from allevents - unsigned int numlist=allevents[egid].size(); + size_t numlist=allevents[egid].size(); allevents[egid].erase(std::remove(allevents[egid].begin(),allevents[egid].end(),el),allevents[egid].end()); bool hadListener=allevents[egid].size()!=numlist; @@ -407,7 +598,7 @@ return hadListener; } -bool EventRouter::EventMapper::removeMapping(void* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) { +bool EventRouter::EventMapper::removeMapping(void* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) { bool hadListener=false; SIDtoListenerVectorMap_t* mapping=filteredevents[egid][etid]; if(mapping!=NULL) { // if there are subscribers to this egid/etid @@ -487,7 +678,7 @@ return false; } -bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid) const { +bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, size_t sid) const { if(allevents[egid].size()>0) return true; for(unsigned int et=0; et0) return true; const SIDtoListenerVectorMap_t* mapping=filteredevents[egid][etid]; @@ -532,7 +723,7 @@ ls.push_back(static_cast(*elit)); } -bool EventRouter::EventMapper::verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const { +bool EventRouter::EventMapper::verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) const { // first check the 'all events' subscribers const std::vector* elv=&allevents[egid]; for(std::vector::const_iterator elit=elv->begin(); elit!=elv->end(); elit++) @@ -589,7 +780,7 @@ return false; } -bool EventRouter::EventMapper::verifyMappingAll(void* listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const { +bool EventRouter::EventMapper::verifyMappingAll(void* listener, EventBase::EventGeneratorID_t egid, size_t sid) const { // first check the 'all events' subscribers const std::vector* elv=&allevents[egid]; for(std::vector::const_iterator elit=elv->begin(); elit!=elv->end(); elit++) @@ -620,7 +811,7 @@ return true; } -bool EventRouter::EventMapper::verifyMappingAny(void* listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const { +bool EventRouter::EventMapper::verifyMappingAny(void* listener, EventBase::EventGeneratorID_t egid, size_t sid) const { // first check the 'all events' subscribers const std::vector* elv=&allevents[egid]; for(std::vector::const_iterator elit=elv->begin(); elit!=elv->end(); elit++) @@ -677,8 +868,8 @@ return ans; } -bool EventRouter::numListeners(EventBase::EventGeneratorID_t egid, unsigned int sid) { - unsigned int ans=allevents[egid].size(); +bool EventRouter::numListeners(EventBase::EventGeneratorID_t egid, size_t sid) { + size_t ans=allevents[egid].size(); for(unsigned int et=0; et #include #include #include +#include #include #include "EventListener.h" #include "EventTrapper.h" #include "Shared/get_time.h" #include "Shared/debuget.h" #include "Shared/attributes.h" +#include "IPC/ProcessID.h" #include +#include "Shared/RemoteState.h" + +#include "Wireless/SocketListener.h" +#include "Wireless/Socket.h" + +class RemoteRouter; +class EventTranslator; +class EventProxy; //! This class will handle distribution of events as well as management of timers /*! Classes must inherit from EventListener and/or EventTrapper in order to @@ -21,7 +32,17 @@ * events. (except if you are posting from within a MotionCommand, in * which case you should use MotionCommand::postEvent() so that it can correctly * handle inter-process communication issues under Aperios (the Aibo's OS) -- under a - * Unix-based OS, this wouldn't be necessary.) + * Unix-based OS, this isn't necessary.) Events posted in non-Main processes + * will be forwarded to Main for processing. + * + * Event processing is a serialized operation, meaning only one event is ever being + * processed at a time, and by one listener at a time. The EventRouter contains its own + * thread lock, so if two threads post events at the same time, the EventRouter + * will handle ensuring mutual exclusion. Listeners are free to spawn their own + * threads to handle processing or posting events to avoid being dependent on + * other listeners' processing times. (Note: threads are not available on the Aibo, + * so listeners which wish to run on the Aibo are stuck with a "cooperative" + * multitasking model) * * The events available for processing are listed in EventBase::EventGeneratorID_t. * Each generator ID's documentation specifies how to interpret the source ID field, and whether @@ -89,7 +110,7 @@ *

Event processing examples:

* * Posting events: - * @code + * @codeEventProxy * //method A: basic event posting (EventBase instance is sent) * erouter->postEvent(EventBase::aiEGID, 1234, EventBase::statusETID); * @@ -148,19 +169,19 @@ * - David Touretzky's Events Chapter * - CMU's Cognitive Robotics course slides */ -class EventRouter : public EventListener { +class EventRouter : public EventListener, public SocketListener { public: EventRouter(); //!< Constructs the router - virtual ~EventRouter() { reset(); removeAllTimers(); } //!< just calls reset and removeAllTimers() - + virtual ~EventRouter(); //!< just calls reset and removeAllTimers() + void reset() { listeners.clear(); trappers.clear(); removeAllTimers(); } //!< erases all listeners, trappers and timers, resets EventRouter //!@name Posting/Processing Events /*!@brief recommended to create and post an event using current buffer setting */ - void postEvent(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid, unsigned int dur=0) { processEvent(EventBase(egid,sid,etid,dur)); } - void postEvent(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid, unsigned int dur, const std::string& n, float m) { processEvent(EventBase(egid,sid,etid,dur,n,m)); } + void postEvent(EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid, unsigned int dur=0) { processEvent(EventBase(egid,sid,etid,dur)); } + void postEvent(EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid, unsigned int dur, const std::string& n, float m) { processEvent(EventBase(egid,sid,etid,dur,n,m)); } //! deprecated -- pass by reference instead; this version posts the specified event and then deletes it after processing is complete /*! moving to pass by reference instead of pass by pointer to avoid questions about who deletes the event and the event's scope, * also keeping the event on the stack is faster by avoiding unnecessary heap operations. */ @@ -177,6 +198,11 @@ * probably a more memnomic interface to use in direct function calls however, * so that is the one you should call. */ void processEvent(const EventBase& e); + + //! returns the forwarding agent for a given process/thread group (see #forwards) + EventTranslator* getForwardingAgent(ProcessID::ProcessID_t proc) const { return forwards[proc]; } + //! sets the forwarding agent for a given process/thread group (see #forwards) + void setForwardingAgent(ProcessID::ProcessID_t proc, EventTranslator* trans); //@} @@ -184,16 +210,16 @@ //! returns true if the specified listener/trapper would receive any events that match the specified criteria bool isListeningAny(EventListener* el, EventBase::EventGeneratorID_t egid) { return listeners.verifyMappingAny(el,egid); } - bool isListeningAny(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid) { return listeners.verifyMappingAny(el,egid,sid); } + bool isListeningAny(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid) { return listeners.verifyMappingAny(el,egid,sid); } bool isListeningAll(EventListener* el, EventBase::EventGeneratorID_t egid) { return listeners.verifyMappingAll(el,egid); } - bool isListeningAll(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid) { return listeners.verifyMappingAll(el,egid,sid); } - bool isListening(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) { return listeners.verifyMapping(el,egid,sid,etid); } + bool isListeningAll(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid) { return listeners.verifyMappingAll(el,egid,sid); } + bool isListening(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) { return listeners.verifyMapping(el,egid,sid,etid); } bool isListening(EventListener* el, const EventBase& e) { return listeners.verifyMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID()); } bool isTrappingAny(EventTrapper* el, EventBase::EventGeneratorID_t egid) { return trappers.verifyMappingAny(el,egid); } - bool isTrappingAny(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid) { return trappers.verifyMappingAny(el,egid,sid); } + bool isTrappingAny(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid) { return trappers.verifyMappingAny(el,egid,sid); } bool isTrappingAll(EventTrapper* el, EventBase::EventGeneratorID_t egid) { return trappers.verifyMappingAll(el,egid); } - bool isTrappingAll(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid) { return trappers.verifyMappingAll(el,egid,sid); } - bool isTrapping(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) { return trappers.verifyMapping(el,egid,sid,etid); } + bool isTrappingAll(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid) { return trappers.verifyMappingAll(el,egid,sid); } + bool isTrapping(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) { return trappers.verifyMapping(el,egid,sid,etid); } bool isTrapping(EventTrapper* el, const EventBase& e) { return trappers.verifyMapping(el,e.getGeneratorID(),e.getSourceID(),e.getTypeID()); } //@} @@ -209,8 +235,8 @@ * ... if Vision sees a ball in an image, and there's no listeners, does it * make an event? ;) */ bool hasListeners(EventBase::EventGeneratorID_t egid) { return trappers.hasMapping(egid) || listeners.hasMapping(egid); } - bool hasListeners(EventBase::EventGeneratorID_t egid, unsigned int sid) { return trappers.hasMapping(egid,sid) || listeners.hasMapping(egid,sid); } - bool hasListeners(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) { return trappers.hasMapping(egid,sid,etid) || listeners.hasMapping(egid,sid,etid); } + bool hasListeners(EventBase::EventGeneratorID_t egid, size_t sid) { return trappers.hasMapping(egid,sid) || listeners.hasMapping(egid,sid); } + bool hasListeners(EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) { return trappers.hasMapping(egid,sid,etid) || listeners.hasMapping(egid,sid,etid); } bool hasListeners(const EventBase& e) { return hasListeners(e.getGeneratorID(),e.getSourceID(),e.getTypeID()); } //@} @@ -218,12 +244,13 @@ //!@name Timer Management //! adds a timer if it doesn't exist, or resets the timer if it already exists. - void addTimer(EventListener* el, unsigned int sid, unsigned int delay, bool repeat=true); + void addTimer(EventListener* el, size_t sid, unsigned int delay, bool repeat=true); void addTimer(EventListener* el, const EventBase& e, bool repeat=true) { addTimer(el,e.getSourceID(),e.getDuration(),repeat); } //!< calls the other addTimer() with the event's source id and duration, doesn't check to see if the generator is timerEGID //! clears all pending timers for listener @a el; see remove() void removeTimer(EventListener* el); - void removeTimer(EventListener* el, unsigned int sid); //!< clears any pending timers with source id @a sid for listener @a el + void removeTimer(EventListener* el, size_t sid); //!< clears any pending timers with source id @a sid for listener @a el + void removeTimer(EventListener* el, EventBase& e) { if(e.getGeneratorID()==EventBase::timerEGID) removeTimer(el,e.getSourceID()); } //!< clears any pending timers with source id matching that of @a e, but only if @a e has generator timerEGID void removeAllTimers(); //!< clears all timers for all listeners unsigned int getNextTimer() { return (timers.size()==0 ? -1U : timers.front()->next); } //!< returns time of next timer activation //@} @@ -233,22 +260,72 @@ //! Adds a listener for all events from a given event generator void addListener(EventListener* el, EventBase::EventGeneratorID_t egid); - void addListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid); //!< Adds a listener for all types from a specific source and generator - void addListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid); //!< Adds a listener for a specific source id and type from a given event generator + void addListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid); //!< Adds a listener for all types from a specific source and generator + void addListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); //!< Adds a listener for a specific source id and type from a given event generator void addListener(EventListener* el, const EventBase& e); //!< Uses the generator, source, and type fields of @a e to add a listener for that specific tuple + + //!@name Remote Event/State code + + //! Converts a int representation of an IP to a string + static std::string intToStringIP(int ip); + //! Converts a string representation of an IP to an int + static int stringToIntIP(std::string ip); + + //! Request remote events to be sent to this dog, works like the regular addListeners + void addRemoteListener(EventListener* el, int host, EventBase::EventGeneratorID_t egid); + void addRemoteListener(EventListener* el, int host, EventBase::EventGeneratorID_t egid, size_t sid); + void addRemoteListener(EventListener* el, int host, const EventBase& e); + void addRemoteListener(EventListener* el, int host, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); + + //! Stop getting remote events from the given dog + void removeRemoteListener(EventListener* el, int host, EventBase::EventGeneratorID_t egid); + void removeRemoteListener(EventListener* el, int host, EventBase::EventGeneratorID_t egid, size_t sid); + void removeRemoteListener(EventListener* el, int host, const EventBase& e); + void removeRemoteListener(EventListener* el, int host, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); + + + //! Request remote state updates from the remote dog, every interval ms + void requestRemoteStateUpdates(int host, RemoteState::StateType type, unsigned int interval = 500); + + //! Stop getting remote state updates + void stopRemoteStateUpdates(int host, RemoteState::StateType type); + + //! This is called once on startup; it tells the EventRouter to listen for incoming requests + bool serveRemoteEventRequests(); + + //! This handles incomiung connection requests by starting a new EventProxy + int processData(char *data, int bytes); + + static const int defaultPort = 2424; + + protected: + + RemoteRouter &remoteRouterForHost(int host); + + std::list proxies; + + std::map rrouters; + Socket *sck; + int nextProxyPort; + + //!} + public: + + //! stops sending ALL events to the listener -- does not remove pending timers however (may need to call removeTimer(el) as well); see remove() void removeListener(EventListener* el); //! stops sending specified events from the generator to the listener. void removeListener(EventListener* el, EventBase::EventGeneratorID_t egid); - void removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid); //!< stops sending specified events from the generator to the listener. - void removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid); //!< stops sending specified events from the generator to the listener. + void removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid); //!< stops sending specified events from the generator to the listener. + void removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); //!< stops sending specified events from the generator to the listener. void removeListener(EventListener* el, const EventBase& e); //!< Uses the generator, source, and type fields of @a e to remove a listener for that specific tuple //! stops all events and timers, shorthand for removeListener(el) and removeTimer(el); Note that trappers are separate, removeTrapper() is @e not called void remove(EventListener* el) { removeListener(el); removeTimer(el); } //@} + //!@name Trapper Management @@ -256,27 +333,28 @@ /*! Note that only the broadcasted timers can be trapped. The EventListener which requested the timer will receive that timer before any trapping is done. */ void addTrapper(EventTrapper* el, const EventBase& e); void addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid); //!< Adds a trapper for all events from a given event generator - void addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid); //!< Adds a trapper for all types from a specific source and generator - void addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid); //!< Adds a trapper for a specific source id and type from a given event generator + void addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid); //!< Adds a trapper for all types from a specific source and generator + void addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); //!< Adds a trapper for a specific source id and type from a given event generator void addTrapper(EventTrapper* el); //!< adds a trapper for ALL events //! stops sending specified events from the generator to the trapper. void removeTrapper(EventTrapper* el, const EventBase& e); void removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid); //!< stops sending specified events from the generator to the trapper. - void removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid); //!< stops sending specified events from the generator to the trapper. - void removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid); //!< stops sending specified events from the generator to the trapper. + void removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid); //!< stops sending specified events from the generator to the trapper. + void removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); //!< stops sending specified events from the generator to the trapper. void removeTrapper(EventTrapper* el); //!< stops sending ALL events to the trapper //@} protected: + //! Contains all the information needed to maintain a timer by the EventRouter struct TimerEntry { //! constructs an entry using the given value for next - useful for with TimerEntryPtrCmp explicit TimerEntry(unsigned int nxt) : el(NULL), sid(0), delay(0), next(nxt), repeat(false) {} //! constructs with the given values, sets next field automatically; see next - TimerEntry(EventListener* e, unsigned int s, unsigned int d, bool r) : el(e), sid(s), delay(d), next(get_time()+delay), repeat(r) {} + TimerEntry(EventListener* e, size_t s, unsigned int d, bool r) : el(e), sid(s), delay(d), next(get_time()+delay), repeat(r) {} //! just does the default, i'm just being explicit since there's a pointer (no deep copy!) TimerEntry(const TimerEntry& t) : el(t.el), sid(t.sid), delay(t.delay), next(t.next), repeat(t.repeat) {} //! just does the default, i'm just being explicit since there's a pointer (no deep copy!) @@ -286,7 +364,7 @@ * @param r true if the timer should automatically repeat */ void Set(unsigned int d, bool r) { delay=d; repeat=r; next=get_time()+delay; } EventListener* el; //!< the listener to fire at - unsigned int sid; //!< the source id to fire with + size_t sid; //!< the source id to fire with unsigned int delay; //!< the delay until firing unsigned int next; //!< the time at which this timer will go off next bool repeat; //!< if true, will reset after firing, else will be deleted @@ -334,7 +412,7 @@ EventMapper(); void addMapping(void* el, EventBase::EventGeneratorID_t egid) { allevents[egid].push_back(el); } //!< Adds a listener for all events from a given event generator - void addMapping(void* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid); //!< Adds a listener for a specific source id and type from a given event generator + void addMapping(void* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); //!< Adds a listener for a specific source id and type from a given event generator //! Removes a listener for all events from a given event generator, returns true if something was actually removed /*! Doesn't necessarily remove the vector or mapping if this was the last listener, use clean() to do that */ @@ -342,7 +420,7 @@ //! Removes a listener for a specific source id and type from a given event generator, returns true if something was actually removed /*! Doesn't necessarily remove the vector or mapping if this was the last listener, use clean() to do that */ - bool removeMapping(void* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid); + bool removeMapping(void* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid); void clean(); //!,std::less > SIDtoListenerVectorMap_t; + typedef std::map,std::less > SIDtoListenerVectorMap_t; //! an array of vectors of pointers to listeners... in other words, a vector of listener pointers for each generator std::vector allevents[EventBase::numEGIDs]; @@ -431,6 +509,22 @@ const EventBase& e; //!< the event being processed }; std::queue postings; //!< stores calls to post() currently in progress -- may grow if one postEvent() triggers another; this allows us to finish processing of the original postEvent() before starting the second. + + //! This table will be checked on each processEvent to forward the event to some other destination + /*! The main reason for including this functionality is in the uni-process model, we don't want + * event postings from real time processes like Motion to block on the event queue processing. + * So with this mechanism we can intercept those events, and queue them in a separate IPC + * mechanism to be picked up by Main later on. + * + * This might also be handy for other purposes, such as remote event forwarding over the network... + * + * If the EventTranslator's trapEvent returns true, then further processing on the event is skipped. + * (see EventTranslator::setTrapEventValue() )*/ + EventTranslator* forwards[ProcessID::NumProcesses]; +private: + EventRouter(const EventRouter&); //!< don't call this + EventRouter& operator=(const EventRouter&); //!< don't call this + }; //! a global router for cross communication, probably the most common usage, although perhaps there may be times you'd rather have multiple event routers for smaller sections diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventTranslator.cc ./Events/EventTranslator.cc --- ../Tekkotsu_3.0/Events/EventTranslator.cc 2006-09-28 17:00:27.000000000 -0400 +++ ./Events/EventTranslator.cc 2007-05-21 13:02:39.000000000 -0400 @@ -16,50 +16,44 @@ using namespace std; -EventTranslator::eventLookup_t EventTranslator::eventLookup; - -EventTranslator::~EventTranslator() { - for(eventLookup_t::iterator it=eventLookup.begin(); it!=eventLookup.end(); ++it) - delete (*it).second; - eventLookup.clear(); -} - void EventTranslator::encodeEvent(const EventBase& event, bool onlyReady/*=false*/) { event.setSaveFormat(EventBase::BINARY); - const unsigned int headerlen=sizeof(event.getClassTypeID()); - const unsigned int bufsize=headerlen+event.getBinSize(); - char * buf=bufferRequest(bufsize); + EventBase::classTypeID_t header=event.getClassTypeID(); + const unsigned int bufsize=LoadSave::getSerializedSize(header)+event.getBinSize(); + char * const buf=bufferRequest(bufsize); if(buf==NULL) { cerr << "ERROR: EventTranslator unable to transmit event because requested buffer was NULL" << endl; return; } - unsigned int header=event.getClassTypeID(); - memcpy(buf,&header,headerlen); - unsigned int used=event.saveBuffer(buf+headerlen,bufsize-headerlen); + char * cur=buf; + unsigned int remain=bufsize; + if(!LoadSave::encodeInc(header,cur,remain,"Ran out of space encoding event header")) return; + unsigned int used=event.saveBuffer(cur,remain); if(used==0) { - cerr << "ERROR: EventTranslator unable to transmit event because EventBase::saveBuffer failed (buffer==" << (void*)(buf+headerlen) << ", size==" << bufsize-headerlen << ")" << endl; + cerr << "ERROR: EventTranslator unable to transmit event because EventBase::saveBuffer failed (buffer==" << (void*)(cur) << ", size==" << remain << ")" << endl; post(buf,0,onlyReady); return; } - post(buf,used,onlyReady); + cur+=used; + remain-=used; + ASSERT(cur-buf==(int)(bufsize-remain),"used count does not match offset"); + post(buf,bufsize-remain,onlyReady); return; } EventBase* EventTranslator::decodeEvent(const char * entry, unsigned int size) { - const unsigned int headerlen=sizeof(unsigned int); - unsigned int header=0; - memcpy(&header,entry,headerlen); + EventBase::classTypeID_t header; + if(!LoadSave::decodeInc(header,entry,size,"Ran out of space decoding event")) return NULL; //cout << "decodeEvent(" << (void*)entry << ","<< size << ") header is " << header << " (" << entry[0] << entry[1] << entry[2] << entry[3] << ")" << endl; - eventLookup_t::iterator it=eventLookup.find(header); - if(it==eventLookup.end()) { + EventBase* evt=EventBase::getTypeRegistry().create(header); + if(evt==NULL) { cerr << "ERROR: EventTranslator unable to translate buffer because header does not match a previously registered class type id" << endl; return NULL; } - EventBase* evt=static_cast((*it).second->constructTemplate()); evt->setSaveFormat(EventBase::BINARY); - if(evt->loadBuffer(entry+headerlen,size-headerlen)==0) { + if(evt->loadBuffer(entry,size)==0) { cerr << "ERROR: EventTranlator unable to translate buffer because data is malformed (EventBase::loadBuffer failed)" << endl; return NULL; } @@ -85,8 +79,13 @@ } void -IPCEventTranslator::post(const char* buf, unsigned int /*size*/, bool onlyReady) { +IPCEventTranslator::post(const char* buf, unsigned int size, bool onlyReady) { ASSERTRET(curRegion!=NULL,"ERROR: IPCEventTranslator::post(buf,size) was NULL"); + if(size==0) { + curRegion->RemoveReference(); + curRegion=NULL; + return; + } if(buf!=curRegion->Base()) { cerr << "ERROR: IPCEventTranslator::post(buf,size) buf does not match value given from previous bufferRequest()" << endl; return; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventTranslator.h ./Events/EventTranslator.h --- ../Tekkotsu_3.0/Events/EventTranslator.h 2006-09-25 19:28:12.000000000 -0400 +++ ./Events/EventTranslator.h 2007-05-21 13:02:39.000000000 -0400 @@ -4,7 +4,6 @@ #include "Events/EventTrapper.h" #include "Events/EventListener.h" -#include "Shared/Factory.h" #include //! EventTranslator receives events from EventRouters in non-Main processes and adds them into a SharedQueue for Main to pick up @@ -14,7 +13,7 @@ EventTranslator() : trapRet(false) {} //!destructor - virtual ~EventTranslator(); + virtual ~EventTranslator() {} //! Call this with events which should be forwarded to other processes /*! @param event the event to serialize and send @@ -38,28 +37,11 @@ /*! @return the reconstituted event, or NULL if an error occured (malformed data) */ static EventBase* decodeEvent(const char* buf, unsigned int size); - //!This should be called during initialization to register all EventBase subclasses - /*! @return true upon success, false if an event matching that prototype's EventBase::getClassTypeID() was already registered */ - template - static bool registerPrototype() { - EB prototype; - eventLookup_t::const_iterator it=eventLookup.find(prototype.getClassTypeID()); - if(it!=eventLookup.end()) - return false; - eventLookup[prototype.getClassTypeID()]=new Factory; - return true; - } - //! set #trapRet, which can let you decide whether trapped events should be filtered or not virtual void setTrapEventValue(bool v) { trapRet=v; } protected: - //! Shorthand for they type of #eventLookup - typedef std::map eventLookup_t; - - //! Allows quick lookup of event subclasses based on their EventBase::getClassTypeID() - static eventLookup_t eventLookup; //! Called by encodeEvent() to request a buffer for serializing into, must be at least @a size /*! This buffer will then be sent to post(), which should free diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/FilterBankEvent.h ./Events/FilterBankEvent.h --- ../Tekkotsu_3.0/Events/FilterBankEvent.h 2005-06-29 18:03:35.000000000 -0400 +++ ./Events/FilterBankEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -4,12 +4,13 @@ #include "Events/EventBase.h" #include "Vision/FilterBankGenerator.h" +#include "Shared/Factories.h" //! This event gives access to a set of image channels at different resolutions, see FilterBankGenerator class FilterBankEvent : public EventBase { public: //! constructor - FilterBankEvent(FilterBankGenerator* creator,EventBase::EventGeneratorID_t gid,unsigned int sid,EventBase::EventTypeID_t tid) + FilterBankEvent(FilterBankGenerator* creator,EventBase::EventGeneratorID_t gid,size_t sid,EventBase::EventTypeID_t tid) : EventBase(gid,sid,tid,0,creator->getName()), src(creator) {} @@ -54,12 +55,20 @@ //! returns the number of frames processed by the generator, see FilterBankGenerator::framesProcessed inline unsigned int getFramesProcessed() const { return src->getFramesProcessed(); } + virtual classTypeID_t getClassTypeID() const { return autoRegisterFilterBankEvent; } + protected: //! pointer to generator which created this event /*! the generator holds all the actual image data to be more memory efficient */ FilterBankGenerator* src; -private: + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + /*! This is instantiated in EventBase.cc to save on file bloat */ + static const EventBase::classTypeID_t autoRegisterFilterBankEvent; + + //! default constructor, only intended to be called from the FamilyFactory, followed by a loadXML... + FilterBankEvent() : EventBase(), src(NULL) {} + friend struct Factory0Arg::Factory; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/LocomotionEvent.cc ./Events/LocomotionEvent.cc --- ../Tekkotsu_3.0/Events/LocomotionEvent.cc 2006-09-21 17:14:47.000000000 -0400 +++ ./Events/LocomotionEvent.cc 2007-05-21 13:02:39.000000000 -0400 @@ -1,10 +1,12 @@ #include "LocomotionEvent.h" #include #include - #include + using namespace std; +const EventBase::classTypeID_t LocomotionEvent::autoRegisterLocomotionEvent=getTypeRegistry().registerType(makeClassTypeID("LOCO")); + std::string LocomotionEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const { if(!showTypeSpecific) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/LocomotionEvent.h ./Events/LocomotionEvent.h --- ../Tekkotsu_3.0/Events/LocomotionEvent.h 2006-09-09 00:32:46.000000000 -0400 +++ ./Events/LocomotionEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -19,12 +19,12 @@ //! constructor LocomotionEvent() : EventBase(),x(0),y(0),a(0) {} - LocomotionEvent(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur=0) : EventBase(gid,sid,tid,dur),x(0),y(0),a(0) {} - LocomotionEvent(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) : EventBase(gid,sid,tid,dur,n,mag),x(0),y(0),a(0) {} + LocomotionEvent(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur=0) : EventBase(gid,sid,tid,dur),x(0),y(0),a(0) {} + LocomotionEvent(EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) : EventBase(gid,sid,tid,dur,n,mag),x(0),y(0),a(0) {} virtual EventBase* clone() const { return new LocomotionEvent(*this); } //@} - virtual unsigned int getClassTypeID() const { return makeClassTypeID("LOCO"); } + virtual unsigned int getClassTypeID() const { return autoRegisterLocomotionEvent; } //! Allows you to set the new X, Y, and A components LocomotionEvent& setXYA(float X, float Y, float A) { @@ -42,9 +42,16 @@ virtual void loadXML(xmlNode* node); virtual void saveXML(xmlNode * node) const; + //!< Returns true if this event indicates motion has stopped (x,y,a are all zero) + virtual bool isStop() const { return x==0 && y==0 && a==0;} + float x; //!< the new x component (body relative) float y; //!< the new y component (body relative) float a; //!< the new angular component (body relative) + +protected: + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterLocomotionEvent; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/LookoutEvents.cc ./Events/LookoutEvents.cc --- ../Tekkotsu_3.0/Events/LookoutEvents.cc 2006-09-09 00:32:46.000000000 -0400 +++ ./Events/LookoutEvents.cc 2007-05-21 13:02:39.000000000 -0400 @@ -6,6 +6,12 @@ using namespace std; +const EventBase::classTypeID_t LookoutPointAtEvent::autoRegisterLookoutPointAtEvent=getTypeRegistry().registerType(makeClassTypeID("LOLA")); +const EventBase::classTypeID_t LookoutSketchEvent::autoRegisterLookoutSketchEvent=getTypeRegistry().registerType(makeClassTypeID("LSKC")); +const EventBase::classTypeID_t LookoutIREvent::autoRegisterLookoutIREvent=getTypeRegistry().registerType(makeClassTypeID("LOIR")); +const EventBase::classTypeID_t LookoutScanEvent::autoRegisterLookoutScanEvent=getTypeRegistry().registerType(makeClassTypeID("LSCN")); + + //================ LookoutPointAtEvent std::string diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/LookoutEvents.h ./Events/LookoutEvents.h --- ../Tekkotsu_3.0/Events/LookoutEvents.h 2006-09-09 00:32:47.000000000 -0400 +++ ./Events/LookoutEvents.h 2007-11-12 23:16:02.000000000 -0500 @@ -9,18 +9,18 @@ #include "DualCoding/Sketch.h" #include "Shared/newmat/newmat.h" - //! Abstract base class for all Lookout Events class LookoutEvent : public EventBase { public: - enum LookoutEventType_t { lookAt, sketch, ir, scan }; + enum LookoutEventType_t { lookAt, sketch, ir, scan, track, search }; + bool success; virtual LookoutEventType_t getLookoutEventType() const = 0; //{ constructors which take exact same set of arguments as EventBase's and pass them directory to EventBase - LookoutEvent() : EventBase() {} - LookoutEvent(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur=0) - : EventBase(gid,sid,tid,dur) {} - LookoutEvent(EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) - : EventBase(gid,sid,tid,dur,n,mag) {} + LookoutEvent() : EventBase(), success(false) {} + LookoutEvent(bool _success, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur=0) + : EventBase(gid,sid,tid,dur), success(_success) {} + LookoutEvent(bool _success, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) + : EventBase(gid,sid,tid,dur,n,mag), success(_success) {} //} }; @@ -29,47 +29,57 @@ public: NEWMAT::Matrix toBaseMatrix; virtual LookoutEventType_t getLookoutEventType() const { return lookAt; } - LookoutPointAtEvent(const NEWMAT::Matrix& mat) : LookoutEvent(), toBaseMatrix(mat) {} - LookoutPointAtEvent(const NEWMAT::Matrix& mat, EventGeneratorID_t gid, - unsigned int sid, EventTypeID_t tid, unsigned int dur=0) - : LookoutEvent(gid,sid,tid,dur),toBaseMatrix(mat) {} - LookoutPointAtEvent(const NEWMAT::Matrix& mat, EventGeneratorID_t gid, - unsigned int sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) - : LookoutEvent(gid,sid,tid,dur,n,mag),toBaseMatrix(mat) {} + LookoutPointAtEvent() : LookoutEvent(), toBaseMatrix() { } + LookoutPointAtEvent(bool _success, const NEWMAT::Matrix& mat) : LookoutEvent(), toBaseMatrix(mat) { success = _success; } + LookoutPointAtEvent(bool _success, const NEWMAT::Matrix& mat, EventGeneratorID_t gid, + size_t sid, EventTypeID_t tid, unsigned int dur=0) + : LookoutEvent(_success,gid,sid,tid,dur),toBaseMatrix(mat) {} + LookoutPointAtEvent(bool _success, const NEWMAT::Matrix& mat, EventGeneratorID_t gid, + size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) + : LookoutEvent(_success,gid,sid,tid,dur,n,mag), toBaseMatrix(mat) {} virtual EventBase* clone() const { return new LookoutPointAtEvent(*this); } - virtual unsigned int getClassTypeID() const { return makeClassTypeID("LOLA"); } + virtual unsigned int getClassTypeID() const { return autoRegisterLookoutPointAtEvent; } virtual std::string getDescription(bool showTypeSpecific=true, unsigned int verbosity=0) const; virtual unsigned int getBinSize() const; virtual unsigned int loadBinaryBuffer(const char buf[], unsigned int len); virtual unsigned int saveBinaryBuffer(char buf[], unsigned int len) const; virtual void loadXML(xmlNode* node); virtual void saveXML(xmlNode * node) const; +protected: + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterLookoutPointAtEvent; }; -// Event which gives you access to the sketch stored as a result of StoreImage request +// Event which gives you access to the sketch stored as a success of StoreImage request class LookoutSketchEvent : public LookoutPointAtEvent { protected: - DualCoding::Sketch *img; // pointer to sketch existing inside lookout's requests queue + DualCoding::Sketch img; // sketch returned by the Lookout public: virtual LookoutEventType_t getLookoutEventType() const { return sketch; } - LookoutSketchEvent(DualCoding::Sketch& _img, const NEWMAT::Matrix& mat) - : LookoutPointAtEvent(mat), img(&_img) {} - LookoutSketchEvent(DualCoding::Sketch& _img, const NEWMAT::Matrix& mat, - EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur=0) - : LookoutPointAtEvent(mat,gid,sid,tid,dur), img(&_img) {} - LookoutSketchEvent(DualCoding::Sketch& _img, const NEWMAT::Matrix& mat, - EventGeneratorID_t gid, unsigned int sid, + LookoutSketchEvent() : LookoutPointAtEvent(), img() {} + LookoutSketchEvent(bool _success, DualCoding::Sketch& _img, const NEWMAT::Matrix& mat) + : LookoutPointAtEvent(_success,mat), img(_img) {} + LookoutSketchEvent(bool _success, DualCoding::Sketch& _img, const NEWMAT::Matrix& mat, + EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur=0) + : LookoutPointAtEvent(_success, mat,gid,sid,tid,dur), img(_img) {} + LookoutSketchEvent(bool _success, DualCoding::Sketch& _img, const NEWMAT::Matrix& mat, + EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) - : LookoutPointAtEvent(mat,gid,sid,tid,dur,n,mag), img(&_img) {} + : LookoutPointAtEvent(_success,mat,gid,sid,tid,dur,n,mag), img(_img) {} //! copy constructor (shallow copy) - LookoutSketchEvent(const LookoutSketchEvent& lose) - : LookoutPointAtEvent(lose), img(lose.img) {} + LookoutSketchEvent(const LookoutSketchEvent& other) + : LookoutPointAtEvent(other), img(other.img) {} - const DualCoding::Sketch& getSketch() const { return *img; } + const DualCoding::Sketch& getSketch() const { return img; } virtual EventBase* clone() const { return new LookoutSketchEvent(*this); } // virtual std::string getDescription(bool showTypeSpecific=true, unsigned int verbosity=0) const; + + virtual unsigned int getClassTypeID() const { return autoRegisterLookoutSketchEvent; } +protected: + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterLookoutSketchEvent; private: LookoutSketchEvent& operator=(const LookoutSketchEvent&); }; @@ -78,36 +88,41 @@ public: float distance; virtual LookoutEventType_t getLookoutEventType() const { return ir; } - LookoutIREvent(float dist, const NEWMAT::Matrix& mat) : LookoutPointAtEvent(mat), distance(dist) {} - LookoutIREvent(float dist, const NEWMAT::Matrix& mat, EventGeneratorID_t gid, - unsigned int sid, EventTypeID_t tid, unsigned int dur=0) - : LookoutPointAtEvent(mat, gid,sid,tid,dur), distance(dist) {} - LookoutIREvent(float dist, const NEWMAT::Matrix& mat, EventGeneratorID_t gid, unsigned int sid, + LookoutIREvent() : LookoutPointAtEvent(), distance() {} + LookoutIREvent(bool _success, float dist, const NEWMAT::Matrix& mat) : LookoutPointAtEvent(_success,mat), distance(dist) {} + LookoutIREvent(bool _success, float dist, const NEWMAT::Matrix& mat, EventGeneratorID_t gid, + size_t sid, EventTypeID_t tid, unsigned int dur=0) + : LookoutPointAtEvent(_success, mat, gid,sid,tid,dur), distance(dist) {} + LookoutIREvent(bool _success, float dist, const NEWMAT::Matrix& mat, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) - : LookoutPointAtEvent(mat,gid,sid,tid,dur,n,mag), distance(dist) {} + : LookoutPointAtEvent(_success,mat,gid,sid,tid,dur,n,mag), distance(dist) {} virtual EventBase* clone() const { return new LookoutIREvent(*this); } - virtual unsigned int getClassTypeID() const { return makeClassTypeID("LOIR"); } + virtual unsigned int getClassTypeID() const { return autoRegisterLookoutIREvent; } virtual std::string getDescription(bool showTypeSpecific=true, unsigned int verbosity=0) const; virtual unsigned int getBinSize() const; virtual unsigned int loadBinaryBuffer(const char buf[], unsigned int len); virtual unsigned int saveBinaryBuffer(char buf[], unsigned int len) const; virtual void loadXML(xmlNode* node); virtual void saveXML(xmlNode * node) const; +protected: + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterLookoutIREvent; }; class LookoutScanEvent : public LookoutEvent { protected: //! pointer to tasks implemented during the scan - vector *tasks; + std::vector *tasks; public: virtual LookoutEventType_t getLookoutEventType() const { return scan; } - LookoutScanEvent(vector& _tasks) : LookoutEvent(), tasks(&_tasks) {} - LookoutScanEvent(vector& _tasks, EventGeneratorID_t gid, - unsigned int sid, EventTypeID_t tid, unsigned int dur=0) - : LookoutEvent(gid,sid,tid,dur), tasks(&_tasks) {} - LookoutScanEvent(vector& _tasks, EventGeneratorID_t gid, unsigned int sid, + LookoutScanEvent() : LookoutEvent(), tasks() {} + LookoutScanEvent(std::vector& _tasks) : LookoutEvent(), tasks(&_tasks) {} + LookoutScanEvent(std::vector& _tasks, EventGeneratorID_t gid, + size_t sid, EventTypeID_t tid, unsigned int dur=0) + : LookoutEvent(true,gid,sid,tid,dur), tasks(&_tasks) {} + LookoutScanEvent(std::vector& _tasks, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur, const std::string& n, float mag) - : LookoutEvent(gid,sid,tid,dur,n,mag), tasks(&_tasks) {} + : LookoutEvent(true,gid,sid,tid,dur,n,mag), tasks(&_tasks) {} //! copy constructor (shallow copy) LookoutScanEvent(const LookoutScanEvent& lose) : LookoutEvent(lose), tasks(lose.tasks) {} @@ -119,7 +134,12 @@ return *this; } virtual EventBase* clone() const { return new LookoutScanEvent(*this); } - const vector& getTasks() const { return *tasks; } + const std::vector& getTasks() const { return *tasks; } + + virtual unsigned int getClassTypeID() const { return autoRegisterLookoutScanEvent; } +protected: + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterLookoutScanEvent; }; #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/NetworkBuffer.h ./Events/NetworkBuffer.h --- ../Tekkotsu_3.0/Events/NetworkBuffer.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/NetworkBuffer.h 2007-11-10 17:58:07.000000000 -0500 @@ -0,0 +1,65 @@ +#ifndef NETWORK_BUFFER_H_ +#define NETWORK_BUFFER_H_ + +/*! This is used to incrementally build up a buffer to be sent over + * the network , so that only one call to the socket write function + * needs to be made. */ +class NetworkBuffer { +public: + + //! constructor + NetworkBuffer() : buf(NULL), offset(0), bufSize(1024) { + buf = new byte[bufSize]; + } + + //! destructor + virtual ~NetworkBuffer() { + delete[] buf; + } + + //! Template for adding a single item to the buffer, such as a struct or an int + template bool addItem(T item) { + if (offset+sizeof(T) > (unsigned int)bufSize) + return false; + + *(T *)(buf+offset) = item; + offset += sizeof(T); + return true; + } + + //! Template for adding a buffer such with a size to the network buffer + bool addBuffer(byte *src, int size) { + if (!addItem(size) || (offset+size > bufSize)) + return false; + + memcpy(buf+offset, src, size); + offset += size; + return true; + } + + //! Returns the current size of the buffer + int getSize() { + return offset; + } + + //! Sends the buffer over the given socket + bool send(Socket *sck) { + if (sck->write(buf, offset) != static_cast(offset)) { + std::cout << "Error sending buffer" << std::endl; + return false; + } + + return true; + } + +protected: + byte *buf; //!< the buffer being built + size_t offset; //!< current position in #buf + size_t bufSize; //!< size of memory region at #buf + +private: + NetworkBuffer(NetworkBuffer&); //!< do not call + NetworkBuffer &operator=(const NetworkBuffer&); //!< do not call +}; + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/PitchEvent.cc ./Events/PitchEvent.cc --- ../Tekkotsu_3.0/Events/PitchEvent.cc 2006-09-21 17:45:47.000000000 -0400 +++ ./Events/PitchEvent.cc 2007-05-21 13:02:39.000000000 -0400 @@ -2,9 +2,10 @@ #include #include -//better to put this here instead of the header using namespace std; +const EventBase::classTypeID_t PitchEvent::autoRegisterPitchEvent=getTypeRegistry().registerType(makeClassTypeID("PITC")); + std::string PitchEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const { if(!showTypeSpecific) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/PitchEvent.h ./Events/PitchEvent.h --- ../Tekkotsu_3.0/Events/PitchEvent.h 2006-09-25 16:49:24.000000000 -0400 +++ ./Events/PitchEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -7,11 +7,14 @@ //! Provides information about a tone detected from the microphone(s) class PitchEvent : public EventBase { public: + //! default constructor, sets generator ID, but nothing else + PitchEvent() : EventBase(), freq(), amplitude(), confidence() {genID=EventBase::micPitchEGID;} + //!constructor - PitchEvent(unsigned int sid, EventTypeID_t type, const float freq_, const char *name_, const float amplitude_, const unsigned int duration_, const float confidence_) + PitchEvent(size_t sid, EventTypeID_t type, const float freq_, const char *name_, const float amplitude_, const unsigned int duration_, const float confidence_) : EventBase(EventBase::micPitchEGID, sid, type,duration_,name_,(type==deactivateETID) ? 0 : confidence_*amplitude_), freq(freq_), amplitude(amplitude_), confidence(confidence_) {} - + //! copy constructor (does what you'd expect, explicit to satisify compiler warning) PitchEvent(const PitchEvent &p) : EventBase(p), freq(p.freq), amplitude(p.amplitude), confidence(p.confidence) @@ -37,10 +40,15 @@ float getAmplitude(void) const { return amplitude; } //!< returns #amplitude float getConfidence(void) const { return confidence; } //!< returns #confidence + virtual classTypeID_t getClassTypeID() const { return autoRegisterPitchEvent; } + protected: float freq; //!< the frequency (Hz) being detected float amplitude; //!< indicates how loud the signal is -- can be both loud and noisy, loud doesn't necessarily mean "strong" float confidence; //!< indicates how much variance is being detected + + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterPitchEvent; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/RemoteEvents.cc ./Events/RemoteEvents.cc --- ../Tekkotsu_3.0/Events/RemoteEvents.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/RemoteEvents.cc 2007-10-16 13:37:21.000000000 -0400 @@ -0,0 +1,72 @@ +#include "Events/RemoteEvents.h" +#include "Events/EventRouter.h" + +RemoteEvents::RemoteEvents() : sck(NULL), + sizeLeft(0), vecbuf(), bufType(Invalid) { + +} + +RemoteEvents::~RemoteEvents() { + +} + +std::string RemoteEvents::remoteIPString() { + return EventRouter::intToStringIP(remoteIPInt()); +} + +int RemoteEvents::remoteIPInt() { + return sck->getPeerAddress(); +} + +//Receiving data------------------------------------------- + +/* Reads in the buffer type header */ +bool RemoteEvents::readType(char* &data, int &bytes) { + //printf("Got pointer: %x, %d bytes\n", data, bytes); + if ((unsigned)bytes < sizeof(BufferType)) + return false; + + bufType = *(BufferType *)data; + data += sizeof(BufferType); + bytes -= sizeof(BufferType); + return true; +} + +/* Reads in a size header from the data pointer. */ +bool RemoteEvents::readSize(char* &data, int &bytes) { + //Return an error if there's not enough data there + if ((unsigned)bytes < sizeof(int)) + return false; + + //Reset the buffer + vecbuf.clear(); + + //Read the size and increment/decrement things as appropriate + sizeLeft = *(int *)data; + data += sizeof(int); + bytes -= sizeof(int); + return true; +} + +/* Reads in data from the given pointer until the target size is + * reached, or bytes becomes zero. Return true if the whole desired + * chunk was read, false otherwise. */ +bool RemoteEvents::readData(char* &data, int &bytes) { + while (bytes) { + //If sizeLeft is zero it's done reading the data + if (!sizeLeft) + return true; + + //Read a byte + vecbuf.push_back(*data++); + bytes--; + sizeLeft--; + } + //Return whether or not the whole chunk was read + return !sizeLeft; +} +//------------------------------------------------------ + +bool RemoteEvents::isConnected() { + return wireless->isConnected(sck->sock); +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/RemoteEvents.h ./Events/RemoteEvents.h --- ../Tekkotsu_3.0/Events/RemoteEvents.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/RemoteEvents.h 2007-11-12 23:16:02.000000000 -0500 @@ -0,0 +1,89 @@ +#ifndef _REMOTEEVENTS_H_ +#define _REMOTEEVENTS_H_ + +#include "Wireless/Socket.h" +#include "Wireless/Wireless.h" +#include "Wireless/SocketListener.h" +#include "Events/EventBase.h" +#include "Events/NetworkBuffer.h" +#include "Shared/RemoteState.h" +#include +#include + + +/*! This class contains the network code common between RemoteRouter + * and EventProxy. It contains methods for sending and receiving + * events, state updates, and requests to recieve the former two + * things. */ +class RemoteEvents : public SocketListener { + public: + + //! This is sent in the header of any data sent over the wireless, + //it indicates what type of data it is + enum BufferType { + Invalid, + StateData, + EventData, + RequestData + }; + + //! This is sent in the header of any requests for remote events + //or state updates + enum RequestType { + EventListenerRequest, + StateUpdateRequest, + RemoveEventListenerRequest, + StopStateUpdateRequest + }; + + //! Returns true of the socket is connected + bool isConnected(); + + //! Returns the remote IP address as a string + std::string remoteIPString(); + + //! Returns the remote IP address as an int + int remoteIPInt(); + + + static const int defaultBufferSize = 1024; + + protected: + + //This is so the class can't be instantiated by itself + RemoteEvents(); + virtual ~RemoteEvents(); + + Socket *sck; + + //Methods and variables for receiving data------------------ + int sizeLeft; + std::vector vecbuf; + BufferType bufType; + + bool readSize(char* &data, int &bytes); + bool readType(char* &data, int &bytes); + bool readData(char* &data, int &bytes); + //------------------------------------------------------- + + RemoteEvents(RemoteEvents&); + RemoteEvents &operator=(const RemoteEvents&); +}; + +/*! This struct holds the information required for a request to a + * server robot for events for state updates. */ +struct RemoteRequest { + RemoteEvents::RequestType type; + + //Event subscription + int numElements; + EventBase::EventGeneratorID_t egid; + size_t sid; + EventBase::EventTypeID_t etid; + + //State updates + RemoteState::StateType sType; + unsigned int interval; +}; + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/RemoteRouter.cc ./Events/RemoteRouter.cc --- ../Tekkotsu_3.0/Events/RemoteRouter.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/RemoteRouter.cc 2007-11-12 23:16:02.000000000 -0500 @@ -0,0 +1,283 @@ +#include "Events/RemoteRouter.h" +#include "Events/EventRouter.h" + +#include "Events/TextMsgEvent.h" +#include "Events/TimerEvent.h" +#include "Events/FilterBankEvent.h" +#include "Events/LocomotionEvent.h" +#include "Events/LookoutEvents.h" +#include "Events/PitchEvent.h" +#include "Events/VisionObjectEvent.h" + +using namespace std; + +RemoteRouter::RemoteRouter(int host) : RemoteEvents(), + rstate(NULL), waitingForPort(true), + requestQueue(), + timerActive(false), waitTime(0), + remoteHost(0) { + rstate = new RemoteState(this); + + remoteHost = host; + + connect(EventRouter::defaultPort); + erouter->addTimer(this, 1, 500, true); +} + +RemoteRouter::~RemoteRouter() { + delete rstate; + + wireless->close(sck); +} + +void RemoteRouter::forwardEvent(std::vector &evec) { + //Decode the event from the buffer and send it + + unsigned int size = evec.size(); + char *buf = &evec[0]; + EventBase etest, *event = NULL; + + if (!etest.checkInc((int)etest.loadBinaryBuffer(buf, size), buf, size)) { + cout << "Error: Received event is not a subclass of EventBase" << endl; + return; + } + + + //If there are bytes left, it's not just an EventBase + if (size) { + + if (etest.checkCreator("EventBase::TextMsgEvent", + buf, size, false)) { + event = new TextMsgEvent(); + } else if (etest.checkCreator("EventBase::TimerEvent", + buf, size, false)) { + event = new TimerEvent(); + } else if (etest.checkCreator("EventBase::LocomotionEvent", + buf, size, false)) { + event = new LocomotionEvent(); + } else if (etest.checkCreator("EventBase::VisionObjectEvent", + buf, size, false)) { + event = new VisionObjectEvent(); + } else { + cout << "Buffer isn't a recognized event type. " << endl; + } + + } else { + event = new EventBase(); + } + + //Load the buffer + if (event) { + if (!event->loadBinaryBuffer(&evec[0], evec.size())) { + cout << "Error loading from buffer" << endl; + } else { + cout << "Created event object successfully. Posting event from host " + << EventRouter::intToStringIP(remoteHost) << endl; + + event->setHostID(remoteHost); + erouter->postEvent(*event); + + delete event; + } + } +} + +void RemoteRouter::connect(int port) { + std::string ip = EventRouter::intToStringIP(remoteHost); + cout << "RemoteRouter: Connecting to " << ip << " on port " + << port << endl; + sck = wireless->socket(Socket::SOCK_STREAM); + wireless->setReceiver(sck, this); + if (wireless->connect(sck, ip.c_str(), port)) { + cout << "RemoteRouter: error connecting to remote host" << endl; + } +} + +int RemoteRouter::processData(char *data, int bytes) { + if (waitingForPort) { + if (bytes != sizeof(int)) { + cout << "RemoteRouter: unexpected data" << endl; + return -1; + } + + wireless->close(sck); + int port = *(int *)data; + connect(port); + waitingForPort = false; + return 0; + } + + while (bytes) { + if (bufType == Invalid) { + //Get the buffer type + if (!readType(data, bytes)) + cout << "Error reading buffer type" << endl; + + } else if (!sizeLeft) { + //Get the size + if (!readSize(data, bytes)) + cout << "Error reading buffer size" << endl; + + } else { + //Read some data + if (readData(data, bytes)) { + //Dispatch the chunk of data + switch(bufType) { + case EventData: + forwardEvent(vecbuf); + break; + case StateData: + rstate->update(&vecbuf[0]); + break; + case Invalid: + cout << "Error: invalid data. This should never happen." << endl; + return -1; + default: + cout << "Error: data came in that wasn't expected" << endl; + return -1; + } + bufType = Invalid; + } + } + + } + + return 0; +} + +void RemoteRouter::requestStateUpdates(RemoteState::StateType type, + unsigned int interval) { + RemoteRequest info; + info.type = StateUpdateRequest; + info.sType = type; + info.interval = interval; + sendRemoteRequest(info); +} + +void RemoteRouter::stopStateUpdates(RemoteState::StateType type) { + RemoteRequest info; + info.type = StopStateUpdateRequest; + info.sType = type; + sendRemoteRequest(info); +} + +void RemoteRouter::addListener(EventBase::EventGeneratorID_t egid) { + RemoteRequest info; + info.type = EventListenerRequest; + info.numElements = 1; + info.egid = egid; + sendRemoteRequest(info); +} + +void RemoteRouter::addListener(EventBase::EventGeneratorID_t egid, + size_t sid) { + RemoteRequest info; + info.type = EventListenerRequest; + info.numElements = 2; + info.egid = egid; + info.sid = sid; + sendRemoteRequest(info); +} + +void RemoteRouter::addListener(EventBase::EventGeneratorID_t egid, + size_t sid, + EventBase::EventTypeID_t etid) { + RemoteRequest info; + info.type = EventListenerRequest; + info.numElements = 3; + info.egid = egid; + info.sid = sid; + info.etid = etid; + sendRemoteRequest(info); +} + +void RemoteRouter::removeListener(EventBase::EventGeneratorID_t egid) { + RemoteRequest info; + info.type = RemoveEventListenerRequest; + info.numElements = 1; + info.egid = egid; + sendRemoteRequest(info); +} + +void RemoteRouter::removeListener(EventBase::EventGeneratorID_t egid, + size_t sid) { + RemoteRequest info; + info.type = RemoveEventListenerRequest; + info.numElements = 2; + info.egid = egid; + info.sid = sid; + sendRemoteRequest(info); +} + +void RemoteRouter::removeListener(EventBase::EventGeneratorID_t egid, + size_t sid, + EventBase::EventTypeID_t etid) { + RemoteRequest info; + info.type = RemoveEventListenerRequest; + info.numElements = 3; + info.egid = egid; + info.sid = sid; + info.etid = etid; + sendRemoteRequest(info); +} + +void RemoteRouter::processEvent(const EventBase& event) { + if (event.getGeneratorID() == EventBase::timerEGID ) { + switch(event.getSourceID()) { + case 0: + if (isReady()) { + cout << "Connected! Sending queue of requests" << endl; + while (requestQueue.size()) { + sendRemoteRequest(requestQueue.front()); + requestQueue.pop_front(); + } + + erouter->removeTimer(this, 0); + timerActive = false; + } else { + waitTime += 500; + if (waitTime == 5000) { + cout << "RemoteRouter has been waiting for 5 seconds to connect, " + << "are you sure you specified the right host?" << endl; + } + } + break; + + case 1: + if (isConnected()) { + int foo = 0; + sck->write((byte *)&foo, sizeof(int)); + erouter->removeTimer(this, 1); + } + break; + + default: + cout << "RemoteRouter got unknown timer event" << endl; + } + } +} + +void RemoteRouter::sendRemoteRequest(RemoteRequest &info) { + if (!isReady()) { + cout << "Tried to send remote request but not connected! Queuing RemoteRequest..." << endl; + + requestQueue.push_back(info); + if (!timerActive) { + erouter->addTimer(this, 0, 500, true); + timerActive = true; + waitTime = 0; + } + return; + } + + NetworkBuffer nBuf; + + nBuf.addItem(RequestData); + nBuf.addItem(sizeof(RemoteRequest)); + nBuf.addItem(info); + + if (!nBuf.send(sck)) { + cout << "Error sending remote request" << endl; + return; + } +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/RemoteRouter.h ./Events/RemoteRouter.h --- ../Tekkotsu_3.0/Events/RemoteRouter.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Events/RemoteRouter.h 2007-11-12 23:16:02.000000000 -0500 @@ -0,0 +1,95 @@ +#ifndef REMOTEROUTER_H_ +#define REMOTEROUTER_H_ + +#include +#include "Wireless/Socket.h" +#include "Wireless/Wireless.h" +#include "Events/RemoteEvents.h" +#include "Events/EventProxy.h" +#include "Events/EventListener.h" +#include "Shared/RemoteState.h" + +#include +#include + +class RemoteState; + +/* ! This class allows a client robot to subscribe to events and state updates on a remote robot. It receives events and state from EventProxy on the + * remote server robot. It is started automatically. Subscribe to events on remote robots using EventRouter::addRemoteListener() and state updates using + * EventRouter::requestRemoteStateUpdates() + */ +class RemoteRouter : public RemoteEvents, public EventListener { + public: + + //! constructor + RemoteRouter(int host); + + //! destructor + virtual ~RemoteRouter(); + + //! Request state data from a remote robot every 'interval' amount of time. Use EventRouter::requestRemoteStateUpdates() rather than calling this directly. + void requestStateUpdates(RemoteState::StateType type, unsigned int interval); + + //! Cancels state data updates from a remote dog for the given StateType. Use EventRouter::stopRemoteStateUpdates() rather than calling this directly. + void stopStateUpdates(RemoteState::StateType type); + + //! Add remote listener by EGID. Use EventRouter::addRemoteListener() rather than calling this directly. + void addListener(EventBase::EventGeneratorID_t egid); + + //! Add remote listener by EGID and SID. Use EventRouter::addRemoteListener() rather than calling this directly. + void addListener(EventBase::EventGeneratorID_t egid, + size_t sid); + + //! Add remote listener by EGID, SID, and ETID. Use EventRouter::addRemoteListener() rather than calling this directly. + void addListener(EventBase::EventGeneratorID_t egid, + size_t sid, + EventBase::EventTypeID_t etid); + + //! Remove remote listener by EGID. Use EventRouter::removeRemoteListener() rather than calling this directly. + void removeListener(EventBase::EventGeneratorID_t egid); + + //! Remove remote listener by EGID and SID. Use EventRouter::removeRemoteListener() rather than calling this directly. + void removeListener(EventBase::EventGeneratorID_t egid, + size_t sid); + + //! Remove remote listener by EGID, SID, and ETID. Use EventRouter::removeRemoteListener() rather than calling this directly. + void removeListener(EventBase::EventGeneratorID_t egid, + size_t sid, + EventBase::EventTypeID_t etid); + + RemoteState *rstate; + + //! Processes timer events which wait for connections to remote EventProxy. + void processEvent(const EventBase& event); + + //! Receives data from remote EventProxy and forwards it to the correct function according to the data type (Event or State) + int processData(char *data, int bytes); + + protected: + + //! Returns true when robot is connected to remote robot + bool isReady() { + return !waitingForPort && isConnected(); + } + + //! Connect robot on specified port + void connect(int port); + + bool waitingForPort; + std::list requestQueue; + bool timerActive; + int waitTime; + + int remoteHost; + + //! Add a remote request to the request queue + void sendRemoteRequest(RemoteRequest& info); + + //! Decode the event from the buffer and post it locally + void forwardEvent(std::vector& event); + + RemoteRouter(RemoteRouter&); + RemoteRouter &operator=(const RemoteRouter&); +}; + +#endif /*REMOTEROUTER_H_*/ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/SegmentedColorFilterBankEvent.h ./Events/SegmentedColorFilterBankEvent.h --- ../Tekkotsu_3.0/Events/SegmentedColorFilterBankEvent.h 2005-06-29 18:03:35.000000000 -0400 +++ ./Events/SegmentedColorFilterBankEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -21,12 +21,12 @@ typedef __gnu_cxx::hash_map, hashcmp_eqstr> hashmap; //!< a shorthand for the hash structure that CMVision expects for the color lookups //! constructor, to be used when first segmented, later stages should use the other constructor - SegmentedColorFilterBankEvent(FilterBankGenerator* creator,EventBase::EventGeneratorID_t gid,unsigned int sid,EventBase::EventTypeID_t tid, FilterBankGenerator* segColorSrc, unsigned int nColors, color_class_state * colorInfos, const hashmap * clrNames) + SegmentedColorFilterBankEvent(FilterBankGenerator* creator,EventBase::EventGeneratorID_t gid,size_t sid,EventBase::EventTypeID_t tid, FilterBankGenerator* segColorSrc, unsigned int nColors, color_class_state * colorInfos, const hashmap * clrNames) : FilterBankEvent(creator,gid,sid,tid), segsrc(segColorSrc), numColors(nColors), colors(colorInfos), colorNames(clrNames) {} //! constructor, allows you to pass along color information to later stages - SegmentedColorFilterBankEvent(FilterBankGenerator* creator,EventBase::EventGeneratorID_t gid,unsigned int sid,EventBase::EventTypeID_t tid, const SegmentedColorFilterBankEvent& segevt ) + SegmentedColorFilterBankEvent(FilterBankGenerator* creator,EventBase::EventGeneratorID_t gid,size_t sid,EventBase::EventTypeID_t tid, const SegmentedColorFilterBankEvent& segevt ) : FilterBankEvent(creator,gid,sid,tid), segsrc(segevt.segsrc), numColors(segevt.numColors), colors(segevt.colors), colorNames(segevt.colorNames) {} @@ -71,13 +71,22 @@ //! returns index of color corresponding to a string (uses a fast hash lookup) inline unsigned int getColorIndex(const std::string& name) const { return getColorIndex(name.c_str()); } + virtual classTypeID_t getClassTypeID() const { return autoRegisterSegmentedColorFilterBankEvent; } + protected: //! pointer to generator which did the segmentation and therefore holds the color information FilterBankGenerator* segsrc; unsigned int numColors; //!< number of available colors - const color_class_state * colors; //!< array of available colors - const hashmap * colorNames; //!< hash map to look up index from name + const color_class_state * colors; //!< array of available colors + const hashmap * colorNames; //!< hash map to look up index from name + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + /*! This is instantiated in EventBase.cc to save on file bloat */ + static const EventBase::classTypeID_t autoRegisterSegmentedColorFilterBankEvent; + + //! default constructor, only intended to be called from the FamilyFactory, followed by a loadXML... + SegmentedColorFilterBankEvent() : FilterBankEvent(), segsrc(NULL), numColors(), colors(), colorNames() {} + friend struct Factory0Arg::Factory; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/TextMsgEvent.cc ./Events/TextMsgEvent.cc --- ../Tekkotsu_3.0/Events/TextMsgEvent.cc 2006-09-09 00:32:48.000000000 -0400 +++ ./Events/TextMsgEvent.cc 2007-05-21 13:02:39.000000000 -0400 @@ -2,6 +2,8 @@ #include #include +const EventBase::classTypeID_t TextMsgEvent::autoRegisterTextMsgEvent=getTypeRegistry().registerType(makeClassTypeID("TXTM")); + std::string TextMsgEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const { if(!showTypeSpecific) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/TextMsgEvent.h ./Events/TextMsgEvent.h --- ../Tekkotsu_3.0/Events/TextMsgEvent.h 2006-09-09 00:32:48.000000000 -0400 +++ ./Events/TextMsgEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -8,21 +8,18 @@ class TextMsgEvent : public EventBase { public: //! Constructor - TextMsgEvent() : EventBase(EventBase::textmsgEGID,(unsigned int)-1, EventBase::statusETID,0),_text("")/*,_token(0)*/ { } + TextMsgEvent() : EventBase(EventBase::textmsgEGID,(size_t)-1, EventBase::statusETID,0),_text("")/*,_token(0)*/ { } - //! Constructor, pass a text msg - TextMsgEvent(const std::string& text, unsigned int srcID=-1U) : EventBase(EventBase::textmsgEGID,srcID, EventBase::statusETID,0),_text(text)/*,_token(0)*/ { } + //! Constructor, pass a text msg + TextMsgEvent(const std::string& text, size_t srcID=-1U) : EventBase(EventBase::textmsgEGID,srcID, EventBase::statusETID,0),_text(text)/*,_token(0)*/ { } virtual EventBase* clone() const { return new TextMsgEvent(*this); } - virtual unsigned int getClassTypeID() const { return makeClassTypeID("TXTM"); } + virtual unsigned int getClassTypeID() const { return autoRegisterTextMsgEvent; } - std::string getText() const { return _text; } //!< returns the text - TextMsgEvent& setText(const std::string& text) { _text=text; return *this; } //!< sets the text + std::string getText() const { return _text; } //!< returns the text + TextMsgEvent& setText(const std::string& text) { _text=text; return *this; } //!< sets the text - //int getToken() const { return _token; } //!< returns the token - //TextMsgEvent& setToken(int token) { _token=token; return *this;} //!< sets the token - std::string getDescription(bool showTypeSpecific=true, unsigned int verbosity=0) const; virtual unsigned int getBinSize() const; @@ -32,8 +29,10 @@ virtual void saveXML(xmlNode * node) const; protected: - std::string _text; //!< the unmodified arguments passed to the command - //int _token; //!< for future expansion, to support centralized parsing + std::string _text; //!< the unmodified arguments passed to the command + + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterTextMsgEvent; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/TimerEvent.cc ./Events/TimerEvent.cc --- ../Tekkotsu_3.0/Events/TimerEvent.cc 2006-09-09 00:32:49.000000000 -0400 +++ ./Events/TimerEvent.cc 2007-05-21 13:02:39.000000000 -0400 @@ -3,9 +3,10 @@ #include #include -//better to put this here instead of the header using namespace std; +const EventBase::classTypeID_t TimerEvent::autoRegisterTimerEvent=getTypeRegistry().registerType(makeClassTypeID("TIMR")); + std::string TimerEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const { if(!showTypeSpecific) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/TimerEvent.h ./Events/TimerEvent.h --- ../Tekkotsu_3.0/Events/TimerEvent.h 2006-09-16 16:11:51.000000000 -0400 +++ ./Events/TimerEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -14,7 +14,7 @@ //! empty constructor, initializes #target to NULL TimerEvent() : EventBase(), target(NULL) {} //! the full specification constructor, pass original requester @a tgt, generator @a gid (probably should always be EventBase::timerEGID), source @a sid, type @a tid (typically EventBase::statusETID), and duration @a dur - TimerEvent(EventListener * tgt, EventGeneratorID_t gid, unsigned int sid, EventTypeID_t tid, unsigned int dur=0) : EventBase(gid,sid,tid,dur), target(tgt) {} + TimerEvent(EventListener * tgt, EventGeneratorID_t gid, size_t sid, EventTypeID_t tid, unsigned int dur=0) : EventBase(gid,sid,tid,dur), target(tgt) {} //! copy constructor, does a shallow copy (copies pointer value, doesn't try to clone #target!) TimerEvent(const TimerEvent& te) : EventBase(te), target(te.target) {} //! assignment operator, does a shallow copy (copies pointer value, doesn't try to clone #target!) @@ -22,7 +22,7 @@ virtual EventBase* clone() const { return new TimerEvent(*this); } - virtual unsigned int getClassTypeID() const { return makeClassTypeID("TIMR"); } + virtual unsigned int getClassTypeID() const { return autoRegisterTimerEvent; } EventListener * getTarget() const { return target; } //!< returns #target void setTarget(EventListener* tgt) { target=tgt; } //!< assigns @a tgt to #target @@ -37,6 +37,9 @@ protected: EventListener * target; //!< indicates the listener for which the timer was created + + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterTimerEvent; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/VisionObjectEvent.cc ./Events/VisionObjectEvent.cc --- ../Tekkotsu_3.0/Events/VisionObjectEvent.cc 2006-09-09 00:32:50.000000000 -0400 +++ ./Events/VisionObjectEvent.cc 2007-05-21 13:02:39.000000000 -0400 @@ -3,7 +3,7 @@ #include #include -// Changed 'getDescription' to show BB and area info in EventLogger. Change functions to add new parameters (BB and area) to buffer +const EventBase::classTypeID_t VisionObjectEvent::autoRegisterVisionObjectEvent=getTypeRegistry().registerType(makeClassTypeID("VISO")); std::string VisionObjectEvent::getDescription(bool showTypeSpecific/*=true*/, unsigned int verbosity/*=0*/) const { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/VisionObjectEvent.h ./Events/VisionObjectEvent.h --- ../Tekkotsu_3.0/Events/VisionObjectEvent.h 2006-09-09 00:32:50.000000000 -0400 +++ ./Events/VisionObjectEvent.h 2007-11-12 23:16:02.000000000 -0500 @@ -11,7 +11,7 @@ /*! @param sid The source ID for the object being detected -- you can define your own values, some are already set in ProjectInterface, but can be reassigned during your project's startup * @param tid The type ID for the event */ - explicit VisionObjectEvent(unsigned int sid=0,EventTypeID_t tid=EventBase::deactivateETID) + explicit VisionObjectEvent(size_t sid=0,EventTypeID_t tid=EventBase::deactivateETID) : EventBase(EventBase::visObjEGID,sid,tid,0), _x1(0),_x2(0),_y1(0),_y2(0), _area(0), _clipLeft(false), _clipRight(false), _clipTop(false), _clipBottom(false), @@ -29,7 +29,7 @@ * @param rx The plus/minus range of the x coordinates (generally xres/xres for cameras which are wider than they are high) * @param ry The plus/minus range of the y coordinates (camera yres/xres for cameras which are wider than they are high) */ - VisionObjectEvent(unsigned int sid, EventTypeID_t tid, float x1, float x2, float y1, float y2,float objarea, float rx, float ry) + VisionObjectEvent(size_t sid, EventTypeID_t tid, float x1, float x2, float y1, float y2,float objarea, float rx, float ry) : EventBase(EventBase::visObjEGID,sid,tid,0), _x1(x1),_x2(x2),_y1(y1),_y2(y2), _area(objarea), _clipLeft(_x1<=-rx), _clipRight(_x2>=rx), _clipTop(_y1<=-ry), _clipBottom(_y2>=ry), @@ -48,7 +48,7 @@ * @param ry The plus/minus range of the y coordinates (camera yres/xres for cameras which are wider than they are high) * @param frame The camera frame number the object was detected in (see #_frame) */ - VisionObjectEvent(unsigned int sid, EventTypeID_t tid, float x1, float x2, float y1, float y2, float objarea, float rx, float ry,unsigned int frame) + VisionObjectEvent(size_t sid, EventTypeID_t tid, float x1, float x2, float y1, float y2, float objarea, float rx, float ry,unsigned int frame) : EventBase(EventBase::visObjEGID,sid,tid,0), _x1(x1),_x2(x2),_y1(y1),_y2(y2), _area(objarea), _clipLeft(_x1<=-rx), _clipRight(_x2>=rx), _clipTop(_y1<=-ry), _clipBottom(_y2>=ry), @@ -60,7 +60,7 @@ virtual EventBase* clone() const { return new VisionObjectEvent(*this); } - virtual unsigned int getClassTypeID() const { return makeClassTypeID("VISO"); } + virtual unsigned int getClassTypeID() const { return autoRegisterVisionObjectEvent; } //!@name Attribute Accessors float getLeft() const { return _x1;} //!< returns the initial x (#_x1) coordinate of the Bounding Box (inclusive value) @@ -75,7 +75,7 @@ float getBottom() const { return _y2;} //!< returns the final y (#_y2) coordinate of the Bounding Box (inclusive value) VisionObjectEvent& setBottom(float y2) { _y2=y2; return *this;} //!< sets the final y (#_y2) coordinate of the Bounding Box - float getObjectArea() const { return _area; } //!< returns the object's #_area within the camera, in squared generalized coordinates. Multiply by the square of the major camera resolution (normally #RobotInfo::CameraResolutionX if using full resolution) and divide by 4.0 to get pixel area. + float getObjectArea() const { return _area; } //!< returns the object's #_area within the camera, in squared generalized coordinates. Multiply by the square of the major camera resolution (normally RobotInfo::CameraResolutionX if using full resolution) and divide by 4.0 to get pixel area. VisionObjectEvent& setObjectArea(float objarea) { _area=objarea; return *this; } //!< sets the object's #_area within the camera, in squared generalized coordinates (multiply by the major camera resolution to get pixel area) //@} @@ -113,7 +113,7 @@ float _x2; //!< a value representing location in visual field - from -1 if on the left edge to 1 if it's on the right edge float _y1; //!< top boundary, in range of @f$ \pm\frac{160}{208} @f$) for ERS-7; actual values vary depending on aspect ratio to keep square coordinates float _y2; //!< bottom boundary, in approximately @f$ \pm\frac{160}{208} @f$ for ERS-7; actual values vary depending on aspect ratio to keep square coordinates - float _area; //!< area of the actual object within bounding box as set by generator, in same units as getBoundaryArea(). Multiply by the square of the major camera resolution (normally #RobotInfo::CameraResolutionX if using full resolution) and divide by 4.0 to get pixel area. + float _area; //!< area of the actual object within bounding box as set by generator, in same units as getBoundaryArea(). Multiply by the square of the major camera resolution (normally RobotInfo::CameraResolutionX if using full resolution) and divide by 4.0 to get pixel area. bool _clipLeft; //!< flag to indicate left boundary is on or beyond the camera image's boundary bool _clipRight; //!< flag to indicate right boundary is on or beyond the camera image's boundary bool _clipTop; //!< flag to indicate top boundary is on or beyond the camera image's boundary @@ -121,6 +121,9 @@ float _xRange; //!< Max range of X dimension (typically 1.0 for AIBO) float _yRange; //!< Max range of Y dimension (typically around 0.8 for AIBO due to camera aspect ratio) unsigned int _frame; //!< Number of frame when the event was generated. + + //! causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry()) + static const EventBase::classTypeID_t autoRegisterVisionObjectEvent; }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/INSTALL ./INSTALL --- ../Tekkotsu_3.0/INSTALL 2003-08-23 19:25:37.000000000 -0400 +++ ./INSTALL 2007-11-08 22:43:04.000000000 -0500 @@ -1,5 +1,5 @@ For full information on installation, visit: - http://www.tekkotsu.org/TekkotsuInstall.html + http://www.tekkotsu.org/downloads.html#installtekkotsu In short, you should put the Tekkotsu directory someplace like /usr/local (the default location scripts will look), and then copy @@ -14,3 +14,4 @@ Your code should go in your own copy of the 'project' directory. To build an executable, type 'make' in your local copy of 'project'. + You should edit project's Environment.conf to choose build settings. diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/ListMemBuf.h ./IPC/ListMemBuf.h --- ../Tekkotsu_3.0/IPC/ListMemBuf.h 2005-06-01 01:47:46.000000000 -0400 +++ ./IPC/ListMemBuf.h 2007-08-24 23:32:06.000000000 -0400 @@ -36,16 +36,19 @@ index_t countb() const; //!< for debugging, should equal size bool empty() const { return cursize==0; } //!(entries[x].data); } //!(entries[x].data); } //!(entries[activeBegin].data); } //!< returns reference to first used entry - const T& front() const { return *reinterpret_cast(entries[activeBegin].data); } //!< returns const reference to first used entry + T& front() { return *(T*)(void*)(entries[activeBegin].data); } //!< returns reference to first used entry + const T& front() const { return *(const T*)(const void*)(entries[activeBegin].data); } //!< returns const reference to first used entry inline index_t end() const { return (index_t)-1; } //!(entries[activeBack].data); } //!(entries[activeBack].data); } //! #include "Shared/TimeET.h" -//#include "local/sim/Process.h" //! Defines the interface for sending new shared memory regions between processes /*! This base class holds all of the template-independent code to allow general @@ -57,9 +58,9 @@ typedef unsigned short index_t; - //!< add one to the receiver reference count + //! add one to the receiver reference count virtual SemaphoreManager::semid_t addReceiver() ATTR_must_check =0; - //!< remove one from the receiver reference count + //! remove one from the receiver reference count virtual void removeReceiver(SemaphoreManager::semid_t rcvr)=0; //! return the receiver reference count virtual unsigned int getNumReceivers() const { return numReceivers; } @@ -103,11 +104,13 @@ //! do not allow any new messages to be posted virtual void close() { AutoLock autolock(lock); isClosed=true; } + //! sets #reportDroppings virtual void setReportDroppings(bool report) { reportDroppings=report; } + //! gets #reportDroppings virtual bool getReportDroppings() const { return reportDroppings; } - //! Each message gets a unique, monotonically increasing serial number; this function returns that number (#serialNumber) + //! Each message gets a unique, monotonically increasing serial number; this function returns that number (MessageQueue::serialNumber) virtual unsigned int getMessageSN(index_t msg)=0; //! Checks to see how many messages have been processed (read by all receivers and removed from queue) @@ -143,12 +146,10 @@ //! returns the current overflow policy, see OverflowPolicy_t OverflowPolicy_t getOverflowPolicy() const { return overflowPolicy; } - static void setSemaphoreManager(SemaphoreManager* mgr) { - semgr=mgr; - } - static SemaphoreManager* getSemaphoreManager() { - return semgr; - } + //! sets #semgr + static void setSemaphoreManager(SemaphoreManager* mgr) { semgr=mgr; } + //! gets #semgr + static SemaphoreManager* getSemaphoreManager() { return semgr; } //! once called, any messages put into the queue must pass through @a filter first (note: there can only be one filter per process!) /*! if a filter was previously registered, it is replaced with the new @a filter */ @@ -223,7 +224,7 @@ entry() : id(), sn(), numRead(0) { memset(readFlags,0,sizeof(readFlags)); } //!< constructor entry(unsigned int serialNumber, RCRegion* r) : id(r->ID()), sn(serialNumber), numRead(0) { memset(readFlags,0,sizeof(readFlags)); } //!< constructor, pass message info - RCRegion::Identifier id; //! the identifier for the shared memory region so that other regions can attach it + RCRegion::Identifier id; //!< the identifier for the shared memory region so that other regions can attach it unsigned int sn; //!< serial number for this message (not the same as its index in the queue -- indicies are reused, this id is unique to this message bool readFlags[MAX_RECEIVERS]; //!< a flag for each receiver to indicate if they have read it unsigned int numRead; //!< a count of the number of receivers which have read this message (should always equal sum(readFlags)) @@ -239,7 +240,7 @@ //! the data storage of receiver semaphores rcvrs_t rcvrs; - //! returns the index within #rcvrs of the receiver id #rcvr + //! returns the index within #rcvrs of the receiver id @a rcvr typename rcvrs_t::index_t lookupReceiver(SemaphoreManager::semid_t rcvr) const; //! shorthand for the type of data storage of message entries diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/MessageQueueStatusThread.cc ./IPC/MessageQueueStatusThread.cc --- ../Tekkotsu_3.0/IPC/MessageQueueStatusThread.cc 2006-08-29 01:56:46.000000000 -0400 +++ ./IPC/MessageQueueStatusThread.cc 2007-10-12 12:55:04.000000000 -0400 @@ -7,7 +7,7 @@ using namespace std; MessageQueueStatusThread::~MessageQueueStatusThread() { - if(isRunning()) { + if(isStarted()) { stop(); //join(); // join turns out to be a bad idea here -- the thread being stopped may be waiting on a lock we currently hold } @@ -19,7 +19,7 @@ if(find(statusListeners.begin(),statusListeners.end(),l)==statusListeners.end()) { //not already added statusListeners.push_back(l); - if(!isRunning()) { + if(!isStarted()) { if(queue==NULL) return; semid=queue->addReadStatusListener(); @@ -38,7 +38,7 @@ std::list::iterator it=find(statusListeners.begin(),statusListeners.end(),l); if(it!=statusListeners.end()) statusListeners.erase(it); - if(isRunning() && statusListeners.size()==0) { + if(isStarted() && statusListeners.size()==0) { stop(); //join(); // join turns out to be a bad idea here -- the thread being stopped may be waiting on a lock we currently hold } @@ -100,6 +100,7 @@ //ok, notify the listeners fireMessagesRead(more+1); } + return NULL; // not going to happen, just to make compiler happy } void MessageQueueStatusThread::stop() { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/MessageQueueStatusThread.h ./IPC/MessageQueueStatusThread.h --- ../Tekkotsu_3.0/IPC/MessageQueueStatusThread.h 2006-06-16 21:15:38.000000000 -0400 +++ ./IPC/MessageQueueStatusThread.h 2007-11-10 17:58:08.000000000 -0500 @@ -25,7 +25,7 @@ /*! Don't assume that because you receive this callback there is space in * the queue -- an earlier listener may have already added a message, or * the queue might have been already waiting to send a message if - * #overflowPolicy is #WAIT + * the queue's overflowPolicy is MessageQueueBase::WAIT * * @param which The MessageQueueBase which has had message(s) read * @param howmany The number of message which have been cleared */ @@ -79,7 +79,7 @@ //! the semaphore which is being monitored, raised by #queue when a message is read SemaphoreManager::semid_t semid; - //! the number of messages read sent last time #sem was raised + //! the number of messages read sent last time the semaphore (#semid) was raised unsigned int numRead; private: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/MessageReceiver.cc ./IPC/MessageReceiver.cc --- ../Tekkotsu_3.0/IPC/MessageReceiver.cc 2006-08-23 17:48:10.000000000 -0400 +++ ./IPC/MessageReceiver.cc 2007-10-12 12:55:04.000000000 -0400 @@ -21,7 +21,7 @@ } MessageReceiver::~MessageReceiver() { - if(!isRunning()) + if(!isStarted()) return; stop(); join(); @@ -65,7 +65,7 @@ } void MessageReceiver::finish() { - if(isRunning()) { + if(isStarted()) { stop(); join(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/MutexLock.cc ./IPC/MutexLock.cc --- ../Tekkotsu_3.0/IPC/MutexLock.cc 2006-05-08 18:07:54.000000000 -0400 +++ ./IPC/MutexLock.cc 2007-06-14 02:22:29.000000000 -0400 @@ -2,10 +2,9 @@ unsigned int MutexLockBase::usleep_granularity=5000; -#ifndef PLATFORM_APERIOS +#if !defined(PLATFORM_APERIOS) && TEKKOTSU_SHM_STYLE!=NO_SHM SemaphoreManager MutexLockBase::preallocated; SemaphoreManager* MutexLockBase::semgr=&preallocated; -ThreadNS::Lock MutexLockBase::thdLocks[SemaphoreManager::MAX_SEM]; #endif /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/MutexLock.h ./IPC/MutexLock.h --- ../Tekkotsu_3.0/IPC/MutexLock.h 2006-08-11 17:51:40.000000000 -0400 +++ ./IPC/MutexLock.h 2007-11-10 17:58:08.000000000 -0500 @@ -9,9 +9,13 @@ #include #ifndef PLATFORM_APERIOS -# include # include "SemaphoreManager.h" -# include "Thread.h" +# if !defined(MUTEX_LOCK_ET_USE_SOFTWARE_ONLY) && TEKKOTSU_SHM_STYLE==NO_SHM +# include "Thread.h" +# endif +# include "RCRegion.h" +# include +# include #endif // If you want to use the same software-only lock on both @@ -37,10 +41,13 @@ static unsigned int usleep_granularity; //!< the estimated cost in microseconds of usleep call itself -- value passed to usleep will be 10 times this (only used by software lock implementation on non-Aperios) //This section is only needed for the non-software-only locks, using the SemaphoreManager -#ifndef PLATFORM_APERIOS +#if !defined(PLATFORM_APERIOS) && TEKKOTSU_SHM_STYLE!=NO_SHM + //! exception if a lock is created but there aren't any more semaphores available class no_more_semaphores : public std::exception { public: + //! constructor no_more_semaphores() throw() : std::exception() {} + //! returns a constant message string virtual const char* what() const throw() { return "SemaphoreManager::getSemaphore() returned invalid()"; } }; @@ -55,9 +62,11 @@ semgr=mgr; } } + //! returns #semgr; static SemaphoreManager* getSemaphoreManager() { return semgr; } + //! this should be called if a fork() is about to occur (need to pass notification on to #preallocated) static void aboutToFork() { preallocated.aboutToFork(); } @@ -80,15 +89,101 @@ * manager is created.*/ static SemaphoreManager preallocated; - //! need to have a thread lock available for each semaphore -- have to acquire the corresponding inter-thread lock before you can acquire the inter-process lock - static ThreadNS::Lock thdLocks[SemaphoreManager::MAX_SEM]; +#elif TEKKOTSU_SHM_STYLE==NO_SHM +public: + static void aboutToFork() {} #endif }; #if !defined(PLATFORM_APERIOS) && !defined(MUTEX_LOCK_ET_USE_SOFTWARE_ONLY) -#include "SemaphoreManager.h" +#if TEKKOTSU_SHM_STYLE==NO_SHM + +//! Implements a mutual exclusion lock using pthread mutex +/*! Use this to prevent more than one thread from accessing a data structure +* at the same time (which often leads to unpredictable and unexpected results) +* +* The template parameter is not used (only needed if compiling with IPC enabled) +* +* Locks in this class can be recursive or non-recursive, depending +* whether you call releaseAll() or unlock(). If you lock 5 times, then +* you need to call unlock() 5 times as well before it will be +* unlocked. However, if you lock 5 times, just one call to releaseAll() +* will undo all 5 levels of locking. +* +* Just remember, unlock() releases one level. But releaseAll() completely unlocks. +* +* Note that there is no check that the thread doing the unlocking is the one +* that actually has the lock. Be careful about this. +*/ +template +class MutexLock : public MutexLockBase { +public: + //! constructor, gets a new semaphore from the semaphore manager + MutexLock() : owner_index(NO_OWNER), thdLock() {} + + //! destructor, releases semaphore back to semaphore manager + ~MutexLock() { + if(owner_index!=NO_OWNER) { + owner_index=NO_OWNER; + while(thdLock.getLockLevel()>0) + thdLock.unlock(); + } + } + + //! blocks until lock is achieved. This is done efficiently using a SysV style semaphore + /*! You should pass some process-specific ID number as the input - just + * make sure no other process will be using the same value. */ + void lock(int id) { + thdLock.lock(); + if(owner_index!=static_cast(id)) + owner_index=id; + } + + //! attempts to get a lock, returns true if it succeeds + /*! You should pass some process-specific ID number as the input - just + * make sure no other process will be using the same value.*/ + bool try_lock(int id) { + if(!thdLock.trylock()) + return false; + owner_index=id; + return true; + } + + //! releases one recursive lock-level from whoever has the current lock + inline void unlock() { + if(thdLock.getLockLevel()<=0) + std::cerr << "Warning: MutexLock::unlock caused underflow" << std::endl; + if(thdLock.getLockLevel()<=1) + owner_index=NO_OWNER; + thdLock.unlock(); + } + + //! completely unlocks, regardless of how many times a recursive lock has been obtained + void releaseAll() { + owner_index=NO_OWNER; + while(thdLock.getLockLevel()>0) + thdLock.unlock(); + } + + //! returns the lockcount + unsigned int get_lock_level() const { return thdLock.getLockLevel(); } + + //! returns the current owner's id + inline int owner() const { return owner_index; } + +protected: + friend class MarkScope; + virtual void useResource(Resource::Data&) { lock(ProcessID::getID()); } + virtual void releaseResource(Resource::Data&) { unlock(); } + + unsigned int owner_index; //!< holds the tekkotsu process id of the current lock owner + ThreadNS::Lock thdLock; //!< all the actual implementation is handed off to the thread lock +}; + +#else /* IPC Lock using Semaphores*/ +# include "SemaphoreManager.h" //! Implements a mutual exclusion lock using semaphores (SYSV style through SemaphoreManager) /*! Use this to prevent more than one process from accessing a data structure @@ -119,8 +214,8 @@ class MutexLock : public MutexLockBase { public: //! constructor, gets a new semaphore from the semaphore manager - MutexLock() - : sem(semgr->getSemaphore()), owner_index(NO_OWNER) + MutexLock() : MutexLockBase(), + sem(semgr->getSemaphore()), owner_index(NO_OWNER), owner_thread() { if(sem==semgr->invalid()) throw no_more_semaphores(); @@ -128,8 +223,8 @@ } //! constructor, use this if you already have a semaphore id you want to use from semaphore manager - MutexLock(SemaphoreManager::semid_t semid) - : sem(semid), owner_index(NO_OWNER) + MutexLock(SemaphoreManager::semid_t semid) : MutexLockBase(), + sem(semid), owner_index(NO_OWNER), owner_thread() { if(sem==semgr->invalid()) throw no_more_semaphores(); @@ -138,29 +233,25 @@ //! destructor, releases semaphore back to semaphore manager ~MutexLock() { + owner_index=NO_OWNER; if(semgr!=NULL && !semgr->hadFault()) semgr->releaseSemaphore(sem); else std::cerr << "Warning: MutexLock leaked semaphore " << sem << " because SemaphoreManager is NULL" << std::endl; - if(owner_index!=NO_OWNER) { - owner_index=NO_OWNER; - while(thdLocks[sem].getLockLevel()>0) - thdLocks[sem].unlock(); - } } //! blocks until lock is achieved. This is done efficiently using a SysV style semaphore /*! You should pass some process-specific ID number as the input - just * make sure no other process will be using the same value. */ void lock(int id) { - thdLocks[sem].lock(); - if(owner_index!=static_cast(id)) { + if(owner_index!=static_cast(id) || !isOwnerThread()) { //have to wait and then claim lock if(semgr!=NULL && !semgr->hadFault()) { semgr->testZero_add(sem,1); } else std::cerr << "Warning: MutexLock assuming lock of " << sem << " because SemaphoreManager is NULL" << std::endl; owner_index=id; + owner_thread=pthread_self(); } else { //we already have lock, add one to its lock level if(semgr!=NULL && !semgr->hadFault()) @@ -174,23 +265,21 @@ /*! You should pass some process-specific ID number as the input - just * make sure no other process will be using the same value.*/ bool try_lock(int id) { - if(!thdLocks[sem].trylock()) - return false; if(semgr==NULL || semgr->hadFault()) { std::cerr << "Warning: MutexLock assuming try_lock success of " << sem << " because SemaphoreManager is NULL" << std::endl; owner_index=id; return true; } - if(owner()==id) { + if(owner()==id && isOwnerThread()) { //we already have lock, add one to its lock level semgr->raise(sem,1); return true; } else { if(semgr->testZero_add(sem,1,false)) { owner_index=id; + owner_thread=pthread_self(); return true; } else { - thdLocks[sem].unlock(); return false; } } @@ -201,20 +290,17 @@ if(semgr==NULL || semgr->hadFault()) { std::cerr << "Warning: MutexLock assuming unlock of " << sem << " from " << owner_index << " because SemaphoreManager is NULL" << std::endl; owner_index=NO_OWNER; - thdLocks[sem].unlock(); return; } if(semgr->getValue(sem)<=0) { std::cerr << "Warning: MutexLock::unlock caused underflow" << std::endl; owner_index=NO_OWNER; - thdLocks[sem].unlock(); return; } if(semgr->getValue(sem)==1) owner_index=NO_OWNER; if(!semgr->lower(sem,1,false)) std::cerr << "Warning: MutexLock::unlock caused strange underflow" << std::endl; - thdLocks[sem].unlock(); } //! completely unlocks, regardless of how many times a recursive lock has been obtained @@ -225,8 +311,6 @@ return; } semgr->setValue(sem,0); - while(thdLocks[sem].getLockLevel()>0) - thdLocks[sem].unlock(); } //! returns the lockcount @@ -241,6 +325,11 @@ inline int owner() const { return owner_index; } protected: + //! returns true if the current thread is the one which owns the lock + bool isOwnerThread() { + pthread_t cur=pthread_self(); + return pthread_equal(cur,owner_thread); + } friend class MarkScope; virtual void useResource(Resource::Data&) { lock(ProcessID::getID()); @@ -251,11 +340,17 @@ SemaphoreManager::semid_t sem; //!< the SysV semaphore number unsigned int owner_index; //!< holds the tekkotsu process id of the current lock owner + pthread_t owner_thread; //!< holds a thread id for the owner thread + +private: + MutexLock(const MutexLock& ml); //!< copy constructor, do not call + MutexLock& operator=(const MutexLock& ml); //!< assignment, do not call }; +#endif /* uni-process or (potentially) multi-process lock? */ #else //SOFTWARE ONLY mutual exclusion, used on Aperios, or if MUTEX_LOCK_ET_USE_SOFTWARE_ONLY is defined diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/PollThread.cc ./IPC/PollThread.cc --- ../Tekkotsu_3.0/IPC/PollThread.cc 2006-08-07 17:55:27.000000000 -0400 +++ ./IPC/PollThread.cc 2007-10-12 12:55:04.000000000 -0400 @@ -7,24 +7,11 @@ using namespace std; void PollThread::start() { - launching=initialPoll=true; + initialPoll=true; startTime.Set(); Thread::start(); } -void PollThread::stop() { - Thread::stop(); - interrupt(); // break thread out of any long sleep commands -} - -void PollThread::interrupt() { - if(launching) //can't interrupt before thread has been launched! - return; - if(signal(SIGALRM,handleInterrupt)==SIG_ERR) - perror("PollThread::run(): initial signal()"); - sendSignal(SIGALRM); -} - bool PollThread::poll() { unsigned int sleeptime=runloop(); if(sleeptime==-1U) @@ -47,7 +34,6 @@ } void * PollThread::run() { - launching=false; timespec sleepSpec,remainSpec; if(startTime.Age()(Thread::getCurrent()); - if(cur==NULL) { - std::cerr << "PollThread::handleInterrupt called from non-PollThread" << endl; - return; - } - if(cur->noCancelDepth==0) - cur->testCancel(); - cur->interrupted(); -} - /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/PollThread.h ./IPC/PollThread.h --- ../Tekkotsu_3.0/IPC/PollThread.h 2006-09-16 13:32:39.000000000 -0400 +++ ./IPC/PollThread.h 2007-10-12 12:55:04.000000000 -0400 @@ -13,27 +13,23 @@ class PollThread : public Thread { public: //! constructor - PollThread() : Thread(), delay(0L), period(0L), startTime(0L), trackPollTime(false), launching(false), initialPoll(false) {} + PollThread() : Thread(), delay(0L), period(0L), startTime(0L), trackPollTime(false), initialPoll(false) {} //! constructor explicit PollThread(const TimeET& initial, const TimeET& freq, bool countPollTime, bool autostart=true) - : Thread(), delay(initial), period(freq), startTime(0L), trackPollTime(countPollTime), launching(false), initialPoll(true) + : Thread(), delay(initial), period(freq), startTime(0L), trackPollTime(countPollTime), initialPoll(true) { if(autostart) start(); } //! destructor ~PollThread() { - if(isRunning()) { + if(isStarted()) { stop(); join(); } } virtual void start(); - virtual void stop(); - - //! sends a signal to the thread which will interrupt any sleep calls (and trigger interrupted() to be called within the thread) - virtual void interrupt(); virtual bool getTrackPollTime() { return trackPollTime; } //!< returns #trackPollTime virtual void setTrackPollTime(bool countPollTime) { trackPollTime=countPollTime; } //!< sets #trackPollTime @@ -66,7 +62,6 @@ TimeET period; //!< amount of time between calls to poll() -- if zero or negative, no delay will be made between calls (other than a call to testCancel()) TimeET startTime; //!< the time at which start() was called or the current period began bool trackPollTime; //!< if true, the time spent in poll() is subtracted from the next sleep time so frequency is fixed; if false, #period is added onto whatever time poll() takes - bool launching; //!< set to true after start until run() is called (can't interrupt before thread has launched) bool initialPoll; //!< set to true after start until after first call to poll has completed }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/ProcessID.cc ./IPC/ProcessID.cc --- ../Tekkotsu_3.0/IPC/ProcessID.cc 2006-09-16 02:01:40.000000000 -0400 +++ ./IPC/ProcessID.cc 2007-03-15 00:14:21.000000000 -0400 @@ -13,8 +13,21 @@ ProcessID_t ID=NumProcesses; //!< holds ID number #ifndef PLATFORM_APERIOS + ProcessID_t getUnhookedID() { return ID; } + void setUnhookedID(ProcessID_t id) { ID=id; } + + ProcessID_t (*getIDHook)()=&getUnhookedID; //!< hook allows overriding the ID system, set with ProcessID::setIDHooks + void (*setIDHook)(ProcessID_t id)=&setUnhookedID; //!< hook allows overriding the ID system, set with ProcessID::setIDHooks + // on "normal" platforms we can trust the id specified by the process to stay consistent - ProcessID_t getID() { return ID; } + ProcessID_t getID() { return (*getIDHook)(); } + + void setID(ProcessID_t id) { (*setIDHook)(id); } + + void setIDHooks(ProcessID_t (*customGetID)(), void (*customSetID)(ProcessID_t id)) { + getIDHook = (customGetID==NULL) ? &getUnhookedID : customGetID; + setIDHook = (customSetID==NULL) ? &setUnhookedID : customSetID; + } #else // but on the Aibo, we have to unroll the stack to see which thread it is @@ -66,10 +79,10 @@ cerr << " " << i << " (sp=" << frames[i].sp << ",ra=" << (void*)frames[i].ra << ",gp=" << (void*)frames[i].gp << ")" << endl; return ID; } + + void setID(ProcessID_t id) { ID=id; } #endif - - void setID(ProcessID_t id) { ID=id; } } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/ProcessID.h ./IPC/ProcessID.h --- ../Tekkotsu_3.0/IPC/ProcessID.h 2006-08-22 18:23:03.000000000 -0400 +++ ./IPC/ProcessID.h 2007-11-09 14:01:18.000000000 -0500 @@ -30,9 +30,20 @@ NumProcesses //!< maximum number of 'friendly' processes -- see class docs }; - ProcessID_t getID(); //!< returns process's ID number - void setID(ProcessID_t id); //!< sets the ID during init (be careful you know what you're doing if you call this) + ProcessID_t getID(); //!< returns process's ID number, subject to overriding via setIDHooks() + void setID(ProcessID_t id); //!< sets the ID during init (be careful you know what you're doing if you call this), subject to overriding via setIDHooks() + +#ifndef PLATFORM_APERIOS + //! allows you to override the behavior of getID and setID -- pass NULL to use default behavior + void setIDHooks(ProcessID_t (*customGetID)(), void (*customSetID)(ProcessID_t id)); + //! returns process's ID number from static global, the default behavior if setIDHooks was passed NULL + ProcessID_t getUnhookedID(); + + //! sets the ID into static global (be careful you know what you're doing if you call this), this is the default behavior if setIDHooks was passed NULL + void setUnhookedID(ProcessID_t id); +#endif + //! returns a string version of the name of the process inline const char* getIDStr() { switch(getID()) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/RCRegion.cc ./IPC/RCRegion.cc --- ../Tekkotsu_3.0/IPC/RCRegion.cc 2006-08-15 17:45:36.000000000 -0400 +++ ./IPC/RCRegion.cc 2007-06-28 00:34:36.000000000 -0400 @@ -8,7 +8,7 @@ #include #include -#if TEKKOTSU_SHM_STYLE!=SYSV_SHM && TEKKOTSU_SHM_STYLE!=POSIX_SHM +#if TEKKOTSU_SHM_STYLE!=SYSV_SHM && TEKKOTSU_SHM_STYLE!=POSIX_SHM && TEKKOTSU_SHM_STYLE!=NO_SHM # error Unknown TEKKOTSU_SHM_STYLE setting #endif @@ -29,16 +29,15 @@ using namespace std; -typedef MarkScope AutoLock; - #if TEKKOTSU_SHM_STYLE==SYSV_SHM key_t RCRegion::nextKey=1024; -#elif TEKKOTSU_SHM_STYLE==POSIX_SHM +#elif TEKKOTSU_SHM_STYLE==POSIX_SHM || TEKKOTSU_SHM_STYLE==NO_SHM key_t RCRegion::nextKey=0; #endif RCRegion::attachedRegions_t RCRegion::attachedRegions; bool RCRegion::isFaultShutdown=false; +bool RCRegion::multiprocess=true; ThreadNS::Lock* RCRegion::staticLock=NULL; @@ -55,6 +54,11 @@ //mitigate this) RCRegion::ConflictResolutionStrategy RCRegion::conflictStrategy=RCRegion::REPLACE; +#elif TEKKOTSU_SHM_STYLE==NO_SHM +//with shared memory disabled, a conflict indicates we're reusing the same name... this is probably +//a bug, so we should fail-fast +RCRegion::ConflictResolutionStrategy RCRegion::conflictStrategy=RCRegion::EXIT; + #endif RCRegion * RCRegion::attach(const Identifier& rid) { @@ -70,7 +74,7 @@ } void RCRegion::AddReference() { - AutoLock autolock(*lock); + MarkScope l(getStaticLock()); //cout << "AddReference " << id.shmid << ' ' << ProcessID::getID(); references[ProcessID::getID()]++; references[ProcessID::NumProcesses]++; @@ -82,78 +86,80 @@ void RCRegion::RemoveReference() { //cout << "RemoveReference " << id.key << ' ' << ProcessID::getID(); - //if(MutexLockBase::getSemaphoreManager()!=NULL) //check in case this region contained the mutexman and SharedObject just destructed it - lock->lock(ProcessID::getID()); - if(references[ProcessID::getID()] == 0) { - cerr << "Warning: RCRegion reference count underflow on " << id.key << " by " << ProcessID::getID() << "! "; - for(unsigned int i=0; iunlock(); - } else { + { MarkScope l(getStaticLock()); - //cout << " detach"; - if(wasLastAnyRef) - lock->~MutexLock(); - else - lock->unlock(); - lock=NULL; -#if TEKKOTSU_SHM_STYLE==SYSV_SHM - if(shmdt(base)<0) - perror("Warning: Region detach"); - base=NULL; - references=NULL; - if(wasLastAnyRef) { - //cout << " delete" << endl; - if(shmctl(id.shmid,IPC_RMID,NULL)<0) - perror("Warning: Region delete"); + if(references[ProcessID::getID()] == 0) { + cerr << "Warning: RCRegion reference count underflow on " << id.key << " by " << ProcessID::getID() << "! "; + for(unsigned int i=0; i*>(base+sz-sizeof(MutexLock)); references=reinterpret_cast(base+sz-extra); if(create) { - new (lock) MutexLock; - AutoLock autolock(*lock,ProcessID::getID()); for(unsigned int i=0; i*>(base+sz-sizeof(MutexLock)); references=reinterpret_cast(base+sz-extra); if(create) { - new (lock) MutexLock; - AutoLock autolock(*lock); for(unsigned int i=0; i=MAX_NAME_LEN) + cerr << "*** WARNING RCRegion named " << name << " will be clipped to " << name.substr(0,MAX_NAME_LEN-1) << endl; + strncpy(id.key,name.c_str(),MAX_NAME_LEN-1); + id.key[MAX_NAME_LEN-1]='\0'; + if(create) { + static unsigned int renameSN=0; + switch(conflictStrategy) { + case RENAME: { + if(attachedRegions.find(id.key)==attachedRegions.end()) + break; + char origName[MAX_NAME_LEN]; + strncpy(origName,id.key,MAX_NAME_LEN); + do { + int err=errno; + if(err!=EEXIST) { + cerr << "ERROR: Opening new region " << id.key << ": " << strerror(err) << " (shm_open)" << endl; + exit(EXIT_FAILURE); + } + unsigned int p=snprintf(id.key,MAX_NAME_LEN,"%s-%d",origName,++renameSN); + if(p>=MAX_NAME_LEN) { + cerr << "ERROR: conflicted key " << origName << ", attempting to rename, but generated name is too long" << endl; + exit(EXIT_FAILURE); + } + //id.key[MAX_NAME_LEN-1]='\0'; +#ifdef DEBUG + cerr << "Warning: conflicted key " << origName << ", attempting to rename as " << id.key << "\n" + << " (may have been leftover from a previous crash)" << endl; +#endif + } while(attachedRegions.find(id.key)!=attachedRegions.end()); + break; + } + case REPLACE: { + if(attachedRegions.find(id.key)==attachedRegions.end()) + break; +#ifdef DEBUG + cerr << "Warning: conflicted key " << id.key << ", attempting to replace" << endl; +#endif + } + //note fall-through from REPLACE into EXIT - only try delete once, and then recreate and exit if it fails again + case EXIT: { + if(attachedRegions.find(id.key)!=attachedRegions.end()) { + cerr << "ERROR: Opening new region " << id.key << ": conflicted with existing region." << endl; + exit(EXIT_FAILURE); + } + } + } + base=new char[sz]; + } else { + attachedRegions_t::const_iterator it=attachedRegions.find(id.key); + ASSERT(it==attachedRegions.end(),"attachment not found with disabled shared mem (TEKKOTSU_SHM_STYLE==NO_SHM)"); + if(it==attachedRegions.end()) { + base=new char[sz]; + } else { + base=it->second->base; + } + } + references=reinterpret_cast(base+sz-extra); + if(create) { + for(unsigned int i=0; i #include #include -//do you want to use the SysV shared memory call interface -//or the POSIX shared memory interface? They have different -//strengths/weaknesses on different platforms... :-/ +/* Do you want to use the SysV shared memory call interface + * or the POSIX shared memory interface? They have different + * strengths/weaknesses on different platforms... :-/ */ + +/*! @def POSIX_SHM + * @brief If TEKKOTSU_SHM_STYLE is set to POSIX_SHM, POSIX style shared memory will be used (shm_open, shm_unlink, mmap, munmap, ...); + * This is the default shared memory interface, both portable and stable. By default, regular open() and unlink() + * will be used to implement the regions using file-backed shared memory. If you define USE_UNBACKED_SHM, + * RCRegion will use shm_open/shm_unlink instead. Unbacked shared memory is nice because there's no + * interaction with your filesystem, but isn't quite as portable. (Cygwin didn't seem to like it too much...) */ + +/*! @def SYSV_SHM + * @brief If TEKKOTSU_SHM_STYLE is set to SYSV_SHM, SysV style shared memory will be used (shmget, shmctl, shmat, shmdt, ...) + * SysV style seems to stick around following a program crash, and can't be unlinked pre-emptively while still in use. + * Since it appears many systems also limit the number of shared memory regions (via a sysctl configuration), leaking + * regions following repeated crashes during development gets annoying. */ + +/*! @def NO_SHM + * @brief If TEKKOTSU_SHM_STYLE is set to NO_SHM, all shared memory operations become straight new/delete's; this restricts the program to using threads in a single process */ + +/*! @def TEKKOTSU_SHM_STYLE + * @brief Can be set to one of POSIX_SHM, SYSV_SHM, or NO_SHM */ + #ifndef POSIX_SHM # define POSIX_SHM 1 #endif #ifndef SYSV_SHM # define SYSV_SHM 2 #endif +#ifndef NO_SHM +# define NO_SHM 3 +#endif #ifndef TEKKOTSU_SHM_STYLE # define TEKKOTSU_SHM_STYLE POSIX_SHM #endif -#if TEKKOTSU_SHM_STYLE!=SYSV_SHM && TEKKOTSU_SHM_STYLE!=POSIX_SHM +#if TEKKOTSU_SHM_STYLE!=SYSV_SHM && TEKKOTSU_SHM_STYLE!=POSIX_SHM && TEKKOTSU_SHM_STYLE!=NO_SHM # error Unknown TEKKOTSU_SHM_STYLE setting #endif @@ -49,22 +71,24 @@ size_t size; //!< the size of the region }; -#elif TEKKOTSU_SHM_STYLE==POSIX_SHM +#elif TEKKOTSU_SHM_STYLE==POSIX_SHM || TEKKOTSU_SHM_STYLE==NO_SHM //! maximum guaranteed length for users' region names (might have a little leeway depending on process ID prefix or tmp path prefix) static const unsigned int MAX_NAME_LEN=64; //! contains all information needed to attach this region from a different process struct Identifier { - Identifier() : size(0) {} + Identifier() : size(0) {} //!< constructor char key[MAX_NAME_LEN]; //!< a string name for the key size_t size; //!< size of the region }; -# ifndef USE_UNBACKED_SHM +# if TEKKOTSU_SHM_STYLE==POSIX_SHM +# ifndef USE_UNBACKED_SHM static plist::Primitive shmRoot; //!< determines location of the file backing within file system -# endif +# endif static plist::Primitive useUniqueMemoryRegions; //!< if true, prefixes region names with #rootPID static pid_t rootPID; //!< this is the pid of the original process, used for unique names of memory regions; pid_t is from sys/types.h +# endif #endif @@ -75,18 +99,18 @@ #if TEKKOTSU_SHM_STYLE==SYSV_SHM //! constructor (OPEN-R compatability) explicit RCRegion(size_t sz) - : id(), base(NULL), references(NULL), lock(NULL) + : id(), base(NULL), references(NULL) { init(sz,nextKey,true); } //! constructor, name isn't used for sysv-style shared memory (not OPEN-R compatable) /*! could hash the name to generate key...? */ RCRegion(const std::string&, size_t sz) - : id(), base(NULL), references(NULL), lock(NULL) + : id(), base(NULL), references(NULL) { init(sz,nextKey,true); } -#elif TEKKOTSU_SHM_STYLE==POSIX_SHM +#elif TEKKOTSU_SHM_STYLE==POSIX_SHM || TEKKOTSU_SHM_STYLE==NO_SHM //! constructor (OPEN-R compatability, name is autogenerated) explicit RCRegion(size_t sz) - : id(), base(NULL), references(NULL), lock(NULL) + : id(), base(NULL), references(NULL) { char name[RCRegion::MAX_NAME_LEN]; snprintf(name,RCRegion::MAX_NAME_LEN,"Rgn.%d.%u",ProcessID::getID(),static_cast(++nextKey)); @@ -95,7 +119,7 @@ } //! constructor, specify your own name for better debugging accountability (not OPEN-R compatable) RCRegion(const std::string& name, size_t sz) - : id(), base(NULL), references(NULL), lock(NULL) + : id(), base(NULL), references(NULL) { init(sz,name,true); } #endif @@ -109,7 +133,7 @@ const Identifier& ID() const { return id; } //!< returns the identifier of this region int NumberOfReference() const { return references[ProcessID::NumProcesses]; } //!< number of total references to this region, total of all processes - int NumberOfLocalReference() const { return references[ProcessID::getID()]; } //!< number of references to the region from the current process + int NumberOfLocalReference() const { return references[ProcessID::getID()]; } //!< number of references to the region from the current process (in the ProcessID threadgroup sense, not necessarily system-process) void AddReference(); //!< adds a reference from the current process void RemoveReference(); //!< removes a reference from the current process void AddSharedReference(); //!< adds a reference which is held by another shared memory region @@ -121,7 +145,7 @@ #if TEKKOTSU_SHM_STYLE==SYSV_SHM //! a map from the shared memory key type to the actual region structure typedef std::map attachedRegions_t; -#elif TEKKOTSU_SHM_STYLE==POSIX_SHM +#elif TEKKOTSU_SHM_STYLE==POSIX_SHM || TEKKOTSU_SHM_STYLE==NO_SHM //! a map from the shared memory key type to the actual region structure typedef std::map attachedRegions_t; #endif @@ -142,9 +166,6 @@ * When you're done, either advance off the end, or manually call RemoveReference() on the iterator's final region */ static void attachedAdvance(attachedRegions_t::const_iterator& it, int x=1); - //! returns the region's MutexLock - MutexLock& getLock() const { return *lock; } - //! Different methods of handling regions with conflicting keys enum ConflictResolutionStrategy { RENAME, //!< try another key until we find one that works (better for SYSV, maybe not so smart for POSIX) @@ -154,21 +175,23 @@ static void setConflictResolution(ConflictResolutionStrategy crs) { conflictStrategy=crs; } //!< sets #conflictStrategy static ConflictResolutionStrategy getConflictResolution() { return conflictStrategy; } //!< returns #conflictStrategy + + static void setMultiprocess(bool mp) { multiprocess=mp; } //!< sets #multiprocess + static bool getMultiprocess() { return multiprocess; } //!< returns #multiprocess protected: //! this protected constructor is used for attaching regions previously created by another process (see attach()) RCRegion(const Identifier& rid) - : id(), base(NULL), references(NULL), lock(NULL) + : id(), base(NULL), references(NULL) { init(rid.size,rid.key,false); } ~RCRegion(); //!< prevents stack allocation -- needs to be heap allocated and reference counted //! the alignment multiple of the extra space at the end of the region static const unsigned int align=sizeof(unsigned int); - //! the amount of space to leave at the end of the region for housekeeping (reference count and mutex lock) - static const unsigned int extra=sizeof(unsigned int)*(ProcessID::NumProcesses+1) - +sizeof(MutexLock); + //! the amount of space to leave at the end of the region for housekeeping (reference counts) + static const unsigned int extra=sizeof(unsigned int)*(ProcessID::NumProcesses+1); //! returns the size of the region to be allocated, given the size requested by the client static unsigned int calcRealSize(unsigned int size); @@ -189,14 +212,19 @@ bool unlinkRegion() const; //! initializes the region's information, either creating a new shared memory region or attempting to connect to a pre-existing one void init(size_t sz, const std::string& name, bool create); +#elif TEKKOTSU_SHM_STYLE==NO_SHM + //! initializes the region's information, either pointing to an existing region or allocating a new one + void init(size_t sz, const std::string& name, bool create); #endif //! controls what to do about creating a region with a conflicting key (i.e. another region already exists with the same key) static ConflictResolutionStrategy conflictStrategy; //! set to true if we are shutting down because of an error, and trying to unload shared regions to avoid leaking beyond program scope static bool isFaultShutdown; + //! set to false if the different "processes" are just threads (and thus the last process reference shouldn't actually trigger unlinking a region + static bool multiprocess; - static ThreadNS::Lock* staticLock; //!< a lock over all static RCRegion members for the current process + static ThreadNS::Lock* staticLock; //!< a lock over all static RCRegion members for the current process, must be obtained before changing reference counts or attaching/detaching regions static key_t nextKey; //!< serial number of next key -- starts at 1024 for TEKKOTSU_SHM_STYLE==SYSV_SHM, 0 for POSIX_SHM static attachedRegions_t attachedRegions; //!< a mapping of key values to RCRegion pointers of the attached region @@ -204,7 +232,6 @@ Identifier id; //!< key values for the region, namely the system key type (either an integer or string depending on TEKKOTSU_SHM_STYLE) and the size of the region char * base; //!< pointer to the region's user data unsigned int * references; //!< pointer to the per-process reference counts (stored within the shared region!) - MutexLock * lock; //!< region's inter-process lock (stored within the shared region!) private: RCRegion(const RCRegion& r); //!< don't call diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/RegionRegistry.h ./IPC/RegionRegistry.h --- ../Tekkotsu_3.0/IPC/RegionRegistry.h 2006-06-16 17:49:23.000000000 -0400 +++ ./IPC/RegionRegistry.h 2007-11-14 21:44:06.000000000 -0500 @@ -12,40 +12,44 @@ #include "ProcessID.h" //! Keeps track of currently available shared memory regions -template +template class RegionRegistry { protected: + //! makes sure we only have one registration in progress at a time mutable MutexLock lock; - typedef MarkScope AutoLock; //! Holds information regarding a shared memory region available for listening struct entry { - //! constructor + //! constructor, provides an empty name entry() : id() { name[0]='\0'; } + //! constructor, pass name and pointer to region entry(const char n[], RCRegion* r) : id(r->ID()) { strncpy(name,n,NAME_LEN); name[NAME_LEN]='\0'; } char name[NAME_LEN+1]; //!< the name for the region - RCRegion::Identifier id; + RCRegion::Identifier id; //!< stores information needed to identify the region to the system }; - typedef ListMemBuf registry_t; - registry_t avail; + typedef ListMemBuf registry_t; //!< type of the collection managing the regions + registry_t avail; //!< collection of available memory regions public: - static const unsigned int CAPACITY=MAX_REGIONS; - static const unsigned int REGION_NAME_LEN=NAME_LEN; - typedef typename registry_t::index_t index_t; + static const unsigned int CAPACITY=MAX_REGIONS; //!< allows access to template parameters + static const unsigned int REGION_NAME_LEN=NAME_LEN; //!< allows access to template parameters + typedef typename registry_t::index_t index_t; //!< shorthand for the index type used to reference regions + //! constructor RegionRegistry() : lock(), avail() {} + //! destructor ~RegionRegistry() { - AutoLock autolock(lock); + MarkScope autolock(lock); avail.clear(); } + //! Searches for the region specified by @a name, returns end() if not found index_t findRegion(const std::string& name) const { - AutoLock autolock(lock); + MarkScope autolock(lock); if(name.size()>NAME_LEN) std::cerr << "WARNING: RegionRegistry::attach("< #include #include +#include +#include -//this is for linux compatability -- apparently you're *supposed* to -//define this yourself? (WTF?) -#if defined(_SEM_SEMUN_UNDEFINED) || defined(__CYGWIN__) -union semun -{ - int val; - struct semid_ds *buf; - unsigned short int *array; - struct seminfo *__buf; +#if defined(__GNU_LIBRARY__) && !defined(_SEM_SEMUN_UNDEFINED) || defined(__FreeBSD__) || defined(__NetBSD__) || defined(__MACH__) +/* union semun is defined by including */ +#else +/*! @cond INTERNAL */ +/* according to X/OPEN we have to define it ourselves */ +union semun { + int val; /* value for SETVAL */ + struct semid_ds *buf; /* buffer for IPC_STAT, IPC_SET */ + unsigned short *array; /* array for GETALL, SETALL */ + /* Linux specific part: */ + struct seminfo *__buf; /* buffer for IPC_INFO */ }; +/*! @endcond */ #endif using namespace std; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/SemaphoreManager.h ./IPC/SemaphoreManager.h --- ../Tekkotsu_3.0/IPC/SemaphoreManager.h 2006-05-08 18:06:35.000000000 -0400 +++ ./IPC/SemaphoreManager.h 2007-03-17 13:06:25.000000000 -0400 @@ -8,8 +8,6 @@ #include "ListMemBuf.h" #include "Shared/attributes.h" -#include -#include #ifndef SYSTEM_MAX_SEM //! Ideally, this would be SEMMSL, but that is hard to portably determine at compile time diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/SharedObject.h ./IPC/SharedObject.h --- ../Tekkotsu_3.0/IPC/SharedObject.h 2006-09-16 16:11:52.000000000 -0400 +++ ./IPC/SharedObject.h 2007-11-10 17:58:08.000000000 -0500 @@ -41,7 +41,7 @@ RCRegion * rcr; //!< the pointer to the shared memory region this is in charge of #ifndef PLATFORM_APERIOS - static unsigned int serialNumber; + static unsigned int serialNumber; //!< incremented for each region created so they will all have unique IDs #endif }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/Thread.cc ./IPC/Thread.cc --- ../Tekkotsu_3.0/IPC/Thread.cc 2006-08-15 17:45:57.000000000 -0400 +++ ./IPC/Thread.cc 2007-11-11 00:58:13.000000000 -0500 @@ -9,37 +9,45 @@ #include #include #include +#include +#ifdef __APPLE__ +# include +#endif using namespace std; #define THREADCANCEL_SANITY_CHECKS +/*! @cond INTERNAL */ +//! provides the system-dependent implementation of a thread struct Threadstorage_t { - Threadstorage_t() : threadInfo(), threadAttr() { - if(int err=pthread_attr_init(&threadAttr)) - cerr << "Threadstorage_t constructor, pthread_attr_init: " << strerror(err) << endl;; - } - ~Threadstorage_t() { - if(int err=pthread_attr_destroy(&threadAttr)) - cerr << "Threadstorage_t destructor, pthread_attr_destroy: " << strerror(err) << endl; - } + //! constructor + Threadstorage_t() : threadInfo() {} + + //! the main POSIX reference to the thread pthread_t threadInfo; - pthread_attr_t threadAttr; + + //! storage which will be set up as a thread-specific memory value, so threads can tell themselves apart static pthread_key_t selfKey; private: Threadstorage_t(const Threadstorage_t& r); //!< don't call Threadstorage_t& operator=(const Threadstorage_t& r); //!< don't call }; pthread_key_t Threadstorage_t::selfKey=0; +/*! @endcond */ Thread::Thread() - : pt(new Threadstorage_t), running(false), returnValue(NULL), - noCancelDepth(0), cancelOrig(PTHREAD_CANCEL_ENABLE) -{} + : pt(new Threadstorage_t), started(false), running(false), returnValue(NULL), + noCancelDepth(0), cancelOrig(PTHREAD_CANCEL_ENABLE), group(NULL) +{ + Thread* cur=getCurrent(); + if(cur!=NULL) + group=cur->getGroup(); +} Thread::~Thread() { //can only happen externally - if(running) { + if(started) { stop(); join(); } @@ -53,13 +61,13 @@ } void Thread::start() { - if(running) { - std::cerr << "Thread::start() -- thread is already running!" << std::endl; + if(started) { + std::cerr << "Thread::start() -- thread is already started!" << std::endl; std::cerr << " make another instance if you want to run another copy of this thread" << std::endl; return; } - running=true; - if(int err=pthread_create(&pt->threadInfo, &pt->threadAttr, launch, this)) + started=true; + if(int err=pthread_create(&pt->threadInfo, NULL, launch, this)) cerr << "Thread start(), pthread_create: " << strerror(err) << endl; } @@ -76,13 +84,39 @@ return returnValue; //never happens -- cancel or max sleep time would exit } +void Thread::interrupt() { + if(!isRunning()) //can't interrupt before thread has been launched! + return; + if(signal(SIGALRM,handleInterrupt)==SIG_ERR) + perror("PollThread::run(): initial signal()"); + sendSignal(SIGALRM); +} + void Thread::stop() { - if(!running) { - std::cerr << "Thread::stop() -- thread is already stopped!" << std::endl; + if(!started && !running) { + std::cerr << "Thread::stop() -- thread has not been started!" << std::endl; return; } + if(started && !running) + usleep(50000); + if(started && !running) + std::cerr << "Thread::stop(): Waiting for thread launch to complete (stillborn thread?)" << std::endl; + while(started && !running) + usleep(100000); + if(!running) + return; if(int err=pthread_cancel(pt->threadInfo)) cerr << "Thread cancel(), pthread_cancel("<threadInfo<<"): " << strerror(err) << endl; +#if defined(__APPLE__) && MAC_OS_X_VERSION_MAX_ALLOWED < MAC_OS_X_VERSION_10_5 + /* Mac OS X Tiger and earlier (v10.4 and prior) don't handle pthread_cancel in system calls, + * (namely sleep, read, listen, etc.) so we need to send a signal to wake it up. + * Mac OS X Leopard seems to fix this, although the thread usually gets canceled before we + * get to signal it, causing a warning in sendSignal()... hence the Mac OS version check. + * This is generally fine to do on other platforms too, but seems to cause a problem on Fedora Core 5 + * where it causes the pthread_cleanup to skip Thread::handle_exit and cause mayhem. + * So we'll restrict the interrupt signal to only those platforms which won't break out of sleep on a cancel */ + interrupt(); // break thread out of any long sleep commands +#endif } void Thread::kill() { @@ -93,14 +127,20 @@ if(int err=pthread_detach(pt->threadInfo)) cerr << "Thread kill(), thread_detach: " << strerror(err) << endl; sendSignal(SIGSTOP); - running=false; + started=running=false; } void Thread::sendSignal(int sig) { + if(started && !running) + usleep(50000); + if(started && !running) + std::cerr << "Thread::stop(): Waiting for thread launch to complete (stillborn thread?)" << std::endl; + while(started && !running) + usleep(100000); if(!isRunning()) return; if(int err=pthread_kill(pt->threadInfo,sig)) - cerr << "Thread kill(), pthread_kill("<noCancelDepth); if(signal(SIGUSR1,Thread::handle_launch_signal)==SIG_ERR) perror("Thread launch(), signal(SIGUSR1,handle_launch_signal)"); + cur->running=true; if(!cur->launched()) { //subclass's launch cancelled launch --(cur->noCancelDepth); @@ -206,7 +247,7 @@ cerr << "ERROR: handle_exit called for a NULL thread" << endl; if(th!=NULL) { static_cast(th)->cancelled(); - static_cast(th)->running=false; + static_cast(th)->started=static_cast(th)->running=false; } return; } @@ -220,7 +261,7 @@ if(int err=pthread_setspecific(Threadstorage_t::selfKey,NULL)) cerr << "WARNING: In Thread::handle_exit(), pthread_setspecific(selfKey) returned " << err << endl; cur->cancelled(); - cur->running=false; + cur->started=cur->running=false; } void Thread::pushNoCancel() { @@ -267,49 +308,77 @@ cerr << "WARNING: In Thread::popNoCancel, cancel state was somehow re-enabled" << endl; #endif } + +void Thread::handleInterrupt(int /*signal*/) { + //if(signal(SIGALRM,SIG_DFL)==SIG_ERR) + // perror("PollThread::handleInterrupt(): could not re-enable signal"); + Thread * cur=Thread::getCurrent(); + if(cur==NULL) { + std::cerr << "Thread::handleInterrupt called from non-Thread" << endl; + return; + } + if(cur->noCancelDepth==0) + cur->testCancel(); + cur->interrupted(); +} + void Thread::warnSelfUndestructed(void* msg) { cerr << "ERROR: Thread local data (selfKey) not deleted by Thread::handle_exit" << endl; Thread* cur = getCurrent(); - if(cur==NULL) { - cerr << " And the thread is NULL" << endl; - } else if(cur->noCancelDepth==0) { - cerr << " But at least the depth is 0" << endl; - } else { - cerr << " The depth indicates there may be " << cur->noCancelDepth << " locks left in place" << endl; - } + if(cur!=NULL) + cerr << " Weird, key wasn't cleared... (" << cur << ") " << cur->noCancelDepth << " locks on stack? " << endl;; if(msg==NULL) { cerr << " Message is null, warnCancelDepthUndestructed shouldn't have been called." << endl; } else { + if(cur!=NULL && cur!=msg) + cerr << " and current thread does not match msg (" << cur << " vs " << msg << ")" << endl; + cur = static_cast(msg); + } + if(cur!=NULL) { + //try to recover + if(cur->noCancelDepth==0) { + cerr << " But at least the depth is 0" << endl; + } else { + cerr << " The depth indicates there may be " << cur->noCancelDepth << " locks left in place" << endl; + } + cur->cancelled(); + cur->started=cur->running=false; pthread_setspecific(Threadstorage_t::selfKey,NULL); } - assert(cur==msg); } namespace ThreadNS { - //!This private class handles the actual lock implementation, which allows Lock to provide an abstract interface + /*! @cond INTERNAL */ + //! This handles the actual lock implementation, which allows Lock to provide an abstract interface class Lock::LockStorage : public ReferenceCounter { + friend class Condition; public: + //! constructor LockStorage() : ReferenceCounter(), locklevel(0), mutex(), attr(), threadkey() { AddReference(); pthread_mutexattr_init(&attr); pthread_mutexattr_settype(&attr,PTHREAD_MUTEX_RECURSIVE); pthread_mutex_init(&mutex,&attr); } + //! destructor, releases any pending locks (with warning ~LockStorage() { pthread_mutexattr_destroy(&attr); pthread_mutex_destroy(&mutex); - if(locklevel>1) { //having one left is ok, perhaps even good (keeping the lock as it is destroyed) + if(locklevel>1) //having one left is ok, perhaps even good (keeping the lock as it is destroyed) cerr << "WARNING: lockstorage destructed with " << locklevel << " locks still in effect" << endl; - while(locklevel>0) { - locklevel--; - Thread::popNoCancel(); - } + while(locklevel>0) { + locklevel--; + Thread::popNoCancel(); } } + //! copy constructor (functional!) -- both locks will wind up referencing the same system resource, so this is more of an alias than a clone LockStorage(const LockStorage& ls) : ReferenceCounter(ls), locklevel(ls.locklevel), mutex(ls.mutex), attr(ls.attr), threadkey(ls.threadkey) {} + //! assignment (functional!) -- both locks will wind up referencing the same system resource, so this is more of an alias than a clone LockStorage& operator=(const LockStorage& ls) { ReferenceCounter::operator=(ls); locklevel=ls.locklevel; mutex=ls.mutex; attr=ls.attr; threadkey=ls.threadkey; return *this; } + + //! trigger and wait for a mutual exclusion lock, recursively void lock() { Thread::pushNoCancel(); if(int err=pthread_mutex_lock(&mutex)) { @@ -318,6 +387,7 @@ } else locklevel++; } + //! attempt to get a lock, but return false if it is not immediately available bool trylock() { Thread::pushNoCancel(); if(!pthread_mutex_trylock(&mutex)) { @@ -328,6 +398,7 @@ return false; } } + //! release a lock (recursively, won't actually release the lock resource until all calls to lock() have been balanced) void unlock() { if(locklevel==0) cerr << "ERROR: ThreadNS::Lock::unlock() underflow" << endl; @@ -336,16 +407,18 @@ cerr << "ERROR: ThreadNS::Lock::unlock() failed: " << strerror(err) << endl; Thread::popNoCancel(); } + //! returns the depth of the lock recursion (#locklevel) unsigned int getLockLevel() { return locklevel; } + protected: - - unsigned int locklevel; - pthread_mutex_t mutex; - pthread_mutexattr_t attr; + unsigned int locklevel; //!< depth of lock recursion (i.e. number of calls to lock() minus calls to unlock()) + pthread_mutex_t mutex; //!< system lock resource + pthread_mutexattr_t attr; //!< system lock resource attributes (used to specify #mutex is recursive in the system as well) pthread_key_t threadkey; //!< not making use of the thread specific nature of these, but we are making use of the call to a destructor (emergencyUnlock) on cancel }; Lock::LockStorage* Lock::glock=NULL; + /*! @endcond */ Lock::Lock() : mylock(new LockStorage), locklevel(0) { if(glock==NULL) @@ -414,7 +487,56 @@ if(glock==NULL) glock=new LockStorage; } - + + /*! @cond INTERNAL */ + //! Implement system-dependent portion of a thread condition, a signaling mechanism. + /*! This is a very basic wrapper -- just adds a constructor and destructor to the POSIX pthread_cond_t. */ + class Condition::ConditionStorage { + public: + //! constructor + ConditionStorage() : cond() { + if(int err=pthread_cond_init(&cond,NULL)) { + cerr << "ERROR: ThreadNS::Condition::ConditionStorage() failed: " << strerror(err) << endl; + } + } + //! destructor + ~ConditionStorage() { + if(int err=pthread_cond_destroy(&cond)) { + cerr << "ERROR: ThreadNS::Condition::~ConditionStorage() failed: " << strerror(err) << endl; + } + } + //! system resource storage + pthread_cond_t cond; + }; + /*! @endcond */ + + Condition::Condition() : mycond(new ConditionStorage) {} + Condition::~Condition() { delete mycond; mycond=NULL; } + + void Condition::broadcast() const { + if(int err=pthread_cond_broadcast(&mycond->cond)) { + cerr << "ERROR: ThreadNS::Condition::broadcast() failed: " << strerror(err) << endl; + } + } + void Condition::signal() const { + if(int err=pthread_cond_signal(&mycond->cond)) { + cerr << "ERROR: ThreadNS::Condition::signal() failed: " << strerror(err) << endl; + } + } + bool Condition::timedwait(Lock& l, const timespec* abstime) const { + if(int err=pthread_cond_timedwait(&mycond->cond,&l.mylock->mutex,abstime)) { + if(err!=ETIMEDOUT) + cerr << "ERROR: ThreadNS::Condition::timedwait() failed: " << strerror(err) << endl; + return false; + } + return true; + } + void Condition::wait(Lock& l) const { + if(int err=pthread_cond_wait(&mycond->cond,&l.mylock->mutex)) { + cerr << "ERROR: ThreadNS::Condition::wait() failed: " << strerror(err) << endl; + } + } + } #endif // PLATFORM check diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/Thread.h ./IPC/Thread.h --- ../Tekkotsu_3.0/IPC/Thread.h 2006-06-16 17:49:23.000000000 -0400 +++ ./IPC/Thread.h 2007-10-12 12:55:04.000000000 -0400 @@ -9,6 +9,8 @@ #include "Shared/Resource.h" #include +struct timespec; + //! provides Thread related data structures namespace ThreadNS { //! an inter-thread lock -- doesn't work across processes, only threads within a process. (see MutexLock for inter-process locks) @@ -26,6 +28,7 @@ unsigned int getLockLevel() const; //!< returns the lock level of the lock storage itself, the sum of all instance's lock levels protected: friend class MarkScope; + friend class Condition; virtual void useResource(Resource::Data&) { lock(); } virtual void releaseResource(Resource::Data&) { unlock(); } @@ -37,7 +40,25 @@ private: Lock(const Lock& l); //!< don't call Lock& operator=(const Lock& l); //!< don't call - }; + }; + + //! Provides an inter-thread signaling and synchronization mechanism + class Condition { + public: + Condition(); //!< constructor + ~Condition(); //!< destructor + + void broadcast() const; //!< wake up all threads waiting on the condition + void signal() const; //!< wake up a single thread waiting on the condition (which thread is unspecified) + bool timedwait(Lock& l, const timespec* abstime) const; //!< wait for at most @a abstime for the condition before giving up (return true if condition found) + void wait(Lock& l) const; //!< wait for condition + protected: + class ConditionStorage; //!< internal class to hold system-dependent information + ConditionStorage* mycond; //!< the condition's implementation storage + private: + Condition(const Condition& l); //!< don't call + Condition& operator=(const Condition& l); //!< don't call + }; } //! Provides a nice wrapping of pthreads library @@ -54,10 +75,19 @@ //! requests that the thread be started, if not already running (you need to create a separate instances if you want to run multiple copies) virtual void start(); + //! sends a signal to the thread which will interrupt any sleep calls (and trigger interrupted() to be called within the thread) + virtual void interrupt(); + //! requests that the thread be stopped gracefully, if running. /*! A cancel flag is sent, and the thread will be stopped at next cancel point, defined * by whenever testCancel(), or a set of other system functions, are called. * See your system's pthread_testcancel() manual page for a list of cancel points. + * + * This function may imply a call to interrupt() on systems which have extremely limited + * system cancel points. Currently, this consists of only Mac OS X. There is hope that + * additional cancellation points will be enabled on this system: + * http://lists.apple.com/archives/darwin-kernel/2004/Jan/msg00032.html + * * @see pushNoCancel(), popNoCancel() */ virtual void stop(); @@ -75,7 +105,10 @@ //! blocks calling thread until this Thread has terminated, via one means or another; return value is final return value by the thread virtual void * join(); - //! indicates whether start() has been previously called + //! indicates whether start() has been called (but may be some delay before isRunning() is true...) + virtual bool isStarted() const { return started; } + + //! indicates whether the thread is currently alive and running, implies isStarted() virtual bool isRunning() const { return running; } //! returns the Thread object for the current thread (or NULL for the main thread) @@ -91,6 +124,11 @@ //! should be called whenever a critical section is left (i.e. mutex released) -- if it was the last one, tests cancellability as well static void popNoCancel(); + //! returns #group + void* getGroup() const { return group; } + //! assigns #group, which will then be inherited by any threads instantiated by this one (the constructor call queries the current thread, no the start() or launch()) + void setGroup(void* g) { group=g; } + protected: //! called by launch() when thread is first entered, return false to cancel launch (set #returnValue as well if you care) virtual bool launched() { return true; } @@ -115,12 +153,21 @@ //! indicates the thread is exiting, either voluntary (run() returned), stop(), or kill() -- calls cancelled() for the thread as indicated by @a th static void handle_exit(void * th); + //! called by handleInterrupt() in target thread following call to interrupt(), assuming thread has not been cancelled (which can intercept the interrupt) + virtual void interrupted() {} + + //! called by SIGALRM signal handler installed by interrupt() just before it posts the corresponding SIGALRM + /*! tests for thread cancel condition before calling on to interrupted() */ + static void handleInterrupt(int signal); + //! emit a warning that the last thread exited while the self-pointer thread-specific key still exists (need to call releaseMainThread() or handle_exit()) static void warnSelfUndestructed(void* msg); //! stores the actual pthread data fields struct Threadstorage_t * pt; - //! set to true once start has been called, set back to false by handle_exit(), or by murder() itself + //! set to true once start() has been called, set back to false by handle_exit(), or by murder() itself + bool started; + //! set to true once launch() has been called, set back to false by handle_exit(), or by murder() itself bool running; //! indicates the value to be returned by the thread entry point (and thus passed back to join()) -- set this in runloop() or launched(), overridden by run()'s return value void * returnValue; @@ -128,6 +175,9 @@ unsigned int noCancelDepth; //! cancel status at root of no-cancel stack (may be no-cancel through and through) int cancelOrig; + + //! indicates a common group of threads, inherited from the thread which created this one, default NULL if created from main thread + void* group; private: Thread(const Thread& r); //!< don't call, not a well defined operation diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/LICENSE ./LICENSE --- ../Tekkotsu_3.0/LICENSE 1969-12-31 19:00:00.000000000 -0500 +++ ./LICENSE 2007-11-09 00:01:03.000000000 -0500 @@ -0,0 +1,504 @@ + GNU LESSER GENERAL PUBLIC LICENSE + Version 2.1, February 1999 + + Copyright (C) 1991, 1999 Free Software Foundation, Inc. + 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + Everyone is permitted to copy and distribute verbatim copies + of this license document, but changing it is not allowed. + +[This is the first released version of the Lesser GPL. It also counts + as the successor of the GNU Library Public License, version 2, hence + the version number 2.1.] + + Preamble + + The licenses for most software are designed to take away your +freedom to share and change it. By contrast, the GNU General Public +Licenses are intended to guarantee your freedom to share and change +free software--to make sure the software is free for all its users. + + This license, the Lesser General Public License, applies to some +specially designated software packages--typically libraries--of the +Free Software Foundation and other authors who decide to use it. You +can use it too, but we suggest you first think carefully about whether +this license or the ordinary General Public License is the better +strategy to use in any particular case, based on the explanations below. + + When we speak of free software, we are referring to freedom of use, +not price. Our General Public Licenses are designed to make sure that +you have the freedom to distribute copies of free software (and charge +for this service if you wish); that you receive source code or can get +it if you want it; that you can change the software and use pieces of +it in new free programs; and that you are informed that you can do +these things. + + To protect your rights, we need to make restrictions that forbid +distributors to deny you these rights or to ask you to surrender these +rights. These restrictions translate to certain responsibilities for +you if you distribute copies of the library or if you modify it. + + For example, if you distribute copies of the library, whether gratis +or for a fee, you must give the recipients all the rights that we gave +you. You must make sure that they, too, receive or can get the source +code. If you link other code with the library, you must provide +complete object files to the recipients, so that they can relink them +with the library after making changes to the library and recompiling +it. And you must show them these terms so they know their rights. + + We protect your rights with a two-step method: (1) we copyright the +library, and (2) we offer you this license, which gives you legal +permission to copy, distribute and/or modify the library. + + To protect each distributor, we want to make it very clear that +there is no warranty for the free library. Also, if the library is +modified by someone else and passed on, the recipients should know +that what they have is not the original version, so that the original +author's reputation will not be affected by problems that might be +introduced by others. + + Finally, software patents pose a constant threat to the existence of +any free program. We wish to make sure that a company cannot +effectively restrict the users of a free program by obtaining a +restrictive license from a patent holder. Therefore, we insist that +any patent license obtained for a version of the library must be +consistent with the full freedom of use specified in this license. + + Most GNU software, including some libraries, is covered by the +ordinary GNU General Public License. This license, the GNU Lesser +General Public License, applies to certain designated libraries, and +is quite different from the ordinary General Public License. We use +this license for certain libraries in order to permit linking those +libraries into non-free programs. + + When a program is linked with a library, whether statically or using +a shared library, the combination of the two is legally speaking a +combined work, a derivative of the original library. The ordinary +General Public License therefore permits such linking only if the +entire combination fits its criteria of freedom. The Lesser General +Public License permits more lax criteria for linking other code with +the library. + + We call this license the "Lesser" General Public License because it +does Less to protect the user's freedom than the ordinary General +Public License. It also provides other free software developers Less +of an advantage over competing non-free programs. These disadvantages +are the reason we use the ordinary General Public License for many +libraries. However, the Lesser license provides advantages in certain +special circumstances. + + For example, on rare occasions, there may be a special need to +encourage the widest possible use of a certain library, so that it becomes +a de-facto standard. To achieve this, non-free programs must be +allowed to use the library. A more frequent case is that a free +library does the same job as widely used non-free libraries. In this +case, there is little to gain by limiting the free library to free +software only, so we use the Lesser General Public License. + + In other cases, permission to use a particular library in non-free +programs enables a greater number of people to use a large body of +free software. For example, permission to use the GNU C Library in +non-free programs enables many more people to use the whole GNU +operating system, as well as its variant, the GNU/Linux operating +system. + + Although the Lesser General Public License is Less protective of the +users' freedom, it does ensure that the user of a program that is +linked with the Library has the freedom and the wherewithal to run +that program using a modified version of the Library. + + The precise terms and conditions for copying, distribution and +modification follow. Pay close attention to the difference between a +"work based on the library" and a "work that uses the library". The +former contains code derived from the library, whereas the latter must +be combined with the library in order to run. + + GNU LESSER GENERAL PUBLIC LICENSE + TERMS AND CONDITIONS FOR COPYING, DISTRIBUTION AND MODIFICATION + + 0. This License Agreement applies to any software library or other +program which contains a notice placed by the copyright holder or +other authorized party saying it may be distributed under the terms of +this Lesser General Public License (also called "this License"). +Each licensee is addressed as "you". + + A "library" means a collection of software functions and/or data +prepared so as to be conveniently linked with application programs +(which use some of those functions and data) to form executables. + + The "Library", below, refers to any such software library or work +which has been distributed under these terms. A "work based on the +Library" means either the Library or any derivative work under +copyright law: that is to say, a work containing the Library or a +portion of it, either verbatim or with modifications and/or translated +straightforwardly into another language. (Hereinafter, translation is +included without limitation in the term "modification".) + + "Source code" for a work means the preferred form of the work for +making modifications to it. For a library, complete source code means +all the source code for all modules it contains, plus any associated +interface definition files, plus the scripts used to control compilation +and installation of the library. + + Activities other than copying, distribution and modification are not +covered by this License; they are outside its scope. The act of +running a program using the Library is not restricted, and output from +such a program is covered only if its contents constitute a work based +on the Library (independent of the use of the Library in a tool for +writing it). Whether that is true depends on what the Library does +and what the program that uses the Library does. + + 1. You may copy and distribute verbatim copies of the Library's +complete source code as you receive it, in any medium, provided that +you conspicuously and appropriately publish on each copy an +appropriate copyright notice and disclaimer of warranty; keep intact +all the notices that refer to this License and to the absence of any +warranty; and distribute a copy of this License along with the +Library. + + You may charge a fee for the physical act of transferring a copy, +and you may at your option offer warranty protection in exchange for a +fee. + + 2. You may modify your copy or copies of the Library or any portion +of it, thus forming a work based on the Library, and copy and +distribute such modifications or work under the terms of Section 1 +above, provided that you also meet all of these conditions: + + a) The modified work must itself be a software library. + + b) You must cause the files modified to carry prominent notices + stating that you changed the files and the date of any change. + + c) You must cause the whole of the work to be licensed at no + charge to all third parties under the terms of this License. + + d) If a facility in the modified Library refers to a function or a + table of data to be supplied by an application program that uses + the facility, other than as an argument passed when the facility + is invoked, then you must make a good faith effort to ensure that, + in the event an application does not supply such function or + table, the facility still operates, and performs whatever part of + its purpose remains meaningful. + + (For example, a function in a library to compute square roots has + a purpose that is entirely well-defined independent of the + application. Therefore, Subsection 2d requires that any + application-supplied function or table used by this function must + be optional: if the application does not supply it, the square + root function must still compute square roots.) + +These requirements apply to the modified work as a whole. If +identifiable sections of that work are not derived from the Library, +and can be reasonably considered independent and separate works in +themselves, then this License, and its terms, do not apply to those +sections when you distribute them as separate works. But when you +distribute the same sections as part of a whole which is a work based +on the Library, the distribution of the whole must be on the terms of +this License, whose permissions for other licensees extend to the +entire whole, and thus to each and every part regardless of who wrote +it. + +Thus, it is not the intent of this section to claim rights or contest +your rights to work written entirely by you; rather, the intent is to +exercise the right to control the distribution of derivative or +collective works based on the Library. + +In addition, mere aggregation of another work not based on the Library +with the Library (or with a work based on the Library) on a volume of +a storage or distribution medium does not bring the other work under +the scope of this License. + + 3. You may opt to apply the terms of the ordinary GNU General Public +License instead of this License to a given copy of the Library. To do +this, you must alter all the notices that refer to this License, so +that they refer to the ordinary GNU General Public License, version 2, +instead of to this License. (If a newer version than version 2 of the +ordinary GNU General Public License has appeared, then you can specify +that version instead if you wish.) Do not make any other change in +these notices. + + Once this change is made in a given copy, it is irreversible for +that copy, so the ordinary GNU General Public License applies to all +subsequent copies and derivative works made from that copy. + + This option is useful when you wish to copy part of the code of +the Library into a program that is not a library. + + 4. You may copy and distribute the Library (or a portion or +derivative of it, under Section 2) in object code or executable form +under the terms of Sections 1 and 2 above provided that you accompany +it with the complete corresponding machine-readable source code, which +must be distributed under the terms of Sections 1 and 2 above on a +medium customarily used for software interchange. + + If distribution of object code is made by offering access to copy +from a designated place, then offering equivalent access to copy the +source code from the same place satisfies the requirement to +distribute the source code, even though third parties are not +compelled to copy the source along with the object code. + + 5. A program that contains no derivative of any portion of the +Library, but is designed to work with the Library by being compiled or +linked with it, is called a "work that uses the Library". Such a +work, in isolation, is not a derivative work of the Library, and +therefore falls outside the scope of this License. + + However, linking a "work that uses the Library" with the Library +creates an executable that is a derivative of the Library (because it +contains portions of the Library), rather than a "work that uses the +library". The executable is therefore covered by this License. +Section 6 states terms for distribution of such executables. + + When a "work that uses the Library" uses material from a header file +that is part of the Library, the object code for the work may be a +derivative work of the Library even though the source code is not. +Whether this is true is especially significant if the work can be +linked without the Library, or if the work is itself a library. The +threshold for this to be true is not precisely defined by law. + + If such an object file uses only numerical parameters, data +structure layouts and accessors, and small macros and small inline +functions (ten lines or less in length), then the use of the object +file is unrestricted, regardless of whether it is legally a derivative +work. (Executables containing this object code plus portions of the +Library will still fall under Section 6.) + + Otherwise, if the work is a derivative of the Library, you may +distribute the object code for the work under the terms of Section 6. +Any executables containing that work also fall under Section 6, +whether or not they are linked directly with the Library itself. + + 6. As an exception to the Sections above, you may also combine or +link a "work that uses the Library" with the Library to produce a +work containing portions of the Library, and distribute that work +under terms of your choice, provided that the terms permit +modification of the work for the customer's own use and reverse +engineering for debugging such modifications. + + You must give prominent notice with each copy of the work that the +Library is used in it and that the Library and its use are covered by +this License. You must supply a copy of this License. If the work +during execution displays copyright notices, you must include the +copyright notice for the Library among them, as well as a reference +directing the user to the copy of this License. Also, you must do one +of these things: + + a) Accompany the work with the complete corresponding + machine-readable source code for the Library including whatever + changes were used in the work (which must be distributed under + Sections 1 and 2 above); and, if the work is an executable linked + with the Library, with the complete machine-readable "work that + uses the Library", as object code and/or source code, so that the + user can modify the Library and then relink to produce a modified + executable containing the modified Library. (It is understood + that the user who changes the contents of definitions files in the + Library will not necessarily be able to recompile the application + to use the modified definitions.) + + b) Use a suitable shared library mechanism for linking with the + Library. A suitable mechanism is one that (1) uses at run time a + copy of the library already present on the user's computer system, + rather than copying library functions into the executable, and (2) + will operate properly with a modified version of the library, if + the user installs one, as long as the modified version is + interface-compatible with the version that the work was made with. + + c) Accompany the work with a written offer, valid for at + least three years, to give the same user the materials + specified in Subsection 6a, above, for a charge no more + than the cost of performing this distribution. + + d) If distribution of the work is made by offering access to copy + from a designated place, offer equivalent access to copy the above + specified materials from the same place. + + e) Verify that the user has already received a copy of these + materials or that you have already sent this user a copy. + + For an executable, the required form of the "work that uses the +Library" must include any data and utility programs needed for +reproducing the executable from it. However, as a special exception, +the materials to be distributed need not include anything that is +normally distributed (in either source or binary form) with the major +components (compiler, kernel, and so on) of the operating system on +which the executable runs, unless that component itself accompanies +the executable. + + It may happen that this requirement contradicts the license +restrictions of other proprietary libraries that do not normally +accompany the operating system. Such a contradiction means you cannot +use both them and the Library together in an executable that you +distribute. + + 7. You may place library facilities that are a work based on the +Library side-by-side in a single library together with other library +facilities not covered by this License, and distribute such a combined +library, provided that the separate distribution of the work based on +the Library and of the other library facilities is otherwise +permitted, and provided that you do these two things: + + a) Accompany the combined library with a copy of the same work + based on the Library, uncombined with any other library + facilities. This must be distributed under the terms of the + Sections above. + + b) Give prominent notice with the combined library of the fact + that part of it is a work based on the Library, and explaining + where to find the accompanying uncombined form of the same work. + + 8. You may not copy, modify, sublicense, link with, or distribute +the Library except as expressly provided under this License. Any +attempt otherwise to copy, modify, sublicense, link with, or +distribute the Library is void, and will automatically terminate your +rights under this License. However, parties who have received copies, +or rights, from you under this License will not have their licenses +terminated so long as such parties remain in full compliance. + + 9. You are not required to accept this License, since you have not +signed it. However, nothing else grants you permission to modify or +distribute the Library or its derivative works. These actions are +prohibited by law if you do not accept this License. Therefore, by +modifying or distributing the Library (or any work based on the +Library), you indicate your acceptance of this License to do so, and +all its terms and conditions for copying, distributing or modifying +the Library or works based on it. + + 10. Each time you redistribute the Library (or any work based on the +Library), the recipient automatically receives a license from the +original licensor to copy, distribute, link with or modify the Library +subject to these terms and conditions. You may not impose any further +restrictions on the recipients' exercise of the rights granted herein. +You are not responsible for enforcing compliance by third parties with +this License. + + 11. If, as a consequence of a court judgment or allegation of patent +infringement or for any other reason (not limited to patent issues), +conditions are imposed on you (whether by court order, agreement or +otherwise) that contradict the conditions of this License, they do not +excuse you from the conditions of this License. If you cannot +distribute so as to satisfy simultaneously your obligations under this +License and any other pertinent obligations, then as a consequence you +may not distribute the Library at all. For example, if a patent +license would not permit royalty-free redistribution of the Library by +all those who receive copies directly or indirectly through you, then +the only way you could satisfy both it and this License would be to +refrain entirely from distribution of the Library. + +If any portion of this section is held invalid or unenforceable under any +particular circumstance, the balance of the section is intended to apply, +and the section as a whole is intended to apply in other circumstances. + +It is not the purpose of this section to induce you to infringe any +patents or other property right claims or to contest validity of any +such claims; this section has the sole purpose of protecting the +integrity of the free software distribution system which is +implemented by public license practices. Many people have made +generous contributions to the wide range of software distributed +through that system in reliance on consistent application of that +system; it is up to the author/donor to decide if he or she is willing +to distribute software through any other system and a licensee cannot +impose that choice. + +This section is intended to make thoroughly clear what is believed to +be a consequence of the rest of this License. + + 12. If the distribution and/or use of the Library is restricted in +certain countries either by patents or by copyrighted interfaces, the +original copyright holder who places the Library under this License may add +an explicit geographical distribution limitation excluding those countries, +so that distribution is permitted only in or among countries not thus +excluded. In such case, this License incorporates the limitation as if +written in the body of this License. + + 13. The Free Software Foundation may publish revised and/or new +versions of the Lesser General Public License from time to time. +Such new versions will be similar in spirit to the present version, +but may differ in detail to address new problems or concerns. + +Each version is given a distinguishing version number. If the Library +specifies a version number of this License which applies to it and +"any later version", you have the option of following the terms and +conditions either of that version or of any later version published by +the Free Software Foundation. If the Library does not specify a +license version number, you may choose any version ever published by +the Free Software Foundation. + + 14. If you wish to incorporate parts of the Library into other free +programs whose distribution conditions are incompatible with these, +write to the author to ask for permission. For software which is +copyrighted by the Free Software Foundation, write to the Free +Software Foundation; we sometimes make exceptions for this. Our +decision will be guided by the two goals of preserving the free status +of all derivatives of our free software and of promoting the sharing +and reuse of software generally. + + NO WARRANTY + + 15. BECAUSE THE LIBRARY IS LICENSED FREE OF CHARGE, THERE IS NO +WARRANTY FOR THE LIBRARY, TO THE EXTENT PERMITTED BY APPLICABLE LAW. +EXCEPT WHEN OTHERWISE STATED IN WRITING THE COPYRIGHT HOLDERS AND/OR +OTHER PARTIES PROVIDE THE LIBRARY "AS IS" WITHOUT WARRANTY OF ANY +KIND, EITHER EXPRESSED OR IMPLIED, INCLUDING, BUT NOT LIMITED TO, THE +IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR +PURPOSE. THE ENTIRE RISK AS TO THE QUALITY AND PERFORMANCE OF THE +LIBRARY IS WITH YOU. SHOULD THE LIBRARY PROVE DEFECTIVE, YOU ASSUME +THE COST OF ALL NECESSARY SERVICING, REPAIR OR CORRECTION. + + 16. IN NO EVENT UNLESS REQUIRED BY APPLICABLE LAW OR AGREED TO IN +WRITING WILL ANY COPYRIGHT HOLDER, OR ANY OTHER PARTY WHO MAY MODIFY +AND/OR REDISTRIBUTE THE LIBRARY AS PERMITTED ABOVE, BE LIABLE TO YOU +FOR DAMAGES, INCLUDING ANY GENERAL, SPECIAL, INCIDENTAL OR +CONSEQUENTIAL DAMAGES ARISING OUT OF THE USE OR INABILITY TO USE THE +LIBRARY (INCLUDING BUT NOT LIMITED TO LOSS OF DATA OR DATA BEING +RENDERED INACCURATE OR LOSSES SUSTAINED BY YOU OR THIRD PARTIES OR A +FAILURE OF THE LIBRARY TO OPERATE WITH ANY OTHER SOFTWARE), EVEN IF +SUCH HOLDER OR OTHER PARTY HAS BEEN ADVISED OF THE POSSIBILITY OF SUCH +DAMAGES. + + END OF TERMS AND CONDITIONS + + How to Apply These Terms to Your New Libraries + + If you develop a new library, and you want it to be of the greatest +possible use to the public, we recommend making it free software that +everyone can redistribute and change. You can do so by permitting +redistribution under these terms (or, alternatively, under the terms of the +ordinary General Public License). + + To apply these terms, attach the following notices to the library. It is +safest to attach them to the start of each source file to most effectively +convey the exclusion of warranty; and each file should have at least the +"copyright" line and a pointer to where the full notice is found. + + + Copyright (C) + + This library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + This library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with this library; if not, write to the Free Software + Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA + +Also add information on how to contact you by electronic and paper mail. + +You should also get your employer (if you work as a programmer) or your +school, if any, to sign a "copyright disclaimer" for the library, if +necessary. Here is a sample; alter the names: + + Yoyodyne, Inc., hereby disclaims all copyright interest in the + library `Frob' (a library for tweaking knobs) written by James Random Hacker. + + , 1 April 1990 + Ty Coon, President of Vice + +That's all there is to it! + + diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Makefile ./Makefile --- ../Tekkotsu_3.0/Makefile 2006-09-26 17:53:57.000000000 -0400 +++ ./Makefile 2007-11-13 21:19:15.000000000 -0500 @@ -17,6 +17,24 @@ TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEKKOTSU_ROOT)/project/Environment.conf include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g') +ifeq ($(MAKELEVEL),0) +INDENT=#empty string just to tokenize leading whitespace removal from the *actual* indentation + $(shell echo " ** Targeting $(TEKKOTSU_TARGET_MODEL) for build on $(TEKKOTSU_TARGET_PLATFORM) **" > /dev/tty) + $(shell echo " ** TEKKOTSU_DEBUG is $(if $(TEKKOTSU_DEBUG),ON: $(TEKKOTSU_DEBUG),OFF) **" > /dev/tty) + $(shell echo " ** TEKKOTSU_OPTIMIZE is $(if $(TEKKOTSU_DEBUG),DISABLED BY DEBUG,$(if $(TEKKOTSU_OPTIMIZE),ON: $(TEKKOTSU_OPTIMIZE),OFF)) **" > /dev/tty) +endif + +#sanity checks +ifeq ($(filter clean% docs alldocs,$(MAKECMDGOALS)),) + ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) + $(if $(shell [ -d "$(OPENRSDK_ROOT)" ] || echo "not found"),$(error OPEN-R SDK not found at '$(OPENRSDK_ROOT)', check installation.)) + $(if $(shell [ -d "$(OPENRSDK_ROOT)/OPEN_R" ] || echo "not found"),$(error OPEN-R SDK header files missing, check installation.)) + endif + $(if $(shell $(CXX) -v > /dev/null 2>&1 || echo "not found"),$(error C++ compiler not found at '$(CXX)', check installation.)) +endif + +$(shell mkdir -p $(TK_BD)) + ############# MAKEFILE VARIABLES ################ @@ -28,26 +46,33 @@ # section. (grep/search for the file name) ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) - PLATFORM_FLAGS= \ + PLATFORM_FLAGS:= \ -isystem $(OPENRSDK_ROOT)/OPEN_R/include/MCOOP \ -isystem $(OPENRSDK_ROOT)/OPEN_R/include/R4000 \ -isystem $(OPENRSDK_ROOT)/OPEN_R/include \ -isystem aperios/include \ - $(if $(TEKKOTSU_DEBUG),-DOPENR_DEBUG,) \ - `aperios/bin/xml2-config --cflags` + $(if $(TEKKOTSU_DEBUG),-DOPENR_DEBUG,) -DLOADFILE_NO_MMAP \ + $(shell aperios/bin/xml2-config --cflags) else - PLATFORM_FLAGS=`xml2-config --cflags` -isystem /usr/include/libpng12 + PLATFORM_FLAGS:=$(shell xml2-config --cflags) -isystem /usr/include/libpng12 \ + $(shell if [ -d "$(ICE_ROOT)" ] ; then echo "-DHAVE_ICE -I$(ICE_ROOT)/include"; fi) endif +ifeq ($(MAKELEVEL),0) + export ENV_CXXFLAGS:=$(CXXFLAGS) +else + unexport CXXFLAGS +endif CXXFLAGS:= \ $(if $(TEKKOTSU_DEBUG),$(TEKKOTSU_DEBUG),$(TEKKOTSU_OPTIMIZE)) \ -pipe -ffast-math -fno-common \ - -Wall -W -Wshadow -Wlarger-than-8192 -Wpointer-arith -Wcast-qual \ + -Wall -Wshadow -Wlarger-than-200000 -Wpointer-arith -Wcast-qual \ -Woverloaded-virtual -Weffc++ -Wdeprecated -Wnon-virtual-dtor \ + -fmessage-length=0 \ -I$(TEKKOTSU_ROOT) -I$(TEKKOTSU_ROOT)/Motion/roboop \ -I$(TEKKOTSU_ROOT)/Shared/newmat \ -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) \ - $(PLATFORM_FLAGS) $(CXXFLAGS) + $(PLATFORM_FLAGS) $(ENV_CXXFLAGS) INCLUDE_PCH=$(if $(TEKKOTSU_PCH),-include $(TK_BD)/$(TEKKOTSU_PCH)) @@ -61,7 +86,7 @@ # external libraries or new directories for the search SRCSUFFIX:=.cc SRC_DIRS:=Behaviors DualCoding Events IPC Motion Shared Sound Vision Wireless -SRCS:=$(shell find $(SRC_DIRS) -name "*$(SRCSUFFIX)" | xargs ls -t) +SRCS:=$(shell find $(SRC_DIRS) -name "*$(SRCSUFFIX)") # We should also make sure these libraries are ready to go # Note we've been lucky that these libraries happen to use a different @@ -78,30 +103,49 @@ #delete automatic suffix list .SUFFIXES: -.PHONY: all compile clean cleanDeps reportTarget testEnv docs dox doc alldocs cleanDoc updateTools updateLibs $(USERLIBS) platformBuild update install +.PHONY: all compile clean cleanDeps docs alldocs cleanDoc updateTools updateLibs $(USERLIBS) platformBuild update install static shared +ifeq ($(filter TGT_ERS%,$(TEKKOTSU_TARGET_MODEL)),) +all: + @echo "Running $(MAKE) from the root directory will build the" + @echo "Tekkotsu library which is linked against by executables." + @echo "The Environment.conf from the template 'project' directory" + @echo "will be used, which can be overridden by environment" + @echo "variables. Current settings are:" + @echo ""; + @echo " Target model: $(TEKKOTSU_TARGET_MODEL)" + @echo " Build directory: $(TEKKOTSU_BUILDDIR)" + @echo ""; + @echo "You will want to run 'make' from your project directory in order" + @echo "to produce executables..." + @echo "" + $(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_LOCAL compile static shared + @echo "Build successful." +else all: @echo "Running $(MAKE) from the root directory will first build the" @echo "Tekkotsu library for Aperios (AIBO), and then for the local" - @echo "platform. The Environment.conf from the template project" - @echo "directory will be used, which currently contains:" + @echo "platform. The Environment.conf from the template 'project'" + @echo "directory will be used, which can be overridden by environment" + @echo "variables. Current settings are:" @echo ""; @echo " Target model: $(TEKKOTSU_TARGET_MODEL)" @echo " Build directory: $(TEKKOTSU_BUILDDIR)" @echo ""; - @echo "You will want to run make from your project directory in order" + @echo "You will want to run 'make' from your project directory in order" @echo "to produce executables..." @echo "" - $(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_APERIOS compile - $(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_LOCAL compile + $(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_APERIOS compile static + $(MAKE) TEKKOTSU_TARGET_PLATFORM=PLATFORM_LOCAL compile static shared @echo "Build successful." +endif update install sim: @echo "" @echo "You probably want to be running make from within your project's directory" @echo "" @echo "You can run $(MAKE) from within the root Tekkotsu directory to build" - @echo "libtekkotsu.a for both Aperios and the host platform, which will then" + @echo "libtekkotsu for both Aperios and the host platform, which will then" @echo "be linked against by the projects and tools." @echo "" @echo "However, you can only install or update to memory stick from within a project." @@ -113,6 +157,17 @@ @echo "Could not find Environment file - check the default project directory still exists" @exit 1 +TOOLS_BUILT_FLAG:=$(TEKKOTSU_BUILDDIR)/.toolsBuilt + +ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) +include aperios/Makefile.aperios +else +include local/Makefile.local +endif + +# Sort by modification date +SRCS:=$(shell ls -t $(SRCS)) + # The object file for each of the source files OBJS:=$(addprefix $(TK_BD)/,$(SRCS:$(SRCSUFFIX)=.o)) @@ -122,14 +177,6 @@ DEPENDS:=$(addprefix $(TK_BD)/,$(SRCS:$(SRCSUFFIX)=.d) $(addsuffix .d,$(TEKKOTSU_PCH))) -TOOLS_BUILT_FLAG:=$(TEKKOTSU_BUILDDIR)/.toolsBuilt - -ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) -include aperios/Makefile.aperios -else -include local/Makefile.local -endif - %.gch: @mkdir -p $(dir $@) @src=$(patsubst $(TK_BD)/%,%,$*); \ @@ -157,51 +204,26 @@ EMPTYDEPS:=$(shell find $(TK_BD) -type f -name "*\.d" -size 0 -print -exec rm \{\} \;) ifneq ($(EMPTYDEPS),) -EMPTYDEPS:=$(shell echo "Empty dependency files detected: $(EMPTYDEPS)" > /dev/tty) + $(shell echo "Empty dependency files detected: $(EMPTYDEPS)" > /dev/tty) endif -ifneq ($(MAKECMDGOALS),) -ifeq ($(filter clean% docs dox doc alldocs newstick,$(MAKECMDGOALS)),) +ifeq ($(filter clean% docs alldocs newstick,$(MAKECMDGOALS)),) -include $(DEPENDS) ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) -include $(TK_BD)/aperios/aperios.d endif endif -endif -compile: reportTarget updateTools updateLibs platformBuild +compile: updateTools updateLibs platformBuild $(TOOLS_BUILT_FLAG): @$(MAKE) TOOLS_BUILT_FLAG="$(TOOLS_BUILT_FLAG)" -C tools -dox docs doc: - docs/builddocs --update --tree --search +docs: + docs/builddocs --update --tree alldocs: - docs/builddocs --update --all --tree --search - -ifeq ($(MAKELEVEL),0) -reportTarget: testEnv - @echo " ** Targeting $(TEKKOTSU_TARGET_MODEL) for build on $(TEKKOTSU_TARGET_PLATFORM) ** "; - @echo " ** TEKKOTSU_DEBUG is $(if $(TEKKOTSU_DEBUG),ON: $(TEKKOTSU_DEBUG),OFF) ** "; - @echo " ** TEKKOTSU_OPTIMIZE is $(if $(TEKKOTSU_DEBUG),DISABLED BY DEBUG,$(if $(TEKKOTSU_OPTIMIZE),ON: $(TEKKOTSU_OPTIMIZE),OFF)) ** "; -else -reportTarget: ; -endif - -testEnv: - @if [ ! -d "$(OPENRSDK_ROOT)" ] ; then \ - echo "ERROR: OPEN-R SDK not found at '$(OPENRSDK_ROOT)', check installation." ; \ - exit 1; \ - fi; - @if $(CXX) -v > /dev/null 2>&1 ; then true; else \ - echo "ERROR: c++ compiler not found at '$(CXX)', check installation." ; \ - exit 1; \ - fi; - @if [ ! -d "$(OPENRSDK_ROOT)/OPEN_R" ] ; then \ - echo "ERROR: OPEN-R SDK header files missing, check installation." ; \ - exit 1; \ - fi; + docs/builddocs --update --all --tree updateTools: | $(TOOLS_BUILT_FLAG) $(MAKE) -C tools @@ -213,6 +235,19 @@ export TEKKOTSU_ENVIRONMENT_CONFIGURATION="$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)"; \ $(MAKE) -C "$@" +ifeq ($(findstring compile,$(MAKECMDGOALS)),compile) +ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) +static: $(TK_BD)/libtekkotsu.a ; +shared: + @echo "PLATFORM_APERIOS does not support shared libraries... Make goal 'shared' ignored." +else +static: $(TK_BD)/libtekkotsu.a ; +shared: $(TK_BD)/libtekkotsu.$(if $(findstring Darwin,$(shell uname)),dylib,so) ; +endif +else +static shared: all ; +endif + $(TK_BD)/libtekkotsu.a: $(OBJS) @echo "Linking object files..." @printf "$@ <- "; echo "[...]" | sed 's@$(TK_BD)/@@g'; @@ -220,6 +255,16 @@ @$(AR) $@ $(OBJS); @$(AR2) $@ +$(TK_BD)/libtekkotsu.dylib: $(OBJS) + @echo "Linking object files..." + @printf "$@ <- "; echo "[...]" | sed 's@$(TK_BD)/@@g'; + @libtool -dynamic -undefined dynamic_lookup -o $@ $(OBJS); + +$(TK_BD)/libtekkotsu.so: $(OBJS) + @echo "Linking object files..." + @printf "$@ <- "; echo "[...]" | sed 's@$(TK_BD)/@@g'; + @$(CXX) -shared -o $@ $(OBJS); + %.h : @echo "ERROR: Seems to be a missing header file '$@'..."; @if [ "$(notdir $@)" = "def.h" -o "$(notdir $@)" = "entry.h" ] ; then \ @@ -255,6 +300,7 @@ $(MAKE) TOOLS_BUILT_FLAG="$(TOOLS_BUILT_FLAG)" -C tools clean; for dir in `ls aperios` ; do \ if [ "$$dir" = "CVS" ] ; then continue; fi; \ + if [ "$$dir" = ".svn" ] ; then continue; fi; \ if [ -f "aperios/$$dir" ] ; then continue; fi; \ rm -f "aperios/$$dir/$${dir}Stub."{h,cc} "aperios/$$dir/def.h" "aperios/$$dir/entry.h" ; \ done diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/EmergencyStopMC.cc ./Motion/EmergencyStopMC.cc --- ../Tekkotsu_3.0/Motion/EmergencyStopMC.cc 2006-09-18 14:08:01.000000000 -0400 +++ ./Motion/EmergencyStopMC.cc 2007-11-18 01:47:03.000000000 -0500 @@ -17,22 +17,36 @@ { for(unsigned int i=0; irobotDesign&WorldState::ERS210Mask) { - ledengine.cycle(ERS210Info::TlRedLEDMask,period,1,0,period/2); - ledengine.cycle(ERS210Info::TlBluLEDMask,period,1); - } else if(state->robotDesign&WorldState::ERS220Mask) { - ledengine.cycle(ERS220Info::TailCenterLEDMask, period, 2.0f, -.5f, (int)(period * 0/5.5)); - ledengine.cycle(ERS220Info::TailLeftLEDMask|ERS220Info::TailRightLEDMask, period, 2.0f, -.5f, (int)(period * 1/5.5)); - ledengine.cycle(ERS220Info::BackLeft3LEDMask|ERS220Info::BackRight1LEDMask, period, 2.0f, -.5f, (int)(period * 2/5.5)); - ledengine.cycle(ERS220Info::BackLeft2LEDMask|ERS220Info::BackRight2LEDMask, period, 2.0f, -.5f, (int)(period * 3/5.5)); - ledengine.cycle(ERS220Info::BackLeft1LEDMask|ERS220Info::BackRight3LEDMask, period, 2.0f, -.5f, (int)(period * 4/5.5)); - } else if(state->robotDesign&WorldState::ERS7Mask) { - ledengine.cycle(1<<(ERS7Info::MdBackColorLEDOffset-LEDOffset),2*period/3,.15,.15/2-.5,0); +#ifdef TGT_HAS_LEDS + if(RobotName == ERS210Info::TargetName) { + int red=capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TlRedLEDOffset]) - LEDOffset; + int blue=capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TlBluLEDOffset]) - LEDOffset; + ledengine.cycle((1<printf("Emergency Stop: unknown model\n"); + serr->printf("Emergency Stop: unknown model, no LED special effects\n"); ledengine.cycle(1<<(NumLEDs-1),period,1,0,period/2); ledengine.cycle(1<<(NumLEDs-2),period,1); } +#endif defaultMaxSpeed(.15); takeSnapshot(); } @@ -59,8 +73,10 @@ if(!dirty) return 0; if(curt>=timeoflastrelease) { +#ifdef TGT_HAS_LEDS for(unsigned int i=LEDOffset; isetOutput(this,i,0.f); //blank out LEDs to avoid residual background display +#endif dirty=false; return 0; } @@ -91,8 +107,10 @@ } } } +#ifdef TGT_HAS_LEDS ledengine.updateLEDs(&cmds[LEDOffset]); - if(state->robotDesign&WorldState::ERS7Mask) { +#endif + if(RobotName == ERS7Info::TargetName) { //a special Battlestar Galactica inspired effect for the ERS-7 static float acts[5]; static bool wasPaused=false; @@ -112,15 +130,21 @@ // w is used to fade out LEDs when releasing estop float w = (paused || curt>=timeoflastrelease) ? 1 : (static_cast(timeoflastrelease-curt)/FADE_OUT_TIME); for(int i=0; i<5; i++) { - imp[i]=exp(invsigma*(t-i-2)*(t-i-2))*w; - acts[i]+=amp*imp[i]; + float p=invsigma*(t-i-2)*(t-i-2); + if(p>-10) { // only bother with impulse if big enough + // (in particular, saw exp returning -inf instead of 0 for <-85... bug in libm?) + imp[i]=expf(p)*w; + acts[i]+=amp*imp[i]; + } else { + imp[i]=0; + } acts[i]*=gamma*w; } - cmds[ERS7Info::FaceLEDPanelOffset+ 6].value=acts[0]/2+imp[0]; - cmds[ERS7Info::FaceLEDPanelOffset+ 8].value=acts[1]/2+imp[1]; - cmds[ERS7Info::FaceLEDPanelOffset+10].value=acts[2]/2+imp[2]; - cmds[ERS7Info::FaceLEDPanelOffset+ 9].value=acts[3]/2+imp[3]; - cmds[ERS7Info::FaceLEDPanelOffset+ 7].value=acts[4]/2+imp[4]; + cmds[ERS7Info::FaceLEDPanelOffset+ 6]=acts[0]/2+imp[0]; + cmds[ERS7Info::FaceLEDPanelOffset+ 8]=acts[1]/2+imp[1]; + cmds[ERS7Info::FaceLEDPanelOffset+10]=acts[2]/2+imp[2]; + cmds[ERS7Info::FaceLEDPanelOffset+ 9]=acts[3]/2+imp[3]; + cmds[ERS7Info::FaceLEDPanelOffset+ 7]=acts[4]/2+imp[4]; } int changed=PostureMC::updateOutputs(); dirty=(curtplayFile(config->motion.estop_on_snd); - cout << "*** PAUSED ***" << endl; + std::cout << "*** PAUSED ***" << std::endl; } else { releaseJoints(); if(sound) sndman->playFile(config->motion.estop_off_snd); - cout << "*** UNPAUSED ***" << endl; + std::cout << "*** UNPAUSED ***" << std::endl; } } } @@ -166,20 +190,43 @@ } for(unsigned int i=0; ipidduties[i]; +#ifdef TGT_HAS_WHEELS + //Wheels need to be set to 0 in e-stop mode + for(unsigned int i=WheelOffset; irobotDesign&WorldState::ERS210Mask) { - cmds[ERS210Info::TlRedLEDOffset].set(0,.5); - cmds[ERS210Info::TlBluLEDOffset].set(0,.5); - } else if(state->robotDesign&WorldState::ERS220Mask) { - for(unsigned int i = 0; i < NumLEDs; i++) - if((ERS220Info::TailLEDMask|ERS220Info::BackLEDMask) & (1 << i)) - cmds[LEDOffset + i].set(0, .5); - } else if(state->robotDesign&WorldState::ERS7Mask) { + if(RobotName == ERS210Info::TargetName) { + int red=capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TlRedLEDOffset]); + int blue=capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TlBluLEDOffset]); + cmds[red].set(0,.5); + cmds[blue].set(0,.5); + } else if(RobotName == ERS220Info::TargetName) { + int tl=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::TailLeftLEDOffset]); + int tc=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::TailCenterLEDOffset]); + int tr=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::TailRightLEDOffset]); + int bl1=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackLeft1LEDOffset]); + int bl2=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackLeft2LEDOffset]); + int bl3=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackLeft3LEDOffset]); + int br1=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackRight1LEDOffset]); + int br2=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackRight2LEDOffset]); + int br3=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackRight3LEDOffset]); + cmds[tl].set(0, .5); cmds[tc].set(0, .5); cmds[tr].set(0, .5); + cmds[bl1].set(0, .5); cmds[bl2].set(0, .5); cmds[bl3].set(0, .5); + cmds[br1].set(0, .5); cmds[br2].set(0, .5); cmds[br3].set(0, .5); + } else if(RobotName == ERS7Info::TargetName) { cmds[ERS7Info::MdBackColorLEDOffset].set(0,.5); for(int i=6; i<6+5; i++) cmds[ERS7Info::FaceLEDPanelOffset+i].set(0,0.5); @@ -187,6 +234,7 @@ cmds[LEDOffset+NumLEDs-1].set(0,.5); cmds[LEDOffset+NumLEDs-2].set(0,.5); } +#endif postEvent(EventBase(EventBase::estopEGID,getID(),EventBase::activateETID,0)); timeoflastfreeze=get_time(); } @@ -200,14 +248,18 @@ } bool EmergencyStopMC::trigger() { - WorldState * st=WorldState::getCurrent(); // this is need because trigger is a static, so it doesn't access the Motion - if(st->robotDesign&WorldState::ERS210Mask) - return st->button_times[ERS210Info::BackButOffset]; - if(st->robotDesign&WorldState::ERS220Mask) - return st->button_times[ERS220Info::BackButOffset]; - if(st->robotDesign&WorldState::ERS7Mask) + WorldState * st=WorldState::getCurrent(); // this is need because trigger is a static, so it doesn't have access to the MC 'state' instance + if(RobotName == ERS210Info::TargetName) + return st->button_times[capabilities.getButtonOffset(ERS210Info::buttonNames[ERS210Info::BackButOffset])]; + if(RobotName == ERS220Info::TargetName) + return st->button_times[capabilities.getButtonOffset(ERS220Info::buttonNames[ERS220Info::BackButOffset])]; + if(RobotName == ERS7Info::TargetName) return st->button_times[ERS7Info::FrontBackButOffset]+st->button_times[ERS7Info::MiddleBackButOffset]+st->button_times[ERS7Info::RearBackButOffset]; - serr->printf("EmergencyStopMC: unsupported model!\n"); +#ifdef TGT_HAS_BUTTONS + // depending on platform, RobotName may be either char* or string + std::string tmpName = RobotName; // convert to consistent form so we can printf it... + serr->printf("EmergencyStopMC: %s unsupported model!\n",tmpName.c_str()); +#endif return false; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/HeadPointerMC.cc ./Motion/HeadPointerMC.cc --- ../Tekkotsu_3.0/Motion/HeadPointerMC.cc 2006-08-31 17:42:02.000000000 -0400 +++ ./Motion/HeadPointerMC.cc 2007-11-18 01:47:03.000000000 -0500 @@ -1,5 +1,3 @@ -#include - #include "HeadPointerMC.h" #include "Kinematics.h" #include "Shared/debuget.h" @@ -7,9 +5,12 @@ #include "MotionManager.h" #include "Shared/Config.h" #include "Wireless/Socket.h" +#include "Shared/ERS7Info.h" +#include "Shared/ERS210Info.h" +#include HeadPointerMC::HeadPointerMC() - : MotionCommand(), dirty(true), hold(true), tolerance(.05), + : MotionCommand(), dirty(true), hold(true), tolerance(.05), // if change default tolerance, update documentation in header targetReached(true), targetTimestamp(0), timeout(2000), headkin(::config->motion.makePath(::config->motion.kinematics),"Camera") { @@ -19,37 +20,78 @@ } void HeadPointerMC::freezeMotion() { +#ifdef TGT_HAS_HEAD for(unsigned int i=0; ioutputs[HeadOffset+i]; dirty=true; +#endif } void HeadPointerMC::defaultMaxSpeed(float x/*=1*/) { - maxSpeed[TiltOffset]=config->motion.max_head_tilt_speed*FrameTime*x/1000; - maxSpeed[PanOffset]=config->motion.max_head_pan_speed*FrameTime*x/1000; - maxSpeed[RollOffset]=config->motion.max_head_roll_speed*FrameTime*x/1000; +#ifdef TGT_HAS_HEAD + const char* n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::TiltOffset]; + unsigned int i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeed[i-HeadOffset]=config->motion.max_head_tilt_speed*FrameTime*x/1000; + n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeed[i-HeadOffset]=config->motion.max_head_pan_speed*FrameTime*x/1000; + n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::NodOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeed[i-HeadOffset]=config->motion.max_head_roll_speed*FrameTime*x/1000; + n = ERS210Info::outputNames[ERS210Info::HeadOffset+ERS210Info::RollOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeed[i-HeadOffset]=config->motion.max_head_roll_speed*FrameTime*x/1000; +#endif } void HeadPointerMC::setWeight(float w) { +#ifdef TGT_HAS_HEAD for(unsigned int x=0; xtimeout)) { //prevents a conflicted HeadPointerMC's from fighting forever @@ -159,16 +215,22 @@ maxdiff=diff; } return (maxdiff>tolerance); +#endif } void HeadPointerMC::markDirty() { dirty=true; targetReached=false; +#ifdef TGT_HAS_HEAD for(unsigned int i=0; igetOutputCmd(HeadOffset+i).value; //not state->outputs[HeadOffset+i]; - see function documentation +#endif } bool HeadPointerMC::ensureValidJoint(unsigned int& i) { +#ifndef TGT_HAS_HEAD + serr->printf("ERROR: HeadPointerMC received a joint index of %d on headless target.\n",i); +#else if(i=HeadOffset && iprintf("ERROR: HeadPointerMC received a joint index of %d (HeadOffset%+d).\n",i,i-HeadOffset); serr->printf("ERROR: This does not appear to be a head joint. HeadPointerMC only controls\n"); serr->printf(" head joints, and assumes its arguments are relative to HeadOffset\n"); +#endif return false; } @@ -190,10 +253,8 @@ * @author ejt (Creator) * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.25 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.29 $ * $State: Exp $ - * $Date: 2006/08/31 21:42:02 $ + * $Date: 2007/11/18 06:47:03 $ */ - - diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/HeadPointerMC.h ./Motion/HeadPointerMC.h --- ../Tekkotsu_3.0/Motion/HeadPointerMC.h 2006-09-26 15:29:40.000000000 -0400 +++ ./Motion/HeadPointerMC.h 2007-11-19 16:45:25.000000000 -0500 @@ -1,9 +1,10 @@ //-*-c++-*- #ifndef INCLUDED_HeadPointerMC_h #define INCLUDED_HeadPointerMC_h + +#include "Shared/RobotInfo.h" #include "MotionCommand.h" #include "OutputCmd.h" -#include "Shared/RobotInfo.h" #include "Shared/mathutils.h" #include "roboop/robot.h" @@ -62,20 +63,32 @@ //! Sets the weight values for all the neck joints void setWeight(float w); - //! Directly sets the neck values (all values in radians) - /*! @param j1 value for first neck joint (tilt on all ERS models) - * @param j2 value for second neck joint (pan on all ERS models) - * @param j3 value for third neck joint (nod on ERS-7, roll on ERS-2xx) */ - void setJoints(float j1, float j2, float j3); + //! Request a set of neck joint values + /*! Originally this corresponded directly to the neck joints of the aibo, however + * on other platforms it will use capabilties mapping to try to set correspnding joints if available. + * (we're not doing kinematics here, trying to set joint values directly. If your + * want a more generic/abstract interface, use lookAtPoint()/lookInDirection(). + * + * Note that for a "pan-tilt" camera, you actually want to set the @em last two parameters, + * @em not the first two! + * + * @param tilt value - this is an initial rotation about the camera x axis + * @param pan value - this is a rotation about the camera y axis + * @param tilt2 value - a second rotation about the camera x axis ("nod") + * + * On ERS-210 and 220, the tilt2 is actually a roll about camera z (ugly, but no one's using those anymore, so moot issue) */ + void setJoints(float tilt, float pan, float tilt2); //! Directly set a single neck joint value /*! @param i joint offset relative to HeadOffset (i.e. one of TPROffset_t) * @param value the value to be assigned to join @a i, in radians */ void setJointValue(unsigned int i, float value) { +#ifdef TGT_HAS_HEAD if(!ensureValidJoint(i)) return; headTargets[i]=clipAngularRange(HeadOffset+i,value); markDirty(); +#endif } //! Returns the target value of joint @a i. Use this if you want to know the current @b commanded joint value; To get the current joint @b position, look in WorldState::outputs @@ -169,7 +182,7 @@ bool dirty; //!< true if a change has been made since last call to updateJointCmds() bool hold; //!< if set to true, the posture will be kept active; otherwise joints will be marked unused after each posture is achieved (as if the posture was pruned); set through setHold() - float tolerance; //!< when autopruning, if the maxdiff() of this posture and the robot's current position is below this value, isAlive() will be false, defaults to 0.01 (5.7 degree error) + float tolerance; //!< when autopruning, if the maxdiff() of this posture and the robot's current position is below this value, isAlive() will be false, defaults to 0.05 radian (2.86 degree error) bool targetReached; //!< false if the head is still moving towards its target unsigned int targetTimestamp; //!< time at which the targetReached flag was set unsigned int timeout; //!< number of milliseconds to wait before giving up on a target that should have already been reached, a value of -1U will try forever @@ -191,4 +204,3 @@ */ #endif - diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/HolonomicMotionModel.cc ./Motion/HolonomicMotionModel.cc --- ../Tekkotsu_3.0/Motion/HolonomicMotionModel.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Motion/HolonomicMotionModel.cc 2007-01-27 15:49:52.000000000 -0500 @@ -0,0 +1,27 @@ +#include "HolonomicMotionModel.h" + +void computeHolonomicMotion(float xvel, float yvel, float avel, float time, float& xpos, float& ypos, float& apos) { + float speed = std::sqrt(xvel*xvel + yvel*yvel); + if (std::fabs(avel)*1e6 <= speed) { + // straight line motion + float distmovx = time * xvel; + float distmovy = time * yvel; + float c=std::cos(apos); + float s=std::sin(apos); + xpos += distmovx*c - distmovy*s; + ypos += distmovx*s + distmovy*c; + //cout << "Dist Moved X: " << distmovx << endl; // .f floating point + //cout << "Dist Moved Y: " << distmovy << endl; // .f floating point + } else { + float radius = speed / avel; // when walking while turning, circle created...radius of that circle + float anglturn = time * avel; // amount turned + float heading = apos + std::atan2(yvel,xvel); // direction of instantaneous motion + heading += anglturn/2; // plus the offset that will occur due to curvature over time + float distmov = 2 * radius * std::sin(anglturn/2); // displacement that will result along heading + + //cout << "radius: " << radius << " Angle Turned: " << anglturn << " Dist Moved: " << distmov << " Heading: " << heading << endl; + xpos += distmov*cos(heading); + ypos += distmov*sin(heading); + apos += anglturn; + } +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/HolonomicMotionModel.h ./Motion/HolonomicMotionModel.h --- ../Tekkotsu_3.0/Motion/HolonomicMotionModel.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Motion/HolonomicMotionModel.h 2007-11-10 17:58:09.000000000 -0500 @@ -0,0 +1,218 @@ +//-*-c++-*- +#ifndef INCLUDED_HolonomicMotionModel_h_ +#define INCLUDED_HolonomicMotionModel_h_ + +#include "Shared/ParticleFilter.h" +#include "Shared/LocalizationParticle.h" +#include "Shared/get_time.h" +#include "Shared/zignor.h" +#include + +//! the main function -- to avoid numeric issues, treats paths that would result in a radius over 1e6 long as a straight line +/*! see HolonomicMotionModel class notes for more information on the math involved */ +void computeHolonomicMotion(float xvel, float yvel, float avel, float time, float& xpos, float& ypos, float& apos); + +//! This class can model the path of a holonomic robot in two dimensions (x and y) +/*! This class can also model a non-holonomic robot, just don't use the y parameter! + * + * The static function computeMotion() does the main computational grunt work. + * + *
+ * Illustration of the equations used. Constant angular and linear velocities result in a + * circular arc as shown. The radius of the arc is directly determined by the ratio of the + * linear speed to the angular speed. The final position after time @f$ \Delta t @f$ will be + * @f$ \delta @f$ along a bearing @f$ \theta/2 @f$, where @f$ \theta @f$ is the angle which has + * been turned during the interval of interest. + *
+ * + * You can call setPosition() to initialize the starting location or if the robot has been moved + * by some external means. You should call setVelocity() whenever the robot's velocity changes. + * The class will internally store the position and time at which the velocity change happened + * so that later calls to getPosition() will return points along the new path. + * + * This class can be used as a motion model in the ParticleFilter class, or independently if + * desired for general purpose motion estimation. (see the standalone computeHolonomicMotion()) + * + * However, if you are looking for a motion model for ParticleFiltering, it may be more convenient + * to use DeadReckoningBehavior (found in Behaviors/Services) because you can start the + * behavior and it will subscribe to automatically receive LocomotionEvents from then on. + * If using HolonomicMotionModel directly with the particle filter, you + * would need to call setVelocity() yourself anytime the robot changes direction. + * + * Variance parameters only come into play with updateMotion(), which is called on + * collections of particles. The other functions all return "ideal" motion calculations. + * Be aware that when using in a particle filter, the position is reset on particle updates + * (updateMotion()). In other words, the position returned by motion model is the + * offset achieved since the last particle update, @e not the position relative to + * world's origin, nor any other fixed point. + * + * Caveat: acceleration is not handled by this model. That would be a nice addition... + * + * @see computeHolonomicMotion() + */ +template +class HolonomicMotionModel : public ParticleFilter::MotionModel { +public: + typedef typename ParticleFilter::MotionModel::particle_collection particle_collection; + + //! constructor, with default noise parameters (xvar=yvar=50, avar=0.15f) + HolonomicMotionModel() + : ParticleFilter::MotionModel(), + xvel(0), yvel(0), avel(0), prevtime(get_time()), posx (0), posy(0), posa(0), + xvar(.25), yvar(.25), avar(.25), crossAxis(.05f), crossAngle(.001f) {} + + //! constructor, with noise parameters (pass 0's to make it an "ideal" motion model) + /*! Variance parameters only come into play with updateMotion(), which is called on + * collections of particles. The other functions all return "ideal" motion calculations. */ + HolonomicMotionModel(float xVariance, float yVariance, float aVariance) + : ParticleFilter::MotionModel(), + xvel(0), yvel(0), avel(0), prevtime(get_time()), posx (0), posy(0), posa(0), + xvar(xVariance), yvar(yVariance), avar(aVariance), + crossAxis((xVariance+yVariance)/10), crossAngle(.001f) {} + + //! called by the particle filter when the current position of each particle should be updated + /*! This will reset the motion model to set the origin at the current location after the particles + * are updated, so that the next call to updateMotion() will supply the particles with the + * displacement which occurred since the last update */ + virtual void updateMotion(particle_collection& particles) { + unsigned int curt = get_time(); + if(curt==prevtime) + return; // no time has passed! + float dt = (curt - prevtime)/1000.f; + if(xvar==0 && yvar==0 && avar==0) { + // if we're using a noiseless motion model, can be a bit faster and avoid all the random number generation + computeHolonomicMotion(xvel,yvel,avel,dt, posx,posy,posa); + for(typename particle_collection::iterator it=particles.begin(); it!=particles.end(); ++it) { + float c = std::cos(it->theta); + float s = std::sin(it->theta); + it->x += posx*c - posy*s; + it->y += posx*s + posy*c; + it->theta += posa; + } + } else { + // otherwise have to do the noise generation too... + for(typename particle_collection::iterator it=particles.begin(); it!=particles.end(); ++it) { + posx=posy=posa=0; + // this factor normalizes across update rates + // (integrating many small updates otherwise yields lower variance in position than fewer large updates...) + float norm=1/std::sqrt(dt); + float xv=xvel*(1+DRanNormalZig32()*xvar*norm) + (yvel*DRanNormalZig32()*crossAxis*norm); + float yv=yvel*(1+DRanNormalZig32()*yvar*norm) + (xvel*DRanNormalZig32()*crossAxis*norm); + float av=avel*(1+DRanNormalZig32()*avar*norm) + ((xvel+yvel)*DRanNormalZig32()*crossAngle*norm); + computeHolonomicMotion(xv,yv,av,dt, posx,posy,posa); + float c = std::cos(it->theta); + float s = std::sin(it->theta); + it->x += posx*c - posy*s; + it->y += posx*s + posy*c; + it->theta += posa; + } + } + posx=posy=posa=0; + prevtime=curt; + } + + //! stores the current position into the arguments (based on get_time() vs the time the position was last set) + void getPosition(float& outx, float& outy, float& outa) const { + outx=posx; + outy=posy; + outa=posa; + float dt = (get_time() - prevtime)/1000.f; + computeHolonomicMotion(xvel,yvel,avel,dt, outx,outy,outa); + } + + //! stores the current position into the arguments (based on curtime vs the time the position was last set) + void getPosition(float& outx, float& outy, float& outa, unsigned int curtime) const { + // store position of last velocity change: + outx=posx; + outy=posy; + outa=posa; + // how much time has passed since then? + float dt = (curtime - prevtime)/1000.f; + // compute current position along path + computeHolonomicMotion(xvel,yvel,avel,dt, outx,outy,outa); + } + + //! sets the current position to the specified values and updates the timestamp to the current time + void setPosition(float x, float y, float angle) { setPosition(x,y,angle,get_time()); } + + //! sets the current position to the specified values and updates the timestamp to the specified time + void setPosition(float x, float y, float angle, unsigned int curtime) { + posx = x; + posy = y; + posa = angle; + prevtime = curtime; + } + + //! stores the current velocity into the arguments (no noise is added, this just echos the values passed to setVelocity()) + void getVelocity(float& outxv, float& outyv, float& outav) const { + outxv=xvel; + outyv=yvel; + outav=avel; + } + + //! sets the current velocity to the specified values and updates the position and timestamp to the current time + void setVelocity(float xv, float yv, float av) { setVelocity(xv,yv,av,get_time()); } + + //! sets the current velocity to the specified values and updates the position and timestamp to the specified time + void setVelocity(float xv, float yv, float av, unsigned int curtime) { + //std::cerr << "setVelocity("<select_string(section,"chain",chain); roconfig->select_int(section,"link",ip.second.link); roconfig->select_string(section,"name",ip.first); + ip.first.erase(ip.first.find_last_not_of('~')+1); // strip old-style '~' padding at end of output names for(ip.second.chain=0; ip.second.chain<(::config->motion.kinematic_chains.size()); ip.second.chain++) if(::config->motion.kinematic_chains[ip.second.chain]==chain) break; @@ -390,6 +391,7 @@ ans.Release(); return ans; } +#ifdef TGT_HAS_LEGS void Kinematics::calcLegHeights(const NEWMAT::ColumnVector& down, float heights[NumLegs]) { #ifndef THREADSAFE_KINEMATICS @@ -597,6 +599,20 @@ p.Release(); return p; } +#else // NO LEGS -- constant ground plane + +NEWMAT::ReturnMatrix +Kinematics::calculateGroundPlane() { + return calculateGroundPlane(pack(0,0,-1)); +} + +NEWMAT::ReturnMatrix +Kinematics::calculateGroundPlane(const NEWMAT::ColumnVector& /*down*/) { + return pack(0,0,1,0); // flat x-y plane through the origin +} + +#endif + NEWMAT::ReturnMatrix Kinematics::projectToPlane(unsigned int j, const NEWMAT::ColumnVector& r_j, unsigned int b, const NEWMAT::ColumnVector& p_b, diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/Kinematics.h ./Motion/Kinematics.h --- ../Tekkotsu_3.0/Motion/Kinematics.h 2006-09-16 13:32:39.000000000 -0400 +++ ./Motion/Kinematics.h 2007-11-11 18:57:23.000000000 -0500 @@ -203,6 +203,7 @@ +#ifdef TGT_HAS_LEGS //! Calculate the leg heights along a given "down" vector (0 is level with base frame) /*! This can be based on either the gravity vector from accelerometer readings, * or if that may be unreliable due to being in motion, you could do some basic @@ -216,6 +217,7 @@ * @note on Aibo platforms, if packing accelerometer readings, don't forget to negate the "left" accelerometer! * @return index of leg which is highest in reference to gravity vector */ LegOrder_t findUnusedLeg(const NEWMAT::ColumnVector& down); +#endif //! Find the ground plane by fitting a plane to the lowest 3 interest points /*! This function merely calls the other version of calculateGroundPlane with the current @@ -367,15 +369,15 @@ struct hashstring { //! hashes a string by multiplying current total by 5, add new character /*! not my idea, this is what the STL library does for char*, i've just reimplemented it for strings */ - size_t operator()(const string& s) const { + size_t operator()(const std::string& s) const { unsigned long h=0; - for(string::size_type x=s.size(); x!=0; x--) + for(std::string::size_type x=s.size(); x!=0; x--) h=h*5+s[x]; return (size_t)h; } }; //! we'll be using the hash_map to store named interest points - typedef __gnu_cxx::hash_map InterestPointMap; + typedef __gnu_cxx::hash_map InterestPointMap; //! these interest points are shared by all Kinematics classes (i.e. all PostureEngines) /*! this is to reduce initialization time, but does mean one robot can't do * kinematic calculations regarding a different model robot... */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/LedEngine.cc ./Motion/LedEngine.cc --- ../Tekkotsu_3.0/Motion/LedEngine.cc 2006-08-22 18:23:04.000000000 -0400 +++ ./Motion/LedEngine.cc 2007-11-18 01:47:03.000000000 -0500 @@ -5,35 +5,22 @@ #include "Shared/ERS220Info.h" #include "Shared/ERS7Info.h" +#ifdef TGT_HAS_LED_PANEL /*! This is "Mimic the number" style */ -const LEDBitMask_t LedEngine::ERS210numMasks[11] = { - ERS210Info::BotRLEDMask|ERS210Info::BotLLEDMask|ERS210Info::TopBrLEDMask, //0 - - ERS210Info::BotLLEDMask|ERS210Info::MidLLEDMask|ERS210Info::TopLLEDMask, //1 - - ERS210Info::BotRLEDMask|ERS210Info::BotLLEDMask|ERS210Info::TopLLEDMask|ERS210Info::TopBrLEDMask, //2 - - ERS210Info::BotRLEDMask|ERS210Info::BotLLEDMask|ERS210Info::MidRLEDMask|ERS210Info::TopLLEDMask - |ERS210Info::TopBrLEDMask, //3 - - ERS210Info::BotLLEDMask|ERS210Info::MidLLEDMask|ERS210Info::TopRLEDMask|ERS210Info::TopLLEDMask, //4 - - ERS210Info::BotRLEDMask|ERS210Info::BotLLEDMask|ERS210Info::TopRLEDMask|ERS210Info::TopBrLEDMask, //5 - - ERS210Info::BotRLEDMask|ERS210Info::BotLLEDMask|ERS210Info::MidRLEDMask|ERS210Info::MidLLEDMask - |ERS210Info::TopRLEDMask|ERS210Info::TopBrLEDMask, //6 - - ERS210Info::BotLLEDMask|ERS210Info::MidLLEDMask|ERS210Info::TopLLEDMask|ERS210Info::TopBrLEDMask, //7 - - ERS210Info::BotRLEDMask|ERS210Info::BotLLEDMask|ERS210Info::MidRLEDMask|ERS210Info::MidLLEDMask - |ERS210Info::TopRLEDMask|ERS210Info::TopLLEDMask|ERS210Info::TopBrLEDMask, //8 - - ERS210Info::BotLLEDMask|ERS210Info::MidLLEDMask|ERS210Info::TopRLEDMask|ERS210Info::TopLLEDMask - |ERS210Info::TopBrLEDMask, //9 - - ERS210Info::BotLLEDMask //. +const LEDBitMask_t LedEngine::defaultMimicNumMasks[11] = { + BotRLEDMask|BotLLEDMask|TopBrLEDMask, //0 + BotLLEDMask|MidLLEDMask|TopLLEDMask, //1 + BotRLEDMask|BotLLEDMask|TopLLEDMask|TopBrLEDMask, //2 + BotRLEDMask|BotLLEDMask|MidRLEDMask|TopLLEDMask|TopBrLEDMask, //3 + BotLLEDMask|MidLLEDMask|TopRLEDMask|TopLLEDMask, //4 + BotRLEDMask|BotLLEDMask|TopRLEDMask|TopBrLEDMask, //5 + BotRLEDMask|BotLLEDMask|MidRLEDMask|MidLLEDMask|TopRLEDMask|TopBrLEDMask, //6 + BotLLEDMask|MidLLEDMask|TopLLEDMask|TopBrLEDMask, //7 + BotRLEDMask|BotLLEDMask|MidRLEDMask|MidLLEDMask|TopRLEDMask|TopLLEDMask|TopBrLEDMask, //8 + BotLLEDMask|MidLLEDMask|TopRLEDMask|TopLLEDMask|TopBrLEDMask, //9 + BotLLEDMask //. }; -/*! This is "Count the dots" style */ +/*! This is "Count the dots" style specialized for the ERS-220 */ const LEDBitMask_t LedEngine::ERS220numMasks[11] = { ERS220Info::ModeLEDMask, //0 @@ -82,7 +69,7 @@ (ERS7Info::FaceLEDPanelMask<< 1) //. }; */ -/*! This is "Count the dots" style */ +/*! This is "Count the dots" style specialized for the ERS-7 */ const LEDBitMask_t LedEngine::ERS7numMasks[11] = { 0, //0 (ERS7Info::FaceLEDPanelMask<<11), //1 @@ -114,6 +101,22 @@ (ERS7Info::FaceLEDPanelMask<< 1) //. }; +#endif // has led panel + +/*! This is "Count the dots" style */ +const LEDBitMask_t LedEngine::defaultCountNumMasks[11] = { + (1<<0)|(1<<8), //0 + (1<<0), //1 + (1<<0)|(1<<1), //2 + (1<<0)|(1<<1)|(1<<2), //3 + (1<<0)|(1<<1)|(1<<2)|(1<<3), //4 + (1<<0)|(1<<1)|(1<<2)|(1<<3)|(1<<4), //5 + (1<<0)|(1<<1)|(1<<2)|(1<<3)|(1<<4)|(1<<5), //6 + (1<<0)|(1<<1)|(1<<2)|(1<<3)|(1<<4)|(1<<5)|(1<<6), //7 + (1<<0)|(1<<1)|(1<<2)|(1<<3)|(1<<4)|(1<<5)|(1<<6)|(1<<7), //8 + (1<<0)|(1<<1)|(1<<2)|(1<<3)|(1<<4)|(1<<5)|(1<<6)|(1<<7)|(1<<8), //9 + (1<<1)|(1<<3)|(1<<5)|(1<<7) //. +}; LedEngine::LedEngine() : dirty(true), numCycling(0), nextFlashEnd((unsigned int)-1) { @@ -144,10 +147,12 @@ int LedEngine::updateLEDs(const MotionCommand* caller, LEDBitMask_t mask/*=AllLEDMask*/) { unsigned int t = get_time(); if (t>nextFlashEnd) recalcFlashEnd(); +#ifdef TGT_HAS_LEDS for(unsigned int i=0; i>i)&1) for(unsigned int f=0; fsetOutput(caller, i+LEDOffset,calcValue(i,t+f*FrameTime),f); +#endif bool tmp=dirty; dirty = numCycling>0; return tmp; @@ -289,11 +294,13 @@ void LedEngine::displayNumber(int x, numStyle_t style) { switch(style) { case onedigit: { - const LEDBitMask_t * numMasks=ERS210numMasks; //Default to 210's mask on new models - might not have as many LEDs - WorldState * st=WorldState::getCurrent(); - if(st->robotDesign & WorldState::ERS220Mask) +#ifdef TGT_HAS_LED_PANEL + const LEDBitMask_t * numMasks=defaultCountNumMasks; + if(RobotName == ERS210Info::TargetName) + numMasks=defaultMimicNumMasks; + else if(RobotName == ERS220Info::TargetName) numMasks=ERS220numMasks; - if(st->robotDesign & WorldState::ERS7Mask) + else if(RobotName == ERS7Info::TargetName) numMasks=ERS7numMasks; if(x>9 || x<-9) { ccycle(FaceLEDMask&~TopBrLEDMask,333,10,-5); @@ -306,8 +313,25 @@ } else set(numMasks[x],1); } +#elif defined(TGT_HAS_LEDS) + if(NumLEDs<9) + return; + const LEDBitMask_t * numMasks=defaultCountNumMasks; + if(x>9 || x<-9) { + ccycle(~(1<<(NumLEDs-1)),333,10,-5); + infos[NumLEDs-1].value=x<0?1:0; + } else { + clear(); + if(x<0) { + set(numMasks[-x],1); + infos[NumLEDs-1].value=infos[NumLEDs-1].value*.5+.25; + } else + set(numMasks[x],1); + } +#endif } break; case twodigit: +#ifdef TGT_HAS_LED_PANEL if(x>99 || x<-99) { ccycle(FaceLEDMask&~TopBrLEDMask,333,10,-5); infos[TopBrLEDOffset-LEDOffset].value=x<0?1:0; @@ -317,9 +341,25 @@ infos[TopBrLEDOffset-LEDOffset].value=1; x=-x; } - setOneOfTwo(x%10,BotLLEDOffset-LEDOffset,MidLLEDOffset-LEDOffset,TopLLEDOffset-LEDOffset); setOneOfTwo(x/10,BotRLEDOffset-LEDOffset,MidRLEDOffset-LEDOffset,TopRLEDOffset-LEDOffset); + setOneOfTwo(x%10,BotLLEDOffset-LEDOffset,MidLLEDOffset-LEDOffset,TopLLEDOffset-LEDOffset); } +#elif defined(TGT_HAS_LEDS) + if(NumLEDs<3) + return; + if(x>99 || x<-99) { + ccycle(~(1<<(NumLEDs-1)),333,10,-5); + infos[NumLEDs-1].value=x<0?1:0; + } else { + clear(); + if(x<0) { + infos[NumLEDs-1].value=1; + x=-x; + } + setOneOfTwo(x/10,NumLEDs-3,NumLEDs-2,NumLEDs-1); + setOneOfTwo(x%10,2,1,0); + } +#endif break; } } @@ -328,7 +368,7 @@ return; float bg = ((x-1)/3)/3.0; float fg = bg+.333333333; - if(WorldState::getCurrent()->robotDesign & WorldState::ERS7Mask) + if(RobotName == ERS7Info::TargetName) bg*=bg; // dim the background a bit more on ERS7 switch(x%3) { case 1: @@ -351,6 +391,7 @@ void LedEngine::displayPercent(float x, percentStyle_t left_style, percentStyle_t right_style) { clear(); +#ifdef TGT_HAS_LED_PANEL if(x<0) { set(FaceLEDMask,.25); return; @@ -369,6 +410,26 @@ setColumn(x,BotLLEDMask,MidLLEDMask,TopLLEDMask,TopBrLEDMask); if(right_style==minor) setColumn(x,BotRLEDMask,MidRLEDMask,TopRLEDMask,TopBrLEDMask); +#else + if(x<0) { + set(~0,.25); + return; + } + if(x>1) { + set(~0,.75); + return; + } + if(left_style==major) + setColumn(x,3,2,1,0); + if(right_style==major) + setColumn(x,NumLEDs-4,NumLEDs-3,NumLEDs-2,NumLEDs-1); + x*=4; + x-=(int)x; + if(left_style==minor) + setColumn(x,3,2,1,0); + if(right_style==minor) + setColumn(x,NumLEDs-4,NumLEDs-3,NumLEDs-2,NumLEDs-1); +#endif } void LedEngine::setColumn(float x, unsigned int low, unsigned int mid, unsigned int high, unsigned int top) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/LedEngine.h ./Motion/LedEngine.h --- ../Tekkotsu_3.0/Motion/LedEngine.h 2006-10-03 18:30:36.000000000 -0400 +++ ./Motion/LedEngine.h 2007-11-18 01:47:03.000000000 -0500 @@ -115,16 +115,33 @@ void extendFlash(unsigned int ms); //!returns the current setting of the LED specified by @a led_id (the value you passed in set()) - float getSetting(LEDOffset_t led_id) { return infos[led_id-LEDOffset].value; } + float getSetting(LEDOffset_t led_id) { +#ifndef TGT_HAS_LEDS + (void)led_id; // avoid unused argument warning + return 0; +#else + return infos[led_id-LEDOffset].value; +#endif + } //!returns the current value of the LED specified by @a led_id (the value being expressed - may change if cycling for instance) - float getValue(LEDOffset_t led_id,unsigned int planahead=0) { return calcValue(led_id-LEDOffset,get_time()+planahead); } + float getValue(LEDOffset_t led_id,unsigned int planahead=0) { +#ifndef TGT_HAS_LEDS + (void)led_id; (void)planahead; // avoid unused argument warnings + return 0; +#else + return calcValue(led_id-LEDOffset,get_time()+planahead); +#endif + } +#ifdef TGT_HAS_LED_PANEL //!holds a series of bit masks for the onedigit style of numerical display (-9:9 and '.') /*!the hope is that these actually resemble the shapes of the numbers so people can - * recognize them more easily - without converting base 2 in their heads. */ - static const LEDBitMask_t ERS210numMasks[11]; + * recognize them more easily - without counting or converting base 2 in their heads. */ + static const LEDBitMask_t defaultMimicNumMasks[11]; static const LEDBitMask_t ERS220numMasks[11]; //!< bit masks for the ondigit style of numberical display - just count the LEDs on the head - static const LEDBitMask_t ERS7numMasks[11]; //!< writes a number on the display + static const LEDBitMask_t ERS7numMasks[11]; //!< bit masks for the ondigit style of numberical display - just count the LEDs on the head +#endif + static const LEDBitMask_t defaultCountNumMasks[11]; //!< bit masks for the ondigit style of numberical display - just count the LEDs on the head //!Use these to specify a style for displaying numbers using displayNumber() enum numStyle_t { onedigit, //!< can display a number -9 thru 9, using the current robot model's numMask. For negative numbers, blinks the top bar - fast if it's supposed to be on, slow if it would otherwise be off diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/LedMC.h ./Motion/LedMC.h --- ../Tekkotsu_3.0/Motion/LedMC.h 2006-09-19 01:40:08.000000000 -0400 +++ ./Motion/LedMC.h 2007-11-18 01:47:03.000000000 -0500 @@ -28,9 +28,11 @@ //! updates the cmds from LedEngine::updateLEDs() virtual int updateOutputs() { updateLEDFrames(cmds); +#ifdef TGT_HAS_LEDS for(unsigned int i=0; isetOutput(this,i+LEDOffset,cmds[i]); +#endif if (nextFlashEnd < (unsigned int)-1) // do we have a flash in progress? notified=false; else if (notified == false) { // flash has ended (nextFlashEnd == -1), but notice not yet sent @@ -46,10 +48,14 @@ //! Sets the JointCmd::weight of the LEDs specified by @a leds to @a weight void setWeights(LEDBitMask_t leds, float weight) { +#ifndef TGT_HAS_LEDS + (void)leds; (void)weight; // avoid unused argument warnings +#else for(unsigned int i=0; i>i)&1) for(unsigned int f=0; f @@ -13,6 +14,15 @@ } } +void MotionCommand::resetWheels() { +#ifdef TGT_HAS_WHEELS + //cout << "Resetting " << NumWheels << " wheels" << endl; + for (unsigned int i = WheelOffset; i < WheelOffset + NumWheels; i++) { + motman->setOutput(this, i, 0.0); + } +#endif +} + /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/MotionCommand.h ./Motion/MotionCommand.h --- ../Tekkotsu_3.0/Motion/MotionCommand.h 2006-10-03 23:14:56.000000000 -0400 +++ ./Motion/MotionCommand.h 2007-11-15 16:31:18.000000000 -0500 @@ -133,7 +133,7 @@ virtual void DoStart() { started=true; } //! called after this is removed from MotionManager - virtual void DoStop() { started=false; clearID(); } + virtual void DoStop() { started=false; clearID(); resetWheels(); } //! returns true if the MotionCommand is currently running (although it may be overridden by a higher priority MotionCommand) virtual bool isActive() const { return started; } @@ -162,7 +162,7 @@ * @param a first value * @param b second value * @param x weight of second value as opposed to first - * @return @f$a*(1.0-x)+b*x@f$ + * @return @f$ a*(1.0-x)+b*x @f$ * @todo - replace with a more fancy spline based thing? */ static inline double interpolate(double a, double b, double x) { return a*(1.0-x)+b*x; @@ -172,7 +172,7 @@ * @param a first value * @param b second value * @param x weight of second value as opposed to first - * @return @f$a*(1.0-x)+b*x@f$ + * @return @f$ a*(1.0-x)+b*x @f$ * @todo - replace with a more fancy spline based thing? */ static inline float interpolate(float a, float b, float x) { return a*(1.0-x)+b*x; @@ -191,6 +191,9 @@ //! calls EventTranslator::trapEvent() directly (avoids needing erouter, which is a non-shared global, causes problems with context, grr, silly OS) void postEvent(const EventBase& event); + //! This function sets all wheel values to 0 + void resetWheels(); + EventTranslator * queue; //!< send events using this, instead of posting to the erouter int autoprune; //!< default true, autoprune setting, if this is true and isAlive() returns false, MotionManager will attempt to remove the MC automatically diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/MotionManager.cc ./Motion/MotionManager.cc --- ../Tekkotsu_3.0/Motion/MotionManager.cc 2006-09-25 19:30:16.000000000 -0400 +++ ./Motion/MotionManager.cc 2007-11-15 16:33:05.000000000 -0500 @@ -14,11 +14,12 @@ #include "Shared/ERS210Info.h" #include "Shared/ERS220Info.h" #include "Shared/ERS7Info.h" +#include "Shared/Config.h" #include MotionManager * motman=NULL; -int MotionManager::_MMaccID=-1U; +int MotionManager::_MMaccID[ProcessID::NumProcesses]; EventTranslator* MotionManager::etrans=NULL; const float MotionManager::kIgnoredPriority =-1; @@ -48,13 +49,11 @@ printf("*** ERROR *** attempted to register more accessors with MotionManager than allowed by MAX_ACCESS\n"); return; } - _MMaccID=numAcc++; - // cout << "ID is now " << _MMaccID << " of " << numAcc << endl; - // cout << "_MMaccID is " << &_MMaccID << endl; - // cout << "numAcc is " << &numAcc << " from " << this << endl; - MMlock.lock(_MMaccID); + _MMaccID[ProcessID::getID()]=numAcc++; + // cout << "ID is now " << getAccID() << " of " << numAcc << endl; + MMlock.lock(getAccID()); // accRegs[accID].init(); - subjs[_MMaccID]=subj; + subjs[getAccID()]=subj; if(cmdlist.size()>0) //Shouldn't happen - busy wait in addMotion cout << "*** WARNING *** MOTIONS ADDED BEFORE ALL INITACCESSED" << endl; MMlock.unlock(); @@ -68,14 +67,12 @@ printf("*** ERROR *** attempted to register more accessors with MotionManager than allowed by MAX_ACCESS\n"); return; } - _MMaccID=numAcc++; - // cout << "ID is now " << _MMaccID << " of " << numAcc << endl; - // cout << "_MMaccID is " << &_MMaccID << endl; - // cout << "numAcc is " << &numAcc << " from " << this << endl; - MMlock.lock(_MMaccID); - subjs[_MMaccID]=&mcbufq; - mcrecvs[_MMaccID]=new MessageReceiver(*subjs[_MMaccID],receivedMsg); - procLocks[_MMaccID]=&behaviorLock; + _MMaccID[ProcessID::getID()]=numAcc++; + // cout << "ID is now " << getAccID() << " of " << numAcc << endl; + MMlock.lock(getAccID()); + subjs[getAccID()]=&mcbufq; + mcrecvs[getAccID()]=new MessageReceiver(*subjs[getAccID()],receivedMsg); + procLocks[getAccID()]=&behaviorLock; if(cmdlist.size()>0) //Shouldn't happen - busy wait in doAddMotion cout << "*** WARNING *** MOTIONS ADDED BEFORE ALL INITACCESSED" << endl; MMlock.unlock(); @@ -88,14 +85,14 @@ #ifndef PLATFORM_APERIOS //kill the message receiver before we get the motion manager lock // that way if there's a message pending, it can be processed instead of deadlocking - mcrecvs[_MMaccID]->finish(); - delete mcrecvs[_MMaccID]; - mcrecvs[_MMaccID]=NULL; + mcrecvs[getAccID()]->finish(); + delete mcrecvs[getAccID()]; + mcrecvs[getAccID()]=NULL; #endif func_begin(); for(MC_ID mc_id=cmdlist.begin(); mc_id!=cmdlist.end(); mc_id=cmdlist.next(mc_id)) { - if(cmdlist[mc_id].rcr[_MMaccID]!=NULL) { + if(cmdlist[mc_id].rcr[getAccID()]!=NULL) { MotionCommand* mc=checkoutMotion(mc_id,true); int found=0; for(unsigned int i=0; iNumberOfLocalReference(); + int refs=cmdlist[mc_id].rcr[getAccID()]->NumberOfLocalReference(); #endif if(refs>1) cout << "Warning: " << ProcessID::getIDStr() << " still had " << refs-1 << " references to motion command " << mc_id << " as it was being dropped (these are now invalid)" << endl; for(int i=0; iRemoveReference(); - cmdlist[mc_id].rcr[_MMaccID]=NULL; + cmdlist[mc_id].rcr[getAccID()]->RemoveReference(); + cmdlist[mc_id].rcr[getAccID()]=NULL; if(found==1) { MC_ID p=cmdlist.prev(mc_id); push_free(mc_id); //don't check in -- lock destructor will release the lock as the entry is destructed @@ -135,7 +132,7 @@ MC_ID mc_id=cmdlist.begin(); for(unsigned int i=0; i= NumOutputs) return; unsigned int hasWeight=NumFrames; - for(unsigned int i=NumFrames-1; i!=0; i--) + for(unsigned int i=NumFrames-1; i!=-1U; i--) if(ocmds[i].weight>0) { hasWeight=i; break; @@ -417,11 +414,17 @@ // now we've got, for each output, a list of requested values sorted by priority // summarize each output - for(uint frame=0; frame1) { + cout << get_time() << "." << frame << " " << outputNames[output] << ": "; + for(cmdstatelist_t::index_t ent=curstatelist.begin(); ent!=curstatelist.end(); ent=curstatelist.next(ent)) + cout << " (" << curstatelist[ent].frames[frame].value <<',' << curstatelist[ent].frames[frame].weight << ',' << curstatelist[ent].priority << ')'; + cout << endl; + }*/ cmdstatelist_t::index_t ent=curstatelist.begin(); while(ent!=curstatelist.end() && alpha>0) { OutputCmd curcmd; @@ -447,6 +450,9 @@ alpha*=curalpha; } } + + //if(curstatelist.size()>1) + // cout << " -> " << sumcmd.value/sumcmd.weight << ',' << sumcmd.weight << " @ " << alpha << endl; if(sumcmd.weight>0) { sumcmd.value/=sumcmd.weight; outputs[frame][output]=sumcmd.value; @@ -455,9 +461,17 @@ if(frame==NumFrames-1) cmds[output]=sumcmd; } + } for(uint output=0; outputmotion.calibration_offset[output-PIDJointOffset]) + * config->motion.calibration_scale[output-PIDJointOffset]; + } + // now summarize each output's PID values (for those which use PID control) for(uint output=PIDJointOffset; outputbuttons[LFrPawOffset]) cout << "getAngles-done." << flush; } -void -MotionManager::updateWorldState() { - //cout << "updateWorldState" << endl; - for(uint output=LEDOffset; outputoutputs[output]=cmdSums[output]; - for(uint output=BinJointOffset; outputoutputs[output]=cmdSums[output]; - - // these parts check to see if there are "fake" joints, and sets their "sensed" values - // to be the current target value, just in case a behavior is waiting for a non-existant - // non-existant joint to move to a certain position. - if(state->robotDesign & WorldState::ERS210Mask) { - for(uint output=0; outputoutputs[output]=cmdSums[output]; - } else if(state->robotDesign & WorldState::ERS220Mask) { - for(uint output=0; outputoutputs[output]=cmdSums[output]; - } else if(state->robotDesign & WorldState::ERS7Mask) { - for(uint output=0; outputoutputs[output]=cmdSums[output]; - } else - cout << "MotionManager::updateWorldState() - could not detect model" << endl; -} - /*! This function handles the conversion from the Tekkotsu format (one * regular IEEE float per parameter, to the OPEN-R format (which * takes a specialized, reduced precision floating point number) This @@ -631,7 +618,7 @@ bool MotionManager::receivedMsg(RCRegion* msg) { try { - MarkScope l(*motman->procLocks[_MMaccID]); + MarkScope l(*motman->procLocks[getAccID()]); /*MotionManagerMsg * mminfo = reinterpret_cast(msg->Base()); if(mminfo->creatorPID==ProcessID::getID()) return true; //don't process echos*/ @@ -665,27 +652,27 @@ } switch(mminfo->type) { case MotionManagerMsg::addMotion: { - if(cmdlist[mc_id].rcr[_MMaccID]==NULL) { + if(cmdlist[mc_id].rcr[getAccID()]==NULL) { //cout << "receiveMotion()NOW: rcr->NumberOfReference()==" << rcr->NumberOfReference() << endl; - cmdlist[mc_id].rcr[_MMaccID]=rcr; + cmdlist[mc_id].rcr[getAccID()]=rcr; //cout << "receiveMotion(): rcr->NumberOfReference()==" << rcr->NumberOfReference() << endl; rcr->AddReference(); //should be able to do a nice dynamic cast instead of a static one // but it gives NULL for some reason - i blame having to do the fork trick //cout << "Adding mc_id=="<< mc_id << " (and dynamic_cast is still " << dynamic_cast(mminfo) << ")" << endl; - cmdlist[mc_id].baseaddrs[_MMaccID]=static_cast(mminfo); + cmdlist[mc_id].baseaddrs[getAccID()]=static_cast(mminfo); } else { #ifdef PLATFORM_APERIOS // this shouldn't happen on Aperios (no echos), but is normal elsewhere cerr << "WARNING: MotionManager::processMsg addMotion for motion which was already added!" << endl; #else - ASSERT(cmdlist[mc_id].lastAccessor==(accID_t)-1 || cmdlist[mc_id].baseaddrs[_MMaccID]==static_cast(mminfo),"Baseaddr changed!"); + ASSERT(cmdlist[mc_id].lastAccessor==(accID_t)-1 || cmdlist[mc_id].baseaddrs[getAccID()]==static_cast(mminfo),"Baseaddr changed!"); #endif } if(ProcessID::getID()==ProcessID::MotionProcess && cmdlist[mc_id].lastAccessor!=(accID_t)-1) { checkoutMotion(mc_id,true); try { - cmdlist[mc_id].baseaddrs[_MMaccID]->DoStart(); + cmdlist[mc_id].baseaddrs[getAccID()]->DoStart(); } catch(const std::exception& ex) { ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionCommand DoStart()",&ex); } catch(...) { @@ -695,10 +682,10 @@ } } break; case MotionManagerMsg::deleteMotion: { - //cout << "deleteMotion(): cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference()==" << cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference() << endl; + //cout << "deleteMotion(): cmdlist[mc_id].rcr[getAccID()]->NumberOfReference()==" << cmdlist[mc_id].rcr[getAccID()]->NumberOfReference() << endl; //cout << "deleting mc_id=="<creatorPID!=ProcessID::getID()) { @@ -709,7 +696,7 @@ } #endif } else { - cmdlist[mc_id].lock.lock(_MMaccID); + cmdlist[mc_id].lock.lock(getAccID()); int found=0; for(unsigned int i=0; iRemoveReference(); - cmdlist[mc_id].rcr[_MMaccID]=NULL; - cmdlist[mc_id].baseaddrs[_MMaccID]=NULL; + cmdlist[mc_id].rcr[getAccID()]->RemoveReference(); + cmdlist[mc_id].rcr[getAccID()]=NULL; + cmdlist[mc_id].baseaddrs[getAccID()]=NULL; if(found==1) { push_free(mc_id); //don't unlock -- lock destructor will release the lock as the entry is destructed } else { @@ -745,7 +732,7 @@ } } } - //cout << "deleteMotion()NOW: cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference()==" << cmdlist[mc_id].rcr[_MMaccID]->NumberOfReference() << endl; + //cout << "deleteMotion()NOW: cmdlist[mc_id].rcr[getAccID()]->NumberOfReference()==" << cmdlist[mc_id].rcr[getAccID()]->NumberOfReference() << endl; } break; default: printf("*** WARNING *** unknown MotionManager msg type received\n"); @@ -761,7 +748,7 @@ * what that true/false was controlling. */ MotionManager::MC_ID MotionManager::doAddMotion(const SharedObjectBase& sm, bool autoprune, float priority) { - MotionCommand * mc = dynamic_cast(reinterpret_cast(sm.data())); + MotionCommand * mc = dynamic_cast(static_cast(sm.data())); if(mc==NULL) { cout << "MotionManager::addMotion() - SharedObject does not seem to hold a MotionCommand" << endl; return invalid_MC_ID; @@ -773,7 +760,7 @@ //cout << cmdlist.size() << " exist..." << endl; // cout << id << "..." << flush; for(MC_ID it=cmdlist.begin(); it!=cmdlist.end(); it=cmdlist.next(it)) { - if(cmdlist[it].baseaddrs[_MMaccID]==mc) { + if(cmdlist[it].baseaddrs[getAccID()]==mc) { cerr << "Warning: adding motion command at " << mc << ", is already running in motion manager as MC_ID " << it << endl; return func_end(it); } @@ -786,12 +773,12 @@ } //cout << "setAdd(" << mc_id << ")" << endl; mc->setAdd(mc_id); - cmdlist[mc_id].baseaddrs[_MMaccID]=mc; - cmdlist[mc_id].rcr[_MMaccID]=sm.getRegion(); + cmdlist[mc_id].baseaddrs[getAccID()]=mc; + cmdlist[mc_id].rcr[getAccID()]=sm.getRegion(); //cout << "addMotion(): sm.getRegion()->NumberOfReference()==" << sm.getRegion()->NumberOfReference() << endl; - cmdlist[mc_id].rcr[_MMaccID]->AddReference(); + cmdlist[mc_id].rcr[getAccID()]->AddReference(); //cout << "addMotion()NOW: sm.getRegion()->NumberOfReference()==" << sm.getRegion()->NumberOfReference() << endl; - cmdlist[mc_id].lastAccessor=_MMaccID; + cmdlist[mc_id].lastAccessor=getAccID(); cmdlist[mc_id].priority=priority; try { erouter->postEvent(EventBase::motmanEGID,mc_id,EventBase::activateETID,0); @@ -805,20 +792,20 @@ OStatus err; /*{ unsigned int i=0; - for(ObserverConstIterator it=subjs[_MMaccID]->begin();it!=subjs[_MMaccID]->end();it++) { - cout << "RemainBuffer("<RemainBuffer(*it) << endl; + for(ObserverConstIterator it=subjs[getAccID()]->begin();it!=subjs[getAccID()]->end();it++) { + cout << "RemainBuffer("<RemainBuffer(*it) << endl; } - ASSERT((int)i==subjs[_MMaccID]->NumberOfObservers(),"did I miss an observer?"); + ASSERT((int)i==subjs[getAccID()]->NumberOfObservers(),"did I miss an observer?"); }*/ //cout << "Sent at " << get_time() << flush; - err=subjs[_MMaccID]->SetData(sm.getRegion()); + err=subjs[getAccID()]->SetData(sm.getRegion()); ASSERT(err==oSUCCESS,"*** ERROR MotionManager: SetData returned " << err); //cout << "addMotion()afterSetData: sm.getRegion()->NumberOfReference()==" << sm.getRegion()->NumberOfReference() << endl; - err=subjs[_MMaccID]->NotifyObservers(); + err=subjs[getAccID()]->NotifyObservers(); ASSERT(err==oSUCCESS,"*** ERROR MotionManager: NotifyObservers returned " << err); #else //PLATFORM_LOCAL try { - subjs[_MMaccID]->sendMessage(sm.getRegion()); + subjs[getAccID()]->sendMessage(sm.getRegion()); } catch(const std::exception& ex) { ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during message sending",&ex); } catch(...) { @@ -834,17 +821,23 @@ MotionManager::checkoutMotion(MC_ID mcid,bool block) { //cout << "checkout..." << flush; if(mcid>=MAX_MOTIONS || mcid==invalid_MC_ID) { - cout << "*** WARNING *** " << ProcessID::getIDStr() << " tried to access invalid mcid " << mcid << endl; + cout << "*** ERROR *** " << ProcessID::getIDStr() << " tried to access invalid mcid " << mcid << endl; + stacktrace::displayCurrentStackTrace(); + return NULL; + } + if(cmdlist[mcid].lastAccessor==(accID_t)-1) { // test both before and after the block + cout << "*** WARNING *** " << ProcessID::getIDStr() << " tried to access dead mcid " << mcid << endl; stacktrace::displayCurrentStackTrace(); return NULL; } + // block would lock up if the motion is dead in the simulator (left in a locked state) if(block) - cmdlist[mcid].lock.lock(_MMaccID); + cmdlist[mcid].lock.lock(getAccID()); else - if(!cmdlist[mcid].lock.try_lock(_MMaccID)) + if(!cmdlist[mcid].lock.try_lock(getAccID())) return NULL; - if(cmdlist[mcid].lastAccessor==(accID_t)-1) { - cout << "*** WARNING *** " << ProcessID::getIDStr() << " tried to access dead mcid " << mcid << endl; + if(cmdlist[mcid].lastAccessor==(accID_t)-1) { // test both before and after the block + cout << "*** WARNING *** " << ProcessID::getIDStr() << " tried to access mcid as it was removed " << mcid << endl; stacktrace::displayCurrentStackTrace(); cmdlist[mcid].lock.unlock(); return NULL; @@ -856,14 +849,14 @@ MotionCommand * MotionManager::convertMotion(MC_ID mc) { - MotionCommand * base = cmdlist[mc].baseaddrs[_MMaccID]; + MotionCommand * base = cmdlist[mc].baseaddrs[getAccID()]; // cout << "base=" << base << "..." << flush; - if(cmdlist[mc].lastAccessor!=_MMaccID) { + if(cmdlist[mc].lastAccessor!=getAccID()) { //cout << "converting from " << MCRegistrar::getRaw(base) << "..." << flush; //cout << "prev=" << accRegs[cmdlist[mcid].lastAccessor].getReg(base) << "..." << flush; // accRegs[id].convert(base); //cout << "to=" << MCRegistrar::getRaw(base) << ", " << accRegs[cmdlist[mcid].lastAccessor].getReg(base) << endl; - cmdlist[mc].lastAccessor=_MMaccID; + cmdlist[mc].lastAccessor=getAccID(); } base->setTranslator(etrans); #ifdef PLATFORM_APERIOS @@ -876,8 +869,8 @@ MotionManager::checkinMotion(MC_ID mcid) { if(mcid>=MAX_MOTIONS || mcid==invalid_MC_ID) return; - if(cmdlist[mcid].lock.get_lock_level()==1 && cmdlist[mcid].rcr[_MMaccID]!=NULL) { //about to release last lock (and region hasn't been removed) - MotionCommand * base = cmdlist[mcid].baseaddrs[_MMaccID]; + if(cmdlist[mcid].lock.get_lock_level()==1 && cmdlist[mcid].rcr[getAccID()]!=NULL) { //about to release last lock (and region hasn't been removed) + MotionCommand * base = cmdlist[mcid].baseaddrs[getAccID()]; base->setTranslator(NULL); #ifdef PLATFORM_APERIOS base->setWorldState(NULL); @@ -897,13 +890,13 @@ func_end(); return; } - if(cmdlist[mcid].rcr[_MMaccID]==NULL) { + if(cmdlist[mcid].rcr[getAccID()]==NULL) { cout << "WARNING: removeMotion called for a NULL motion! mc_id="<SetData(&dmsg,sizeof(dmsg)); - subjs[_MMaccID]->NotifyObservers(); + subjs[getAccID()]->SetData(&dmsg,sizeof(dmsg)); + subjs[getAccID()]->NotifyObservers(); #else //PLATFORM_LOCAL // local will "echo" the message, so we'll do the actual remove when we get the echo SharedObject dmsg; dmsg->setDelete(mcid); //cout << "Remove at " << get_time() << flush; try { - subjs[_MMaccID]->sendMessage(dmsg.getRegion()); + subjs[getAccID()]->sendMessage(dmsg.getRegion()); } catch(const std::exception& ex) { ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during message sending",&ex); } catch(...) { @@ -998,7 +991,7 @@ MotionManager::skip_ahead(MC_ID mcid) const { // this is in case a new motion has been added, but the current // process hasn't received its own copy yet, so should skip over them - while(mcid!=cmdlist.end() && cmdlist[mcid].rcr[_MMaccID]==NULL) + while(mcid!=cmdlist.end() && cmdlist[mcid].rcr[getAccID()]==NULL) mcid=cmdlist.next(mcid); return mcid; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/MotionManager.h ./Motion/MotionManager.h --- ../Tekkotsu_3.0/Motion/MotionManager.h 2006-10-03 18:28:15.000000000 -0400 +++ ./Motion/MotionManager.h 2007-11-10 17:58:09.000000000 -0500 @@ -46,6 +46,11 @@ * MC_ID id = motman->addPersistentMotion( SharedObject([arg1,...]) [, priority ] ); * // then later: motman->removeMotion(id); * @endcode + * + * The priority level can be changed later via setPriority(), and there are + * symbolic values defined in #kIgnoredPriority through #kEmergencyPriority + * to give some common guidelines on the magnitudes to use. The default + * priority level if unspecified is #kStdPriority. * * If you want to do some more initializations not handled by the MotionCommand's * constructor (the @p arg1, @p arg2, ... params) then you would @@ -119,8 +124,8 @@ void setOutput(const MotionCommand* caller, unsigned int output, const OutputCmd& cmd, const OutputPID& pid); //!< @b LOCKS @b MotionManager Requests a value and PID be set for the specified output void setOutput(const MotionCommand* caller, unsigned int output, const OutputCmd cmd[NumFrames], const OutputPID& pid); //!< @b LOCKS @b MotionManager Requests a value and PID be set for the specified output const OutputCmd& getOutputCmd(unsigned int output) const { return cmds[output]; } //!< Returns the value of the output last sent to the OS. Note that this will differ from the sensed value in state, even when staying still. There is no corresponding getOutputPID because this value *will* duplicate the value in state. - void setPriority(MC_ID mcid, float p) { cmdlist[mcid].priority=p; }//!< sets the priority level of a MotionCommand - float getPriority(MC_ID mcid) const { return cmdlist[mcid].priority; } //!< returns priority level of a MotionCommand + void setPriority(MC_ID mcid, float p) { cmdlist[mcid].priority=p; }//!< sets the priority level of a MotionCommand, symbolic values are available to give some guidelines -- see #kIgnoredPriority through #kEmergencyPriority + float getPriority(MC_ID mcid) const { return cmdlist[mcid].priority; } //!< returns priority level of a MotionCommand, symbolic values are available to give some guidelines -- see #kIgnoredPriority through #kEmergencyPriority //@} //@{ @@ -134,9 +139,9 @@ //!@name MotionCommand "Risky" MotionCommand * checkoutMotion(MC_ID mcid,bool block=true); //!< locks the command and possibly performs RTTI conversion; supports recursive calls void checkinMotion(MC_ID mcid); //!< marks a MotionCommand as unused - MotionCommand * peekMotion(MC_ID mcid) { return mcid==invalid_MC_ID?NULL:cmdlist[mcid].baseaddrs[_MMaccID]; } //!< allows access to a MotionCommand without checking it out; warning @b never call a function based on this, only access member fields through it + MotionCommand * peekMotion(MC_ID mcid) { return mcid==invalid_MC_ID?NULL:cmdlist[mcid].baseaddrs[getAccID()]; } //!< allows access to a MotionCommand without checking it out; warning @b never call a function based on this, only access member fields through it unsigned int checkoutLevel(MC_ID mcid) { return mcid==invalid_MC_ID?0:cmdlist[mcid].lock.get_lock_level(); } //!< returns the number of times @a mcid has been checked out minus the times it's been checked in - bool isOwner(MC_ID mcid) { return mcid==invalid_MC_ID?false:(cmdlist[mcid].lock.owner()==_MMaccID); } + bool isOwner(MC_ID mcid) { return mcid==invalid_MC_ID?false:(cmdlist[mcid].lock.owner()==getAccID()); } //@} //!@name MotionCommand Unsafe @@ -149,14 +154,13 @@ //@} //@{ - void lock() { MMlock.lock(_MMaccID); } //!< gets an exclusive lock on MotionManager - functions marked @b LOCKS @b MotionManager will cause (and require) this to happen automatically - bool trylock() { return MMlock.try_lock(_MMaccID); } //!< tries to get a lock without blocking + void lock() { MMlock.lock(getAccID()); } //!< gets an exclusive lock on MotionManager - functions marked @b LOCKS @b MotionManager will cause (and require) this to happen automatically + bool trylock() { return MMlock.try_lock(getAccID()); } //!< tries to get a lock without blocking void unlock() { MMlock.unlock(); } //!< releases a lock on the motion manager //@} //@{ void getOutputs(float outputs[][NumOutputs]); //!< @b LOCKS @b MotionManager called by MotionObject to fill in the output values for the next ::NumFrames frames (only MotoObj should call this...) - void updateWorldState(); //!< call this when you want MotionManager to set the WorldState to reflect what things should be for unsensed outputs (LEDs, ears) (only MotoObj should be calling this...) #ifdef PLATFORM_APERIOS bool updatePIDs(OPrimitiveID primIDs[NumOutputs]); //!< call this when you want MotionManager to update modified PID values, returns true if changes made (only MotoObj should be calling this...), see PIDMC for general PID documentation #else @@ -206,7 +210,7 @@ typedef unsigned short accID_t; //!< type to use to refer to accessors of MotionManager (or its locks) - void func_begin() { MMlock.lock(_MMaccID); } //!< called at the begining of many functions to lock MotionManager + void func_begin() { MMlock.lock(getAccID()); } //!< called at the begining of many functions to lock MotionManager void func_end() { MMlock.unlock(); } //!< called at the end of a function which called func_begin() to release it template T func_end(T val) { func_end(); return val; } //!< same as func_end(), except passes return value through @@ -250,11 +254,12 @@ #else //PLATFORM_LOCAL //!Storage of each process's attachment of the message queue, used to internally transmit sound buffers to SoundPlay MessageQueueBase * subjs[MAX_ACCESS]; - MessageReceiver * mcrecvs[MAX_ACCESS]; - Resource* procLocks[MAX_ACCESS]; + MessageReceiver * mcrecvs[MAX_ACCESS]; //!< message receivers which watch for incoming motion command regions, or requests to free them + Resource* procLocks[MAX_ACCESS]; //!< pointers to per-process thread locks, acquired during message processing from one of #mcrecvs #endif - static int _MMaccID; //!motion.makePath(filename).c_str()); } +/*! @deprecated use radians instead (we don't have a good way to know which output values are angles, and which are 'other', e.g. wheel velocities or LED brightness...) */ +void MotionSequenceEngine::setSaveDegrees() { loadSaveMode=M_PI/180; } + void MotionSequenceEngine::setTime(unsigned int x) { playtime=x; WorldState * st=WorldState::getCurrent(); @@ -365,10 +369,6 @@ setOutputCmd(i,pose.getOutputCmd(i)); } -void MotionSequenceEngine::overlayPose(const PostureEngine& pose) { - setPose(pose); -} - PostureEngine MotionSequenceEngine::getPose() { PostureEngine pose; getPose(pose); @@ -569,18 +569,21 @@ } unsigned int MotionSequenceEngine::getOutputIndex(const char name[], unsigned int idx) { + unsigned int n=strlen(name); + while(name[n-1]=='~') + --n; if(idxoutputname value [weight]' - sets the specified output to the value - assumes 1 for weight; you can view the list of valid joint names in the outputNames array within the RobotInfo extension namespace for your model. (e.g. ERS210Info::outputNames[]) * - 'load filename' - file can be a posture or another motion sequence (if MS, leaves playhead at end of the motion sequence); see setPose() and overlayMotion() * - 'loadExplicit filename' - file must be a posture, sets position for all outputs, including zero-weighted ones; see setExplicitPose() - * - 'degrees' - all following values will be interpreted as degrees [default] - * - 'radians' - all following values will be interpreted as radians * - '#comment' - a comment line * - Last line: '\#END' * @@ -60,21 +59,20 @@ * Example 1: This motion sequence will straighten out the head, panning from right to left.\n
 \#MSq 
-degrees 
 
 \# Straighten head
 advanceTime  50 
-NECK:tilt       15 
+NECK:tilt       0.262
 NECK:nod       0 
 
 \# Pan right
 advanceTime  850 
-NECK:pan~       -45 
+NECK:pan~       -0.785 
 
 \# Pan left
 advanceTime  900 
-NECK:pan~       45 
-NECK:tilt       15 
+NECK:pan~       0.785 
+NECK:tilt       0.262 
 NECK:nod       0 
 
 \#END
@@ -92,7 +90,6 @@
  *  head left to right, and @e then pan the tail left to right.\n
 
 \#MSq
-degrees
 
 \# Bring head and tail to neural positions
 advanceTime 50
@@ -103,10 +100,10 @@
 
 \# Pan left
 advanceTime 1000
-NECK:pan~ 90
+NECK:pan~ 1.571
 \# Pan right
 advanceTime 1000
-NECK:pan~ -90
+NECK:pan~ -1.571
 
 \# Center head
 \# Update tail time index
@@ -117,10 +114,10 @@
 
 \# Wag left
 advanceTime 500
-TAIL:pan~ 90
+TAIL:pan~ 1.571
 \# Wag right
 advanceTime 500
-TAIL:pan~ -90
+TAIL:pan~ -1.571
 
 \#END 
 
@@ -198,7 +195,8 @@ virtual unsigned int saveBuffer(char buf[], unsigned int len) const; //!< inherited, saves the motion sequence - will save a flat file - doesn't remember references to other files which were loaded virtual unsigned int loadFile(const char filename[]); //!< inherited, doesn't clear before loading - call clear yourself if you want to reset, otherwise it will overlay. Leaves playtime at end of load. virtual unsigned int saveFile(const char filename[]) const; //!< inherited, saves the motion sequence - will save a flat file - doesn't remember references to other files which were loaded - void setSaveDegrees() { loadSaveMode=M_PI/180; } //!< will store angles as degrees on future saves + //! deprecated, use radians instead; calling this will store angles as degrees on future saves + void setSaveDegrees() ATTR_deprecated; bool isSaveDegrees() const { return loadSaveMode!=1; } //!< returns true if will store angles as degrees on future saves void setSaveRadians() { loadSaveMode=1; } //!< will store angles as radians on future saves bool isSaveRadians() const { return loadSaveMode==1; } //!< returns true if will store angles as degrees on future saves @@ -214,7 +212,6 @@ void setExplicitPose(const PostureEngine& pose); //!< calls setOutputCmd on each of the OutputCmds in @a pose, even if they are zero-weight (can be used to fade joints in/out with other conflicting motions) PostureEngine getPose(); //!< returns the set of OutputCmd's at the current playhead as a PostureEngine void getPose(PostureEngine& pose); //!< stores the set of OutputCmd's at the current playhead into the specified PostureEngine - void overlayPose(const PostureEngine& pose) __attribute__((__deprecated__)); //!< deprecated, use setPose instead (what setPose used to do is now setExplicitPose) unsigned int overlayMotion(const std::string& msFile); //!< loads @a msFile from disk and calls overlayMotion(const MotionSequenceEngine&) with it, returns the duration of @a msFile (0 if there was an error) void overlayMotion(const MotionSequenceEngine& ms); //!< applies each keyframe of @a ms to this, leaves playhead at the end (in other words, advances playhead to end of @a ms) void compress(); //!< compresses the sequence by eliminating sequences of moves which are identical diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/OldHeadPointerMC.cc ./Motion/OldHeadPointerMC.cc --- ../Tekkotsu_3.0/Motion/OldHeadPointerMC.cc 2004-10-14 16:23:50.000000000 -0400 +++ ./Motion/OldHeadPointerMC.cc 1969-12-31 19:00:00.000000000 -0500 @@ -1,185 +0,0 @@ -#include "OldHeadPointerMC.h" -#include "Shared/debuget.h" -#include "Shared/WorldState.h" -#include "MotionManager.h" -#include -#include "Shared/Config.h" - -OldHeadPointerMC::OldHeadPointerMC() : - MotionCommand(), dirty(true), active(true), targetReached(false) { - setWeight(1); - defaultMaxSpeed(); - for(unsigned int i=0; ioutputs[HeadOffset+i]; - } -} - -void OldHeadPointerMC::setJoints(double tilt, double pan, double roll) { - setJointValue(TiltOffset,tilt); - setJointValue(PanOffset,pan); - setJointValue(RollOffset,roll); -} - -void OldHeadPointerMC::setWeight(double w) { - for(unsigned int x=0; xmotion.max_head_tilt_speed*FrameTime/1000; - maxSpeed[PanOffset]=config->motion.max_head_pan_speed*FrameTime/1000; - maxSpeed[RollOffset]=config->motion.max_head_roll_speed*FrameTime/1000; -} - -void OldHeadPointerMC::setMode(CoordFrame_t m, bool conv) { - for(unsigned int x=0; xsetOutput(this,i+HeadOffset,headCmds[i]); - } else { // we may be trying to exceeded maxSpeed - unsigned int f=0; - while(value>headCmds[i].value+maxSpeed[i] && fsetOutput(this,i+HeadOffset,headCmds[i],f); - f++; - } - while(valuesetOutput(this,i+HeadOffset,headCmds[i],f); - f++; - } - if(fsetOutput(this,i+HeadOffset,headCmds[i],f); - } else // we didn't reach target value, still dirty - dirty=true; - } - } - float dist=0; - for(unsigned int i=0; ioutputs[HeadOffset+i]-headTargets[i]); - dist+=diff*diff; - } - if(dist<0.05*0.05 && !targetReached) { - postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID)); - targetReached=true; - } - } - return tmp; -} - -const OutputCmd& OldHeadPointerMC::getOutputCmd(unsigned int i) { - i-=HeadOffset; - if(isensors[BAccelOffset]; - double lacc=state->sensors[LAccelOffset]; - double dacc=state->sensors[DAccelOffset]; - switch(i) { - case TiltOffset: - return v+atan2(bacc,sqrt(dacc*dacc+lacc*lacc)); - case PanOffset: - return v; - case RollOffset: //==NodOffset - if(state->robotDesign&WorldState::ERS7Mask) { - float pans=sin(state->outputs[HeadOffset+PanOffset]); - float panc=cos(state->outputs[HeadOffset+PanOffset]); - float ans=v; - ans+=atan2(bacc*panc-lacc*pans,sqrt(dacc*dacc+lacc*lacc*panc*panc+bacc*bacc*pans*pans)); - ans-=panc*state->outputs[HeadOffset+TiltOffset]; - return ans; - } else - return v+atan2(-lacc,sqrt(dacc*dacc+bacc*bacc)); - default: - ASSERT(false,"Passed bad offset "<sensors[BAccelOffset]; - double lacc=state->sensors[LAccelOffset]; - double dacc=state->sensors[DAccelOffset]; - switch(i) { - case TiltOffset: - return v-atan2(bacc,sqrt(dacc*dacc+lacc*lacc)); - case PanOffset: - return v; - case RollOffset: //==NodOffset - if(state->robotDesign&WorldState::ERS7Mask) { - float pans=sin(state->outputs[HeadOffset+PanOffset]); - float panc=cos(state->outputs[HeadOffset+PanOffset]); - float ans=v; - ans-=atan2(bacc*panc-lacc*pans,sqrt(dacc*dacc+lacc*lacc*panc*panc+bacc*bacc*pans*pans)); - ans+=panc*state->outputs[HeadOffset+TiltOffset]; - return ans; - } else - return v-atan2(-lacc,sqrt(dacc*dacc+bacc*bacc)); - default: - ASSERT(false,"Passed bad offset "<max) { - float mn_dist=fabs(normalizeAngle(min-x)); - float mx_dist=fabs(normalizeAngle(max-x)); - if(mn_distERS7Info::outputRanges[ERS7Info::HeadOffset+PanOffset][MaxRange] + if(angles[1]outputRanges[HeadOffset+PanOffset][MaxRange] ) { double elv=-atan2(target.x,target.z); - elv=bound(elv,ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MinRange],ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MaxRange]); + elv=bound(elv,outputRanges[HeadOffset+TiltOffset][MinRange],outputRanges[HeadOffset+TiltOffset][MaxRange]); angles[0]=elv; if(!getNodAndPan(angles,target)) return; @@ -433,31 +433,31 @@ // y = ( A^2*h % sqrt(B^2*(A^4+B^2*r^2+A^2*(B^2-h^2+r^2))) ) / (A^2+B^2) // (2 solutions) - if(angles[2]ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MaxRange] + if(angles[2]outputRanges[HeadOffset+NodOffset][MaxRange] ) { double nod; - if(angles[2]ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MaxRange]) - angles[0]=ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MaxRange]; + if(angles[0]outputRanges[HeadOffset+TiltOffset][MaxRange]) + angles[0]=outputRanges[HeadOffset+TiltOffset][MaxRange]; getNodAndPan(angles,target); //sout->printf("rad=%g slope=%g intcpt=%g A=%g B=%g yval=%g tilt=%g\n",rad,slope,intcpt,A,B,yval,angles[0]); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/OutputCmd.h ./Motion/OutputCmd.h --- ../Tekkotsu_3.0/Motion/OutputCmd.h 2003-09-07 18:14:01.000000000 -0400 +++ ./Motion/OutputCmd.h 2007-11-15 00:32:52.000000000 -0500 @@ -7,9 +7,14 @@ public: OutputCmd() : value(0), weight(0) {} //!< Constructor - OutputCmd(float v) : value(v), weight(1) {} //!< Constructor + OutputCmd(float v) : value(v), weight(1) {} //!< Constructor (provides implicit conversion from float) OutputCmd(float v, float w) : value(v), weight(w) {} //!< Constructor OutputCmd(const OutputCmd& a, const OutputCmd& b, float w) : value(a.value*w+b.value*(1-w)), weight(a.weight*w+b.value*(1-w)) {} //!< Constructor, see set(a,b,w) + + //! assignment from another OutputCmd (just copy everything, straightforward) + OutputCmd& operator=(const OutputCmd& oc) { value=oc.value; weight=oc.weight; return *this; } + //! assignment from a float, set weight to 1 + OutputCmd& operator=(float v) { value=v; weight=1; return *this; } inline void set(float v, float w=1) { value=v; weight=w; } //!< sets the value to @a v and weight to @a w inline void set(const OutputCmd& a, const OutputCmd& b, float w) { value=a.value*w+b.value*(1-w); weight=a.weight*w+b.weight*(1-w); } //!< sets the value to a weighted average of @a a and @a b (higher @a w, more @a a) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/PIDMC.h ./Motion/PIDMC.h --- ../Tekkotsu_3.0/Motion/PIDMC.h 2004-12-20 19:42:21.000000000 -0500 +++ ./Motion/PIDMC.h 2006-10-30 15:21:50.000000000 -0500 @@ -49,7 +49,13 @@ PIDMC(float powerlevel, float w=1) : MotionCommand(), dirty(false) { setAllPowerLevel(powerlevel,w); } - //!Constructor, sets general power level of a range of joints, uses default and 0 weight for others + //!Constructor, sets general power level of a range of joints, uses default and 0 weight for others, see setRangePowerLevel() + /*! @param low the first joint to apply @a powerlevel to + * @param high one-past last joint to apply @a powerlevel to (i.e. exclusive upper limit) + * @param powerlevel scaling factor for all of the default PID parameters + * @param w MotionManager weight for averaging conflicting commands + * + * Note that if you want to set a single joint @e i, then @a low = @e i, and @a high = @e i + 1 because high is an exclusive upper limit*/ PIDMC(unsigned int low, unsigned int high, float powerlevel, float w=1) : MotionCommand(), dirty(false) { setRangePowerLevel(PIDJointOffset,low,1.f,0.f); setRangePowerLevel(low,high,powerlevel,w); @@ -95,6 +101,13 @@ } //!Sets a range of joints' PIDs to a given power level and weight + /*! @param low the first joint to apply power level @a p to + * @param high one-past last joint to apply power level @a p to (i.e. exclusive upper limit) + * @param p scaling factor for all of the default PID parameters + * @param w MotionManager weight for averaging conflicting commands + * + * Note that if you want to set a single joint @e i with this function (as opposed to setJointPowerLevel() which is designed for that...) + * then you would need to pass @a low = @e i, and @a high = @e i + 1 because high is an exclusive upper limit*/ void setRangePowerLevel(unsigned int low, unsigned int high, float p, float w=1) { low-=PIDJointOffset; high-=PIDJointOffset; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/PostureEngine.cc ./Motion/PostureEngine.cc --- ../Tekkotsu_3.0/Motion/PostureEngine.cc 2006-09-09 00:32:55.000000000 -0400 +++ ./Motion/PostureEngine.cc 2007-11-11 18:57:23.000000000 -0500 @@ -2,8 +2,13 @@ #include "Shared/WorldState.h" #include "Motion/roboop/robot.h" #include "Shared/Config.h" +#include "Shared/string_util.h" #include #include +#include +#include + +using namespace std; PostureEngine::~PostureEngine() {} @@ -47,13 +52,13 @@ return tmp.setUnderlay(pe); } /*! joints being averaged with unused joints have their weights averaged, but not their values (so an output can crossfade properly)\n - * @param pe the other PostureEngine - * @param w amount to weight towards @a pe - * - if @a w < .001, nothing is done - * - if @a w > .999, a straight copy of @a pe occurs (sets joints to unused properly at end of fade) - * - .001 and .999 is used instead of 0 and 1 to allow for slight addition errors in a loop (if - * using repeated additions of a delta value instead of repeated divisions) - * @return @c *this, stores results into this */ + * @param pe the other PostureEngine + * @param w amount to weight towards @a pe + * - if @a w < .001, nothing is done + * - if @a w > .999, a straight copy of @a pe occurs (sets joints to unused properly at end of fade) + * - .001 and .999 is used instead of 0 and 1 to allow for slight addition errors in a loop (if + * using repeated additions of a delta value instead of repeated divisions) + * @return @c *this, stores results into this */ PostureEngine& PostureEngine::setAverage(const PostureEngine& pe, float w) { if(w<0.001) return *this; @@ -71,13 +76,13 @@ return *this; } /*! joints being averaged with weight<=0 have their weights averaged, but not their values (so an output can crossfade properly)\n - * @param pe the other PostureEngine - * @param w amount to weight towards @a pe - * - if @a w < .001, nothing is done - * - if @a w > .999, a straight copy of @a pe occurs (sets joints to unused properly at end of fade) - * - .001 and .999 is used instead of 0 and 1 to allow for slight addition errors in a loop (if - * using repeated additions of a delta value instead of repeated divisions) - * @return a new posture containing the results */ + * @param pe the other PostureEngine + * @param w amount to weight towards @a pe + * - if @a w < .001, nothing is done + * - if @a w > .999, a straight copy of @a pe occurs (sets joints to unused properly at end of fade) + * - .001 and .999 is used instead of 0 and 1 to allow for slight addition errors in a loop (if + * using repeated additions of a delta value instead of repeated divisions) + * @return a new posture containing the results */ PostureEngine PostureEngine::createAverage(const PostureEngine& pe, float w) const { PostureEngine tmp(*this); return tmp.setAverage(pe,w); @@ -137,7 +142,11 @@ const unsigned int len=0; char buf[len]; if(saveFormatCondensed) { +#ifndef PLATFORM_APERIOS written+=snprintf(buf,len,"condensed %s\n",RobotName); +#else + written+=snprintf(buf,len,"condensed %s\n",RobotName.c_str()); +#endif if(loadSaveSensors!=NULL) written+=snprintf(buf,len,"meta-info = %u %u\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber); bool weightsAllEqual=true; @@ -174,23 +183,26 @@ } } else { if(loadSaveSensors!=NULL) - written+=snprintf(buf,len,"\n timestamp\t%u\n framenumber\t%u\n\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber); + written+=snprintf(buf,len,"\n timestamp\t%u\n framenumber\t%u\n\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber); for(unsigned int i=0; i0) { - written+=snprintf(buf,len,"%s\t% .4f\t% .4f\n",outputNames[i],cmds[i].value,cmds[i].weight); + if(cmds[i].weight==1) + written+=snprintf(buf,len,"%s\t% .4f\n",outputNames[i],cmds[i].value); + else + written+=snprintf(buf,len,"%s\t% .4f\t% .4f\n",outputNames[i],cmds[i].value,cmds[i].weight); } if(loadSaveSensors!=NULL) { written+=snprintf(buf,len,"\n"); for(unsigned int i=0; ibuttons[i]); + written+=snprintf(buf,len," %s\t% .4f\t\n",buttonNames[i],loadSaveSensors->buttons[i]); } written+=snprintf(buf,len,"\n"); for(unsigned int i=0; isensors[i]); + written+=snprintf(buf,len," %s\t% .4f\t\n",sensorNames[i],loadSaveSensors->sensors[i]); } written+=snprintf(buf,len,"\n"); for(unsigned int i=0; ipidduties[i]); + written+=snprintf(buf,len," duty-%s\t% .4f\t\n",outputNames[i],loadSaveSensors->pidduties[i]); } written+=snprintf(buf,len,"\n"); } @@ -199,326 +211,367 @@ } unsigned int PostureEngine::loadBuffer(const char buf[], unsigned int len) { - unsigned int origlen=len; - clear(); - if(strncmp("#POS",buf,4)!=0) { - // we don't want to display an error here because we may be only testing file type, - // so it's up to the caller to decide if it's necessarily an error if the file isn't - // a posture - //std::cout << "ERROR PostureEngine load corrupted - expected #POS header" << std::endl; - return 0; - } - saveFormatCondensed=false; - char formatstring[64]; - snprintf(formatstring,64,"%%%dc %%g %%g%%n",outputNameLen); //std::cout << "Format: " << formatstring << std::endl; - unsigned int idx=0; - unsigned int linenum=1; - enum section_t { - SECTION_METAINFO, SECTION_OUTPUTS, SECTION_BUTTONS, SECTION_SENSORS, SECTION_PIDDUTIES - } curSection=SECTION_OUTPUTS; - char jname[outputNameLen+1]; - jname[outputNameLen]='\0'; - while(len<=origlen && len>0) { - float fval, fwht=1; - int written; - // printf("%d %.9s\n",linenum+1,buf); - if(buf[0]=='\r') { - buf++; len--; - if(buf[0]=='\n') { - buf++; len--; - } - linenum++; - continue; - } - if(buf[0]=='\n') { - buf++; len--; - linenum++; - continue; - } - if(buf[0]=='#') { - if(strncmp("#END\n",buf,5)==0 || strncmp("#END\r",buf,5)==0) { - return origlen-len+5; - } else if(strncmp("#END\r\n",buf,6)==0) { - return origlen-len+6; - } else { - while(len>0 && *buf!='\n' && *buf!='\r') {len--;buf++;} - if(*buf=='\n') { //in case of \r\n - buf++; - len--; + unsigned int origlen=len; + clear(); + if(buf==NULL || len==0) { + cerr << "*** ERROR: PostureEngine::loadBuffer(" << static_cast(buf) << ',' << len << ")" << endl; + return 0; } - linenum++; - continue; - } - } - if(isspace(buf[0])) { - buf++; len--; - continue; - } - written=-1; - if(strncmp(buf,"condensed ",strlen("condensed"))==0) { - char model[64]; - written=0; sscanf(buf,"condensed %64s%n",model,&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(strncmp(model,RobotName,64)!=0) { - printf("*** ERROR line %d, specified model (%.64s) for condensed mode does not match current robot (%s)\n",linenum,model,RobotName); - return 0; - } - saveFormatCondensed=true; - for(unsigned int i=0; ibuttons[i],&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - } - } else if(strncmp(section,"sensors",sectionLen)==0) { - for(unsigned int i=0; isensors[i],&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - } - } else if(strncmp(section,"pidduties",sectionLen)==0) { - for(unsigned int i=0; ipidduties[i],&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - } - } else if(strncmp(section,"meta-info",sectionLen)==0) { - written=0; sscanf(buf,"%u %u%n",&loadSaveSensors->lastSensorUpdateTime,&loadSaveSensors->frameNumber,&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - } else { - printf("*** Warning: line %d, unknown section '%.64s', skipping.\n",linenum,section); + if(strncmp("#POS",buf,4)!=0) { + // we don't want to display an error here because we may be only testing file type, + // so it's up to the caller to decide if it's necessarily an error if the file isn't + // a posture + //std::cout << "ERROR PostureEngine load corrupted - expected #POS header" << std::endl; + return 0; } - } else { - if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_OUTPUTS) - printf("*** WARNING PostureEngine encountered nested - line %d\n",linenum); - curSection=SECTION_METAINFO; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_METAINFO) - printf("*** WARNING PostureEngine encountered when not in sensor section - line %d\n",linenum); - curSection=SECTION_OUTPUTS; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_OUTPUTS) - printf("*** WARNING PostureEngine encountered nested - line %d\n",linenum); - curSection=SECTION_BUTTONS; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_BUTTONS) - printf("*** WARNING PostureEngine encountered when not in sensor section - line %d\n",linenum); - curSection=SECTION_OUTPUTS; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_OUTPUTS) - printf("*** WARNING PostureEngine encountered nested - line %d\n",linenum); - curSection=SECTION_SENSORS; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_SENSORS) - printf("*** WARNING PostureEngine encountered when not in sensor section - line %d\n",linenum); - curSection=SECTION_OUTPUTS; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_OUTPUTS) - printf("*** WARNING PostureEngine encountered nested - line %d\n",linenum); - curSection=SECTION_PIDDUTIES; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else if(strncmp(buf,"",strlen(""))==0) { - written=0; sscanf(buf,"%n",&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(curSection!=SECTION_PIDDUTIES) - printf("*** WARNING PostureEngine encountered when not in sensor section - line %d\n",linenum); - curSection=SECTION_OUTPUTS; - idx=0; //reset idx any time we switch sections, avoid illegal idx values - continue; - } else { - if(curSection==SECTION_METAINFO) { - const unsigned int nameLen=64; - char name[nameLen]; - unsigned int ival; - written=0; sscanf(buf,"%64s %u%n",name,&ival,&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - if(strncmp(name,"timestamp",nameLen)==0) { - loadSaveSensors->lastSensorUpdateTime=ival; - } else if(strncmp(name,"framenumber",nameLen)==0) { - loadSaveSensors->frameNumber=ival; - } else { - std::cout << "*** WARNING '" << name << "' is not a valid meta-info on this model. (ignoring line " << linenum << ")" << std::endl; - } - } else if(curSection==SECTION_BUTTONS) { - const unsigned int nameLen=64; - char name[nameLen]; - written=0; sscanf(buf,"%64s %g%n",name,&fval,&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - unsigned int startidx=idx; - for(;idxbuttons[idx]=fval; - break; - } - if(idx==NumButtons) { //not found following startidx, look from beginning - for(idx=0;idxbuttons[idx]=fval; - break; + saveFormatCondensed=false; + Capabilities* caps = &capabilities; + unsigned int linenum=0; + bool filtered=false; // true if in a specialization section for a different model + section_t curSection=SECTION_OUTPUTS; + map sectionMap; + sectionMap["meta-info"]=SECTION_METAINFO; + sectionMap["outputs"]=SECTION_OUTPUTS; + sectionMap["buttons"]=SECTION_BUTTONS; + sectionMap["sensors"]=SECTION_SENSORS; + sectionMap["pidduties"]=SECTION_PIDDUTIES; + + + while(len<=origlen && len>0) { + // extract a line from the buffer (line endings could be \r, \n, or \r\n ) + string line; + for(unsigned int lineend=0; lineendsensors[idx]=fval; - break; - } - if(idx==NumSensors) { //not found following startidx, look from beginning - for(idx=0;idxsensors[idx]=fval; - break; + + // strip comment + string::size_type commentPos = line.find('#'); + if(commentPos!=string::npos) { + if(line.substr(commentPos)=="#END") + return origlen-len; + line = line.substr(0,commentPos); } - if(idx==startidx && strcmp(name,sensorNames[idx])!=0) //not found at all - std::cout << "*** WARNING '" << name << "' is not a valid sensor on this model. (ignoring line " << linenum << ")" << std::endl; - } - } else if(curSection==SECTION_PIDDUTIES) { - const unsigned int nameLen=64; - char name[nameLen]; - written=0; sscanf(buf,"%64s %g%n",name,&fval,&written); - if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0; - unsigned int startidx=idx; - for(;idxpidduties[PIDJointOffset+idx]=fval; - break; - } - if(idx==NumPIDJoints) { //not found following startidx, look from beginning - for(idx=0;idxpidduties[PIDJointOffset+idx]=fval; - break; + + // tokenize + // whitespace and '=' are used as delimiters + vector words; + for(unsigned int i=0; i& sectionMap, std::vector& words, section_t& curSection, Capabilities*& caps, bool& filtered) { + if(words[0]=="specialize") { + if(words.size()>2) + cerr << "*** Warning line " << linenum << ", extra arguments to 'specialize'" << endl; + filtered = false; + if(words.size()>1) try { + filtered = !string_util::reMatch(RobotName,words[1],REG_EXTENDED); + } catch(const std::string& err) { + cerr << "*** ERROR line " << linenum << ", bad regular expression: " << err << endl; + return false; } - if(idx==startidx && strcmp(jname,outputNames[idx])!=0) {//not found at all, check if this is a symmetric case - unsigned int lidx=NumOutputs, ridx=NumOutputs; - char tname[outputNameLen+1]; - strncpy(tname+1,jname,outputNameLen); - tname[0]='L'; - for(idx=0;idx2) + cerr << "*** Warning line " << linenum << ", extra arguments to 'condensed'" << endl; + if(words.size()==1) { + cerr << "*** ERROR line " << linenum << ", missing model name for 'condensed'" << endl; + return false; + } else { + caps = getCapabilities(words[1]); + if(caps==NULL) { + cerr << "*** ERROR line " << linenum << ", unknown model for 'condensed': " << words[1] << endl; + return false; + } + saveFormatCondensed=true; + } + + } else if(words[0]=="verbose") { + if(words.size()>1) + cerr << "*** Warning line " << linenum << ", extra arguments to 'verbose'" << endl; + saveFormatCondensed=false; + + } else if(words[0][0]=='<' && words[0][words[0].size()-1]=='>') { + if(words.size()>1) + cerr << "*** Warning line " << linenum << ", extra arguments to section tag (this isn't a real XML format, tag must be on line by itself)" << endl; + bool isend = (words[0][1]=='/'); + const string name = words[0].substr(isend?1:2, words[0].size()-(isend?2:3)); + map::const_iterator it = sectionMap.find(name); + if(it==sectionMap.end()) { + cerr << "*** ERROR line " << linenum << ", unknown section '" << name << "'" << endl; + return false; + } + section_t section = it->second; + if(isend) { + if(curSection!=section) + cerr << "*** Warning line " << linenum << ", mismatched close tag " << name << endl; + curSection=SECTION_OUTPUTS; + } else { + if(curSection!=SECTION_OUTPUTS) + cerr << "*** Warning line " << linenum << ", nested tags not supported, or missing close tag" << endl; + curSection=section; + } + + } else if(filtered) { + // no-op + + } else { + // either a section name (condensed form) or an output/button/sensor name (verbose form) + map::const_iterator it = sectionMap.find(words[0]); + if(it==sectionMap.end()) { + // not an entry in sectionMap... + if(words[0]=="weights") { // weights is a "condensed-only" section, handled a little specially since it's not in sectionMap... + if(caps==&capabilities) { + // we're using the "native" target... make things a bit quicker + for(unsigned int i=1; igetOutputName(i-1); + unsigned int off = capabilities.findOutputOffset(name); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", output '" << name << "' from robot " << caps->getRobotName() << " cannot be mapped to host " << RobotName << endl; + } else { + cmds[off].weight = atof(words[i].c_str()); + } } } - tname[0]='R'; - for(idx=0;idxlastSensorUpdateTime = atoi(words[1].c_str()); + } else if(words[0]=="framenumber") { + if(loadSaveSensors!=NULL) + loadSaveSensors->frameNumber = atoi(words[1].c_str()); + } else { + cerr << "*** Warning line " << linenum << ", '" << words[0] << "' is not a valid meta-info" << endl; + } + } break; + case SECTION_OUTPUTS: { + stripTildes(words[0]); + unsigned int off = capabilities.findOutputOffset(words[0].c_str()), loff=-1U; + if(off==-1U) { + // try again with L/R prefixes + loff = capabilities.findOutputOffset(('L'+words[0]).c_str()); + if(loff!=-1U) + off = capabilities.findOutputOffset(('R'+words[0]).c_str()); + } + if(off==-1U) + cerr << "*** Warning line " << linenum << ", '" << words[0] << "' is not a valid output on this model (" << RobotName << ")" << endl; + else { + float value = atof(words[1].c_str()); + float weight=1; + if(words.size()>2) + weight = atof(words[2].c_str()); + cmds[off].set(value,weight); + if(loff!=-1U) + cmds[loff].set(value,weight); + } + } break; + case SECTION_BUTTONS: { + unsigned int off = capabilities.findButtonOffset(words[0].c_str()); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", '" << words[0] << "' is not a valid button on this model (" << RobotName << ")" << endl; + } else if(loadSaveSensors!=NULL) { + loadSaveSensors->buttons[off] = atof(words[1].c_str()); + } + } break; + case SECTION_SENSORS: { + unsigned int off = capabilities.findSensorOffset(words[0].c_str()); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", '" << words[0] << "' is not a valid sensor on this model (" << RobotName << ")" << endl; + } else if(loadSaveSensors!=NULL) { + loadSaveSensors->sensors[off] = atof(words[1].c_str()); + } + } break; + case SECTION_PIDDUTIES: { + stripTildes(words[0]); + unsigned int off = capabilities.findOutputOffset(words[0].c_str()); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", '" << words[0] << "' is not a valid output on this model (" << RobotName << ")" << endl; + } else if(off=PIDJointOffset+NumPIDJoints) { + cerr << "*** Warning line " << linenum << ", output '" << words[0] << "' from robot " << caps->getRobotName() << " does not map to a PID joint on the local host " << RobotName << endl; + } else if(loadSaveSensors!=NULL) { + loadSaveSensors->pidduties[off-PIDJointOffset] = atof(words[1].c_str()); + } + } break; + } // end of section 'switch' + } // end of condensed 'weight' section vs. verbose entry 'else' + + } else { + // is a section name (aka condensed entry) + switch(it->second) { + case SECTION_METAINFO: { + if(loadSaveSensors==NULL) break; + if(words.size()>1) + loadSaveSensors->lastSensorUpdateTime = atoi(words[1].c_str()); + if(words.size()>1) + loadSaveSensors->frameNumber = atoi(words[2].c_str()); + } break; + case SECTION_OUTPUTS: { + unsigned int size=words.size(); + if(size-1!=caps->getNumOutputs()) { + cerr << "*** ERROR line " << linenum << ", " << caps->getRobotName() << " expected " << caps->getNumOutputs() << " values, got " << (size-1) << endl; + return 0; } - } - if(lidx!=NumOutputs && ridx!=NumOutputs) { - cmds[lidx].set(fval,fwht); - cmds[ridx].set(fval,fwht); - } else { - idx=startidx; - std::cout << "*** WARNING '" << jname << "' is not a valid joint on this model. (ignoring line " << linenum << ")" << std::endl; - } - } - } - } - } - } - } - while(*buf!='\n' && *buf!='\r') { - buf++; len--; - } - if(buf[0]=='\r' && buf[1]=='\n') { - buf+=2; len-=2; - } else { - buf++; len--; - } - linenum++; - } - std::cout << "*** WARNING PostureEngine load missing #END" << std::endl; - return origlen-len; + if(caps==&capabilities) { + // we're using the "native" target... make things a bit quicker + for(unsigned int i=1; igetOutputName(i-1); + unsigned int off = capabilities.findOutputOffset(name); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", output '" << name << "' from robot " << caps->getRobotName() << " cannot be mapped to host " << RobotName << endl; + } else { + cmds[off].set(atof(words[i].c_str())); + } + } + } + } break; + case SECTION_BUTTONS: { + if(loadSaveSensors==NULL) + break; + unsigned int size=words.size(); + if(size-1!=caps->getNumButtons()) { + cerr << "*** ERROR line " << linenum << ", " << caps->getRobotName() << " expected " << caps->getNumButtons() << " values, got " << (size-1) << endl; + return 0; + } + if(caps==&capabilities) { + // we're using the "native" target... make things a bit quicker + for(unsigned int i=1; ibuttons[i-1] = atof(words[i].c_str()); + } else { + // we're using another target, map to the host + for(unsigned int i=1; igetButtonName(i-1); + unsigned int off = capabilities.findButtonOffset(name); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", button '" << name << "' from robot " << caps->getRobotName() << " cannot be mapped to host " << RobotName << endl; + } else { + loadSaveSensors->buttons[off] = atof(words[i].c_str()); + } + } + } + } break; + case SECTION_SENSORS: { + if(loadSaveSensors==NULL) + break; + unsigned int size=words.size(); + if(size-1!=caps->getNumSensors()) { + cerr << "*** ERROR line " << linenum << ", " << caps->getRobotName() << " expected " << caps->getNumSensors() << " values, got " << (size-1) << endl; + return 0; + } + if(caps==&capabilities) { + // we're using the "native" target... make things a bit quicker + for(unsigned int i=1; isensors[i-1] = atof(words[i].c_str()); + } else { + // we're using another target, map to the host + for(unsigned int i=1; igetSensorName(i-1); + unsigned int off = capabilities.findSensorOffset(name); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", sensor '" << name << "' from robot " << caps->getRobotName() << " cannot be mapped to host " << RobotName << endl; + } else { + loadSaveSensors->sensors[off] = atof(words[i].c_str()); + } + } + } + } break; + case SECTION_PIDDUTIES: { + if(loadSaveSensors==NULL) + break; + unsigned int size=words.size(); + if(size-1!=caps->getNumPIDJoints()) { + cerr << "*** ERROR line " << linenum << ", " << caps->getRobotName() << " expected " << caps->getNumPIDJoints() << " values, got " << (size-1) << endl; + return 0; + } + if(caps==&capabilities) { + for(unsigned int i=1; ipidduties[i-1] = atof(words[i].c_str()); + } else { + // we're using another target, map to the host + unsigned int pidoff = caps->getPIDJointOffset(); + for(unsigned int i=1; igetOutputName(pidoff+i-1); + unsigned int off = capabilities.findOutputOffset(name); + if(off==-1U) { + cerr << "*** Warning line " << linenum << ", output '" << name << "' from robot " << caps->getRobotName() << " cannot be mapped to host " << RobotName << endl; + } else if(off=PIDJointOffset+NumPIDJoints) { + cerr << "*** Warning line " << linenum << ", output '" << name << "' from robot " << caps->getRobotName() << " does not map to a PID joint on the local host " << RobotName << endl; + } else { + loadSaveSensors->pidduties[off-PIDJointOffset] = atof(words[i].c_str()); + } + } + } + } break; + } // end of section name 'switch' + } // end of section name found 'else' + } // end of not-a-keyword 'else' + return true; } - + //Why do i need a cast to const char**??? It doesn't work without, should be automatic... grrrr unsigned int PostureEngine::saveBuffer(char buf[], unsigned int len) const { unsigned int origlen=len; int written=snprintf(buf,len,"#POS\n"); if(!checkInc(written,buf,len,"*** ERROR PostureEngine save failed on header\n")) return 0; if(saveFormatCondensed) { +#ifndef PLATFORM_APERIOS written=snprintf(buf,len,"condensed %s\n",RobotName); +#else + written=snprintf(buf,len,"condensed %s\n",RobotName.c_str()); +#endif if(!checkInc(written,buf,len,"*** ERROR PostureEngine save condensed header failed\n")) return 0; if(loadSaveSensors!=NULL) { written=snprintf(buf,len,"meta-info = %u %u\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber); @@ -570,31 +623,35 @@ } } else { if(loadSaveSensors!=NULL) { - written=snprintf(buf,len,"\n timestamp\t%u\n framenumber\t%u\n\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber); + written=snprintf(buf,len,"\n timestamp\t%u\n framenumber\t%u\n\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber); if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor begin save failed\n")) return 0; } - for(unsigned int i=0; i0) { - written=snprintf(buf,len,"%s\t% .4f\t% .4f\n",outputNames[i],cmds[i].value,cmds[i].weight); + if(cmds[i].weight==1) + written=snprintf(buf,len,"%s\t% .4f\n",outputNames[i],cmds[i].value); + else + written=snprintf(buf,len,"%s\t% .4f\t% .4f\n",outputNames[i],cmds[i].value,cmds[i].weight); if(!checkInc(written,buf,len,"*** ERROR PostureEngine save failed\n")) return 0; } + } if(loadSaveSensors!=NULL) { written=snprintf(buf,len,"\n"); if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor begin save failed\n")) return 0; for(unsigned int i=0; ibuttons[i]); + written=snprintf(buf,len," %s\t% .4f\t\n",buttonNames[i],loadSaveSensors->buttons[i]); if(!checkInc(written,buf,len,"*** ERROR PostureEngine save button failed\n")) return 0; } written=snprintf(buf,len,"\n"); if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor end save failed\n")) return 0; for(unsigned int i=0; isensors[i]); + written=snprintf(buf,len," %s\t% .4f\t\n",sensorNames[i],loadSaveSensors->sensors[i]); if(!checkInc(written,buf,len,"*** ERROR PostureEngine save sensor failed\n")) return 0; } written=snprintf(buf,len,"\n"); if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor end save failed\n")) return 0; for(unsigned int i=0; ipidduties[i]); + written=snprintf(buf,len," %s\t% .4f\t\n",outputNames[i],loadSaveSensors->pidduties[i]); if(!checkInc(written,buf,len,"*** ERROR PostureEngine save pidduties failed\n")) return 0; } written=snprintf(buf,len,"\n"); @@ -605,7 +662,7 @@ if(!checkInc(written,buf,len,"*** ERROR PostureEngine save failed on #END\n")) return 0; return origlen-len; } - + unsigned int PostureEngine::loadFile(const char filename[]) { return LoadSave::loadFile(config->motion.makePath(filename).c_str()); } @@ -614,37 +671,37 @@ } /* -NEWMAT::ReturnMatrix -Kinematics::getOrientation(unsigned int j) { - unsigned int c=-1U,l=-1U; - if(!lookup(j,c,l)) { - NEWMAT::Matrix A(4,4); - A<kine(R,p,j); - R.Release(); return R; -} - -NEWMAT::ReturnMatrix -Kinematics::getPosition(unsigned int j) { - unsigned int c=-1U,l=-1U; - if(!lookup(j,c,l)) { - NEWMAT::Matrix A(4,4); - A<kine(R,p,j); - p.Release(); return p; -} -*/ - + NEWMAT::ReturnMatrix + Kinematics::getOrientation(unsigned int j) { + unsigned int c=-1U,l=-1U; + if(!lookup(j,c,l)) { + NEWMAT::Matrix A(4,4); + A<kine(R,p,j); + R.Release(); return R; + } + + NEWMAT::ReturnMatrix + Kinematics::getPosition(unsigned int j) { + unsigned int c=-1U,l=-1U; + if(!lookup(j,c,l)) { + NEWMAT::Matrix A(4,4); + A<kine(R,p,j); + p.Release(); return p; + } + */ + bool PostureEngine::solveLinkPosition(const NEWMAT::ColumnVector& Pobj, unsigned int j, const NEWMAT::ColumnVector& Plink) { unsigned int c=-1U,l=-1U; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/PostureEngine.h ./Motion/PostureEngine.h --- ../Tekkotsu_3.0/Motion/PostureEngine.h 2006-10-03 22:57:12.000000000 -0400 +++ ./Motion/PostureEngine.h 2007-11-11 18:57:23.000000000 -0500 @@ -10,7 +10,66 @@ class WorldState; //! A class for storing a set of positions and weights for all the outputs -/*! Handy for any class which wants to deal with setting joints and postures without writing a custom class +/*! File Format: ([..] indicates an optional parameter)\n + * - First line: '\#POS' + * - Followed by a series of: + * - 'specialize [regex]' - only robots whose model name matches the regular + * expression will attempt to parse lines between this and the next 'specialize' command. An empty + * (absent) regex matches all robots (equivalent to 'specialize .*') + * - 'condensed model' - specifies model name for which condensed specifications will be + * interpreted + * - 'verbose' - switches the load/save format back to "verbose" style, where each output/sensor + * value is listed individually + * - '<section> ... </section>' - specifies a + * section for following "verbose" style lines (valid section values listed below) + * - 'section value1 value2 value3 ...' - specify all values for a section in + * one line, "condensed" style (valid section values listed below). Must have a value for every + * item in the section (no extra or missing values) + * - 'output-name value [weight]' - specifies an output value, with optional weighting + * value (if no weight specified, '1' is assumed) + * - Last line: '\#END' + * + * Note that '=' can be used to separate tokens as well as any whitespace character. + * All angle values should be specified in radians. + * + * Valid section names are: + * - meta-info - only recognizes two fields: timestamp and framenumber + * - outputs - supports all output names (e.g. ERS7Info::outputNames) + * - buttons - supports all button names (e.g. ERS7Info::buttonNames) + * - sensors - supports all sensor names (e.g. ERS7Info::sensorNames) + * - pidduties - supports output names corresponding to PID joints (this is the "duty cycle" for the joint) + * + * Additionally 'weights' can be used as a condensed section name (but not a + * verbose tag-style section, since weights are specified on each line). The + * 'weights' specification must follow the 'outputs' specification to be effective. + * + * Data following '\#' is ignored as comments. Be aware if you + * load the file and then save it again, these comments will be lost. + * + * Example 1: Specifies only neck joints, looks forward and up a little +
+\#POS 
+NECK:tilt	0
+NECK:pan	0
+NECK:nod	0.2
+\#END
+
+ * All other, unspecified, joints will be set to weight=0. + * + * Example 2: Logged sensor data from an ERS-7 robot +
+\#POS
+condensed ERS-7
+meta-info = 1439041 178803
+outputs = -0.131722 0.148077 1.74592 -0.30276 0.341717 2.13361 -1.03935 0.091124 2.18958 -0.804097 0.034171 1.67458 -0.016362 -0.089143 0.125563 0.407243 -0.054399 -0.064704 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0
+buttons = 0 0 0 0 0 0 0 0 0 1
+sensors = 500 860.139 425 -2.06456 -0.516139 -8.94642 0.99 30.63 2200 8.265 0
+pidduties = -0.164062 0.0878906 0.0957031 0.246094 -0.0195312 -0.0546875 -0.164062 -0.0195312 0.164062 0.0273438 0 -0.0683594 -0.00585938 -0.00390625 0.0820312 -0.0390625 0.015625 0.00390625
+\#END
+
+ * Condensed posture files can still be loaded on other models. For each entry, RobotInfo::Capabilities will be + * used to map from the model specified by the condensed command to the current host. + * * @see PostureMC * @see Tekkotsu's Kinematics page * @see David Touretzky's "Postures and Motion Sequences" Chapter @@ -193,6 +252,22 @@ //@} protected: + //! enumeration of the different section types that may be used as section tags in verbose mode + enum section_t { + SECTION_METAINFO, //!< includes timestamp and framenumber + SECTION_OUTPUTS, //!< entries corresponding to NumOutputs + SECTION_BUTTONS, //!< entries corresponding to NumButtons + SECTION_SENSORS, //!< entries corresponding to NumSensors + SECTION_PIDDUTIES //!< entries corresponding to NumPIDJoints + }; + //! helper function for loadBuffer, called for each individual line + virtual bool loadLine(unsigned int linenum, const std::map& sectionMap, std::vector& words, section_t& curSection, Capabilities*& caps, bool& filtered); + //! helper function for loadLine, strips trailing '~'s from output names to provide backward compatability (note pass by reference, operates 'in-place' on @a word) + /*! (originally, all output names were uniform length and used '~'s as padding... ugh.) */ + void stripTildes(std::string& word) { + word.erase(word.find_last_not_of('~')+1); // if n is npos, npos is -1U, so becomes 0... should be safe :) + } + //all updates come from this posture engine's own state, not WorldState virtual void update(unsigned int c, unsigned int l); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/PostureMC.cc ./Motion/PostureMC.cc --- ../Tekkotsu_3.0/Motion/PostureMC.cc 2006-08-31 17:48:00.000000000 -0400 +++ ./Motion/PostureMC.cc 2007-08-24 23:40:31.000000000 -0400 @@ -1,6 +1,8 @@ #include "PostureMC.h" #include "Shared/Config.h" #include "Shared/WorldState.h" +#include "Shared/ERS7Info.h" +#include "Shared/ERS210Info.h" PostureMC& PostureMC::setDirty(bool d/*=true*/) { dirty=d; @@ -14,9 +16,28 @@ for(unsigned int i=0; imotion.max_head_tilt_speed*FrameTime*x/1000; maxSpeeds[HeadOffset+PanOffset]=config->motion.max_head_pan_speed*FrameTime*x/1000; maxSpeeds[HeadOffset+RollOffset]=config->motion.max_head_roll_speed*FrameTime*x/1000; +#else + const char* n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::TiltOffset]; + unsigned int i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeeds[i]=config->motion.max_head_tilt_speed*FrameTime*x/1000; + n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeeds[i]=config->motion.max_head_pan_speed*FrameTime*x/1000; + n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::NodOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeeds[i]=config->motion.max_head_roll_speed*FrameTime*x/1000; + n = ERS210Info::outputNames[ERS210Info::HeadOffset+ERS210Info::RollOffset]; + i = capabilities.findOutputOffset(n); + if(i!=-1U) + maxSpeeds[i]=config->motion.max_head_roll_speed*FrameTime*x/1000; +#endif } int PostureMC::updateOutputs() { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/RemoteControllerMC.h ./Motion/RemoteControllerMC.h --- ../Tekkotsu_3.0/Motion/RemoteControllerMC.h 2004-12-20 19:42:21.000000000 -0500 +++ ./Motion/RemoteControllerMC.h 2007-11-15 00:33:10.000000000 -0500 @@ -6,42 +6,31 @@ #include "OutputCmd.h" #include "Shared/RobotInfo.h" -//! This class is used for setting all PIDJoints to a certain set of values (not the gains, just the joint positions) -/*! This is PostureMC's little brother. Not quite so full of features, but straightforward and easy to understand. (hopefully) */ +//! This class is used for setting all outputs to a certain set of values (not the gains, just the joint positions) +/*! This is PostureMC's little brother. Not quite so full of features, but straightforward and easy to understand. (hopefully) + * This is about as simple of a motion command as you'll find, so it might make for good sample code. */ class RemoteControllerMC : public MotionCommand { - public: - //! constructor, defaults to active, all joints at 0 - RemoteControllerMC():MotionCommand(), dirty(true), active(true) { - for (unsigned int i=0; isetOutput(this, PIDJointOffset+i, cmds[i]); - dirty=false; - return tmp; - } - virtual int isDirty() { return (dirty && active)?1:0; } //!< true if a change has been made since the last updateJointCmds() and we're active + for (unsigned int i=0; isetOutput(this, i, cmds[i]); + return NumOutputs; + } + virtual int isAlive() { return true; } //!< always true - virtual void DoStart() { MotionCommand::DoStart(); dirty=true; } //!< marks this as dirty each time it is added - //@} - - void setDirty() { dirty=true; } //!< sets dirty flag to true - float cmds[NumPIDJoints]; //!< current vector of positions - - protected: - bool dirty; //!< true if a change has been made since last call to updateJointCmds() - bool active; //!< set by accessor functions, defaults to true + + OutputCmd cmds[NumOutputs]; //!< current vector of positions }; /*! @file - * @brief Describes RemoteControllerMC, a class used for setting all PIDJoints to a certain set of values (not the gains, just the joint positions) + * @brief Describes RemoteControllerMC, a class used for setting all outputs to a certain set of values (not the gains, just the joint positions) * @author alokl (Creator) * * $Author: ejt $ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/TailWagMC.h ./Motion/TailWagMC.h --- ../Tekkotsu_3.0/Motion/TailWagMC.h 2006-02-15 14:14:13.000000000 -0500 +++ ./Motion/TailWagMC.h 2007-06-28 00:36:21.000000000 -0400 @@ -32,16 +32,30 @@ return 0; // only ERS-210 and ERS-7 have moveable tails - unsigned int tail_pan_offset, tail_tilt_offset; - if(state->robotDesign & WorldState::ERS210Mask) { - tail_pan_offset = ERS210Info::TailOffset+PanOffset; - tail_tilt_offset = ERS210Info::TailOffset+TiltOffset; + unsigned int tail_pan_offset=-1U, tail_tilt_offset=-1U; + if(RobotName == ERS210Info::TargetName) { + // might be in 2xx compatability mode, use dynamic lookup + unsigned tail = capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TailOffset]); + tail_pan_offset = tail+PanOffset; + tail_tilt_offset = tail+TiltOffset; } - else if(state->robotDesign & WorldState::ERS7Mask) { + else if(RobotName == ERS7Info::TargetName) { + // no compatability mode, just use direct symbol: tail_pan_offset = ERS7Info::TailOffset+PanOffset; tail_tilt_offset = ERS7Info::TailOffset+TiltOffset; + } else { + // unknown model, see if we have a tail named after the ERS-210 tail: + tail_pan_offset = capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TailOffset+PanOffset]); + if(tail_pan_offset!=-1U) { + // try the tilt too... + tail_tilt_offset = capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TailOffset+TiltOffset]); + } else { + // maybe just named "tail"? + tail_pan_offset = capabilities.getOutputOffset("Tail"); + } } - else return 0; + if(tail_pan_offset==-1U) + return 0; for(unsigned int i=0; isetOutput(this,tail_pan_offset,pans); - motman->setOutput(this,tail_tilt_offset,tilt); + if(tail_tilt_offset!=-1U) + motman->setOutput(this,tail_tilt_offset,tilt); return tilt.weight>0?2:1; } @@ -69,12 +84,13 @@ float curPos=(get_time()%period)/(float)period; offset=static_cast((prevPos-curPos)*period); } - unsigned int getPeriod() { return period; } //!< gets the period of time between swings, in milliseconds + unsigned int getPeriod() const { return period; } //!< gets the period of time between swings, in milliseconds void setMagnitude(double mag) { magnitude=mag; } //!< sets the magnitude of swings, in radians - double getMagnitude() { return magnitude; } //!< gets the magnitude of swings, in radians + double getMagnitude() const { return magnitude; } //!< gets the magnitude of swings, in radians void setTilt(double r) { tilt.set(r,1); } //!< sets the tilt of the tail while wagging, in radians void unsetTilt() { tilt.unset(); } //!< makes the tilt control unspecified, will let something else control tilt - double getTilt() { return tilt.value; } //!< sets the tilt of the tail while wagging, in radians + double getTilt() const { return tilt.value; } //!< gets the tilt of the tail while wagging, in radians + double getPan() const { return last_pan; } //!< returns the most recent pan value of the tail while wagging, in radians bool getActive() { return active; } //!< returns true if this is currently trying to wag the tail diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/UPennWalkMC.cc ./Motion/UPennWalkMC.cc --- ../Tekkotsu_3.0/Motion/UPennWalkMC.cc 2006-08-31 17:37:10.000000000 -0400 +++ ./Motion/UPennWalkMC.cc 2007-03-23 16:05:37.000000000 -0400 @@ -159,6 +159,7 @@ void UPennWalkMC::SetLegJoints(double * x) { +#ifdef TGT_HAS_LEGS motman->setOutput(this,LFrLegOffset+RotatorOffset,x[LEG_LEFT_FORE*JointsPerLeg+0]); motman->setOutput(this,LFrLegOffset+ElevatorOffset,x[LEG_LEFT_FORE*JointsPerLeg+1]); motman->setOutput(this,LFrLegOffset+KneeOffset,x[LEG_LEFT_FORE*JointsPerLeg+2]); @@ -174,6 +175,7 @@ motman->setOutput(this,RBkLegOffset+RotatorOffset,x[LEG_RIGHT_HIND*JointsPerLeg+0]); motman->setOutput(this,RBkLegOffset+ElevatorOffset,x[LEG_RIGHT_HIND*JointsPerLeg+1]); motman->setOutput(this,RBkLegOffset+KneeOffset,x[LEG_RIGHT_HIND*JointsPerLeg+2]); +#endif } void diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/UPennWalkMC.h ./Motion/UPennWalkMC.h --- ../Tekkotsu_3.0/Motion/UPennWalkMC.h 2005-04-12 18:18:34.000000000 -0400 +++ ./Motion/UPennWalkMC.h 2006-11-13 09:44:06.000000000 -0500 @@ -61,7 +61,7 @@ //! Calculate 12 leg joint angles from leg positions /*! Note positions are relative to stance parameters * so all zero inputs -> stance angles */ - void UPennWalkMC::LegPositionsToAngles(double *a); + void LegPositionsToAngles(double *a); void StandLegs(double x=0, double y=0, double z=0); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/WalkMC.cc ./Motion/WalkMC.cc --- ../Tekkotsu_3.0/Motion/WalkMC.cc 2006-09-10 14:48:46.000000000 -0400 +++ ./Motion/WalkMC.cc 2007-11-18 01:47:03.000000000 -0500 @@ -132,9 +132,16 @@ return 0; if((target_vel_xya.x == 0) && (target_vel_xya.y == 0) && (target_vel_xya.z == 0)) { // we may stopping, but not stopped yet... - return ((vel_xya.x != 0) || (vel_xya.y != 0) || (vel_xya.z != 0)); + if((vel_xya.x == 0) && (vel_xya.y == 0) && (vel_xya.z == 0)) + return false; } +#ifdef TGT_HAS_LEGS return JointsPerLeg*NumLegs; +#elif defined(TGT_HAS_WHEELS) + return NumWheels; +#else + return 0; +#endif } // tss "SmoothWalk" addition ends @@ -167,7 +174,7 @@ } // Leg parameters - for(unsigned int i=0; isetOutput(this,joint,cmds[joint]); - + // cout << "WalkMC-done" << endl; - return NumLegs*JointsPerLeg; + return NumLegs*JointsPerLeg; + +#elif defined(TGT_HAS_WHEELS) + vel_xya=target_vel_xya; + float wheelcircum = 2*M_PI*config->motion.wheelRadius; + float baserpm = vel_xya.x / wheelcircum; + float turnrpm = (vel_xya.z*config->motion.wheelBaseWidth/2) / wheelcircum; + float left = baserpm - turnrpm; + float right = baserpm + turnrpm; + for(unsigned int frame=0; frame " << left << ' ' << right << std::endl; + + for(unsigned int w=WheelOffset; wsetOutput(this,w,cmds[w]); + + // cout << "WalkMC-done" << endl; + return NumWheels; + +#else +# warning target has neither legs nor wheels -- WalkMC is a no-op + return 0; +#endif } void WalkMC::resetLegPos() { BodyPosition nextpos; nextpos.loc.set(0,0,wp.body_height); nextpos.angle.set(0,wp.body_angle,0); +#ifdef TGT_HAS_LEGS for(unsigned int i=0; i " << legpos[i].x << ' ' << legpos[i].y << ' ' << legpos[i].z << endl; */ } +#endif //cout << "----------------------" << endl; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/WalkMC.h ./Motion/WalkMC.h --- ../Tekkotsu_3.0/Motion/WalkMC.h 2006-10-03 17:42:50.000000000 -0400 +++ ./Motion/WalkMC.h 2007-11-12 23:16:03.000000000 -0500 @@ -98,8 +98,8 @@ double body_angle; //!< the angle to hold the body (rad - 0 is level) double hop; //!< sinusoidal hop amplitude double sway; //!< sinusoidal sway in y direction - long period; //!< the time between steps - long useDiffDrive; //!< if non-zero, diff-drive style turning is used instead of rotational turning + int period; //!< the time between steps + int useDiffDrive; //!< if non-zero, diff-drive style turning is used instead of rotational turning float sag; //!< the amount to sagging to account for when a foot is lifted float reserved; //!< just live with it }; @@ -204,8 +204,10 @@ virtual void setAccelerationStyle(AccelerationStyle_t acc) { acc_style=acc; } //!< sets #acc_style virtual AccelerationStyle_t getAccelerationStyle() const { return acc_style; } //!< returns #acc_style +#ifdef TGT_HAS_LEGS //! returns the current leg position of leg @a i const vector3d& getLegPosition(LegOrder_t i) const { return legpos[i]; } +#endif struct WalkParam& getWP() { return wp; }; //!< returns the current walk parameter structure struct CalibrationParam& getCP() { return cp; }; //!< returns the current walk calibration parameter diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/WaypointEngine.h ./Motion/WaypointEngine.h --- ../Tekkotsu_3.0/Motion/WaypointEngine.h 2006-09-09 00:32:58.000000000 -0400 +++ ./Motion/WaypointEngine.h 2007-03-04 20:19:11.000000000 -0500 @@ -4,6 +4,7 @@ #include "IPC/ListMemBuf.h" #include "Shared/LoadSave.h" +#include "Shared/Config.h" //! Provides computation and management of a desired path through a series of waypoints /*! This is a generalized set of data structures and management code - diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/Makefile ./Motion/roboop/Makefile --- ../Tekkotsu_3.0/Motion/roboop/Makefile 2006-03-28 12:08:21.000000000 -0500 +++ ./Motion/roboop/Makefile 2007-11-12 23:14:44.000000000 -0500 @@ -6,16 +6,19 @@ ifndef TEKKOTSU_ENVIRONMENT_CONFIGURATION $(error An error has occured, TEKKOTSU_ENVIRONMENT_CONFIGURATION was not defined) endif -TEKKOTSU_ROOT:=../.. +TEKKOTSU_ROOT:=$(shell cd ../.. && pwd) include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g') BUILDDIR=$(TK_LIB_BD)/Motion/roboop SRCSUFFIX=.cpp # You may need to adjust these cc options: -CXXFLAGS= -I ../../Shared/newmat -fno-inline \ +CXXFLAGS:= -I ../../Shared/newmat -fno-inline \ -Wall -W -Wlarger-than-8192 -Wpointer-arith -Wcast-qual \ -Woverloaded-virtual -Wdeprecated -Wnon-virtual-dtor \ - -O3 -frename-registers -fomit-frame-pointer -fno-common \ + -g \ + -fmessage-length=0 $(CXXFLAGS) $(ENV_CXXFLAGS) \ + +# -frename-registers -fomit-frame-pointer -fno-common \ ifeq ($(strip $(shell $(CXX) --version | head -n 1)),powerpc-apple-darwin8-g++-4.0.0 (GCC) 4.0.0 20041026 (Apple Computer, Inc. build 4061)) $(shell echo "Disabling ROBOOP optimization due to darwin gcc 4.0.0 compiler bug triggered by robot.cpp" > /dev/tty) @@ -25,14 +28,14 @@ # -Wshadow -Weffc++ # Link-time cc options: -LDFLAGS= +LDFLAGS:= $(LDFLAGS) # To link any special libraries, add the necessary -l commands here. LDLIBS= # miscellaneous OS-dependent stuff # linker -LN= $(CC) +LN= $(CXX) # file deletion command RM= rm -f # file rename command @@ -63,6 +66,9 @@ LIBOBJECTS= $(addprefix $(BUILDDIR)/,$(LIBSOURCES:.cpp=.o)) all: $(BUILDDIR)/libroboop.a +ifneq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) +all: $(BUILDDIR)/libroboop.$(if $(findstring Darwin,$(shell uname)),dylib,so) +endif .PHONY: all clean @@ -72,6 +78,16 @@ @$(AR) $@ $(LIBOBJECTS) @$(AR2) $@ +$(BUILDDIR)/libroboop.dylib: $(LIBOBJECTS) + $(RM) $@ + @echo "Linking $@..." + @libtool -dynamic -undefined dynamic_lookup -o $@ $(LIBOBJECTS); + +$(BUILDDIR)/libroboop.so: $(LIBOBJECTS) + $(RM) $@ + @echo "Linking $@..." + @$(CXX) -shared -o $@ $(LIBOBJECTS); + clean: $(RM) *.o *.a *.log core $(PCH) $(RM) -r $(BUILDDIR) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/clik.cpp ./Motion/roboop/clik.cpp --- ../Tekkotsu_3.0/Motion/roboop/clik.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/clik.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -36,6 +36,8 @@ #include "clik.h" +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/config.cpp ./Motion/roboop/config.cpp --- ../Tekkotsu_3.0/Motion/roboop/config.cpp 2006-09-25 19:30:32.000000000 -0400 +++ ./Motion/roboop/config.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -62,6 +62,8 @@ #include #endif +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; @@ -113,21 +115,21 @@ const char *ptr_filename = filename.c_str(); //transform string to *char std::ifstream inconffile(ptr_filename, std::ios::in); - if(inconffile) - { - string temp; - int tmpPos; - map* cursection=NULL; - string parameter, value; + string temp; #ifdef __WATCOMC__ - char tempo[256], tempo2[256]; - inconffile.getline(tempo,sizeof(tempo)); - temp = tempo; + char tempo[256], tempo2[256]; + inconffile.getline(tempo,sizeof(tempo)); + temp = tempo; #else - getline(inconffile, temp); + getline(inconffile, temp); #endif + if(inconffile) + { + int tmpPos; + map* cursection=NULL; + string parameter, value; - while( !inconffile.eof() ) + while( inconffile ) { // Is-it comment line? if(temp[0] != '#') diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/config.h ./Motion/roboop/config.h --- ../Tekkotsu_3.0/Motion/roboop/config.h 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/config.h 2007-11-11 18:57:24.000000000 -0500 @@ -79,10 +79,6 @@ //! @brief Return when a section or parameter does not exist. #define SECTION_OR_PARAMETER_DOES_NOT_EXIST -3 -#ifndef __WATCOMC__ -using namespace std; -#endif - //! @brief Handle configuration files. /*! The file syntax used is: @@ -126,51 +122,51 @@ class Config { public: Config() : conf(), filename() {} - Config(const string & filename_,bool doRead=false); + Config(const std::string & filename_,bool doRead=false); Config(const Config & x); Config & operator=(const Config & x); short read_conf(); void print(); - bool section_exists(const string& section) const; - bool parameter_exists(const string& section, const string& parameter) const; + bool section_exists(const std::string& section) const; + bool parameter_exists(const std::string& section, const std::string& parameter) const; - short select_string(const string section, const string parameter, - string & value) const; - short select_bool(const string section, const string parameter, + short select_string(const std::string section, const std::string parameter, + std::string & value) const; + short select_bool(const std::string section, const std::string parameter, bool & value) const; - short select_short(const string section, const string parameter, + short select_short(const std::string section, const std::string parameter, short & value) const; - short select_int(const string section, const string parameter, + short select_int(const std::string section, const std::string parameter, int & value) const; - short select_float(const string section, const string parameter, + short select_float(const std::string section, const std::string parameter, float & value) const; - short select_double(const string section, const string parameter, + short select_double(const std::string section, const std::string parameter, double & value) const; - short select_real(const string section, const string parameter, + short select_real(const std::string section, const std::string parameter, Real & value) const; - short write_conf(const string name, const string file_title, + short write_conf(const std::string name, const std::string file_title, const int space_between_column); - void add_string(const string section, const string parameter, - const string value); - void add_bool(const string section, const string parameter, + void add_string(const std::string section, const std::string parameter, + const std::string value); + void add_bool(const std::string section, const std::string parameter, const bool value); - void add_int(const string section, const string parameter, + void add_int(const std::string section, const std::string parameter, const int value); - void add_float(const string section, const string parameter, + void add_float(const std::string section, const std::string parameter, const float value); - void add_double(const string section, const string parameter, + void add_double(const std::string section, const std::string parameter, const double value); - void add_real(const string section, const string parameter, + void add_real(const std::string section, const std::string parameter, const Real value); private: //! holds configuration data - a map from section name to sub-map of parameters to values - typedef map > confdata_t; + typedef std::map > confdata_t; confdata_t conf; //!< Data store from/to configuration file. - string filename; //!< Configuration file name. + std::string filename; //!< Configuration file name. }; #ifdef use_namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/control_select.cpp ./Motion/roboop/control_select.cpp --- ../Tekkotsu_3.0/Motion/roboop/control_select.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/control_select.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -36,6 +36,8 @@ #include "control_select.h" +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/control_select.h ./Motion/roboop/control_select.h --- ../Tekkotsu_3.0/Motion/roboop/control_select.h 2005-07-25 23:22:08.000000000 -0400 +++ ./Motion/roboop/control_select.h 2007-11-11 18:57:24.000000000 -0500 @@ -99,11 +99,11 @@ { public: Control_Select(); - Control_Select(const string & filename); + Control_Select(const std::string & filename); Control_Select(const Control_Select & x); Control_Select & operator=(const Control_Select & x); int get_dof(); - void set_control(const string & filename); + void set_control(const std::string & filename); Proportional_Derivative pd; Computed_torque_method ctm; Resolved_acc rra; @@ -111,7 +111,7 @@ short type, //!< Type of controller: PD, CTM,... space_type; //!< JOINT_SPACE or CARTESIAN_SPACE. - string ControllerName; //!< Controller name. + std::string ControllerName; //!< Controller name. private: int dof; //!< Degree of freedom. }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/controller.cpp ./Motion/roboop/controller.cpp --- ../Tekkotsu_3.0/Motion/roboop/controller.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/controller.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -28,6 +28,8 @@ #include "controller.h" +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/dynamics_sim.cpp ./Motion/roboop/dynamics_sim.cpp --- ../Tekkotsu_3.0/Motion/roboop/dynamics_sim.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/dynamics_sim.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -28,6 +28,8 @@ #include "dynamics_sim.h" +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/gnugraph.cpp ./Motion/roboop/gnugraph.cpp --- ../Tekkotsu_3.0/Motion/roboop/gnugraph.cpp 2005-07-25 23:22:08.000000000 -0400 +++ ./Motion/roboop/gnugraph.cpp 2007-11-13 21:38:24.000000000 -0500 @@ -61,6 +61,9 @@ */ #include "gnugraph.h" +#include + +using namespace std; #ifdef use_namespace namespace ROBOOP { @@ -358,7 +361,7 @@ } -short IO_matrix_file::write(const vector & data, const vector & title) +short IO_matrix_file::write(const std::vector & data, const std::vector & title) /*! @brief Write data on disk. @param data: Data. @@ -467,7 +470,7 @@ } -short IO_matrix_file::read(vector & data, vector & data_title) +short IO_matrix_file::read(std::vector & data, std::vector & data_title) //! @brief Read one sequence of data per call. { /* @@ -537,7 +540,7 @@ } -short IO_matrix_file::read_all(vector & data, vector & data_title) +short IO_matrix_file::read_all(std::vector & data, std::vector & data_title) /*! @brief Reads all sequences of data. diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/gnugraph.h ./Motion/roboop/gnugraph.h --- ../Tekkotsu_3.0/Motion/roboop/gnugraph.h 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/gnugraph.h 2007-11-11 18:57:24.000000000 -0500 @@ -90,8 +90,8 @@ int start_y, int end_y); short set_plot2d(const char *title_graph, const char *x_axis_title, const char *y_axis_title, - const vectorlabel, int type, const Matrix &xdata, const Matrix &ydata, - const vector & data_select); + const std::vectorlabel, int type, const Matrix &xdata, const Matrix &ydata, + const std::vector & data_select); // interface class for gnuplot @@ -115,11 +115,11 @@ class GNUcurve { friend class Plot2d; //!< Plot2d need access to private data Matrix xy; //!< n x 2 matrix defining the curve */ - string clabel; //!< string defining the curve label for the legend + std::string clabel; //!< string defining the curve label for the legend int ctype; //!< curve type: lines, points, linespoints, impulses, //!< dots, steps, boxes public: - GNUcurve(const Matrix & data, const string & label = "", int type = LINES); + GNUcurve(const Matrix & data, const std::string & label = "", int type = LINES); GNUcurve(void); GNUcurve(const GNUcurve & gnuc); GNUcurve & operator=(const GNUcurve & gnuc); @@ -132,23 +132,23 @@ @brief 2d plot object. */ class Plot2d { - string + std::string title, //!< Graph title. xlabel, //!< Graph x axis. ylabel; //!< Graph y axis. - string gnucommand; //!< GNU plot command. + std::string gnucommand; //!< GNU plot command. int ncurves; //!< Number of curves. GNUcurve *curves; //!< Pointer to GNUcurve object. public: Plot2d(void); ~Plot2d(void); void dump(void); - void settitle(const string & t); - void setxlabel(const string & t); - void setylabel(const string & t); - void addcurve(const Matrix & data, const string & label = "", int type = LINES); + void settitle(const std::string & t); + void setxlabel(const std::string & t); + void setylabel(const std::string & t); + void addcurve(const Matrix & data, const std::string & label = "", int type = LINES); void gnuplot(void); - void addcommand(const string & gcom); + void addcommand(const std::string & gcom); }; #define IO_COULD_NOT_OPEN_FILE -1 @@ -164,19 +164,19 @@ */ class IO_matrix_file { public: - IO_matrix_file(const string & filename); - short write(const vector & data); - short write(const vector & data, const vector & title); - short read(vector & data); - short read(vector & data, vector & title); - short read_all(vector & data, vector & data_title); + IO_matrix_file(const std::string & filename); + short write(const std::vector & data); + short write(const std::vector & data, const std::vector & title); + short read(std::vector & data); + short read(std::vector & data, std::vector & title); + short read_all(std::vector & data, std::vector & data_title); private: int position_read, //!< Position to read the file. nb_iterations_write, //!< Number of iterations in writing mode. nb_iterations_read, //!< Number of iterations in reading mode. nb_element; //!< Number of elements to read or write. - string filename; //!< File name. + std::string filename; //!< File name. }; @@ -187,13 +187,13 @@ class Plot_file : public IO_matrix_file, Plot2d { public: - Plot_file(const string & filename); - short graph(const string & title_graph, const string & label, const short x, + Plot_file(const std::string & filename); + short graph(const std::string & title_graph, const std::string & label, const short x, const short y, const short x_start, const short y_start, const short y_end); private: - vector data_from_file; //!< Data file. - vector data_title; //!< Data file title. + std::vector data_from_file; //!< Data file. + std::vector data_title; //!< Data file title. }; #ifdef use_namespace diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/homogen.cpp ./Motion/roboop/homogen.cpp --- ../Tekkotsu_3.0/Motion/roboop/homogen.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/homogen.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -47,6 +47,8 @@ #include "robot.h" +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/invkine.cpp ./Motion/roboop/invkine.cpp --- ../Tekkotsu_3.0/Motion/roboop/invkine.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/invkine.cpp 2007-11-16 11:46:45.000000000 -0500 @@ -64,6 +64,8 @@ #include "robot.h" #include +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; @@ -220,7 +222,7 @@ The joint position vector before the inverse kinematics is returned if the algorithm does not converge. */ -{ +{ ColumnVector qout, dq, q_tmp; UpperTriangularMatrix U; //int deb=0; @@ -598,6 +600,10 @@ case ERS2XX_HEAD: case ERS7_HEAD: //no specializations yet... :( + case PANTILT: + case GOOSENECK: + return inv_kin_goose_neck(Tobj); + case CRABARM: default: return Robot_basic::inv_kin(Tobj, mj, endlink, converge); } @@ -620,6 +626,11 @@ case RHINO: case PUMA: //no specializations yet... :( + case PANTILT: + return inv_kin_pan_tilt(Pobj, converge); + case GOOSENECK: + return inv_kin_goose_neck_pos(Pobj); + case CRABARM: default: return Robot_basic::inv_kin_pos(Pobj, mj, endlink, Plink, converge); } @@ -641,13 +652,15 @@ case RHINO: case PUMA: //no specializations yet... :( + case PANTILT: + case GOOSENECK: +// return inv_kin_goose_neck_orientation(Robj) + case CRABARM: default: return Robot_basic::inv_kin_orientation(Robj, mj, endlink, converge); } } - - ReturnMatrix Robot::inv_kin_rhino(const Matrix & Tobj, bool & converge) /*! @brief Analytic Rhino inverse kinematics. @@ -909,7 +922,155 @@ return qout; } +ReturnMatrix Robot::inv_kin_pan_tilt(const ColumnVector & Pobj, bool & converge) +/* + @brief Inverse Kinematics of Pan Tilt Robot + @param Pobj: Vector expressing the desired end effector position + @param converge: Indicate if the algorithm converge. +*/ +{ + //std::cout << "Inv_Kine Pan Tilt!" << std::endl; + ColumnVector qout, qtmp, /* Joint angle vectors */ + xyz1, xyz2, /* Frame 1 and 2 coordinates */ + xyz0 = Pobj; /* Base frame coordinates */ + Matrix M01, /* Matrix to convert coordinates from base (frame 0) to frame 1 */ + M12; /* Matrix to convert coordinates from frame 1 to frame 2 */ + + qtmp = get_q(); + M01 = convertFrame(1,2); + //std::cout << "Matrix M01" << std::endl << setw(5) << M01 << std::endl; + xyz1 = M01*xyz0; + //std::cout << xyz1(1) << " " << xyz1(2) << " " << xyz1(3) << std::endl; + qtmp(2)=atan2(xyz1(2),xyz1(1)); + set_q(qtmp); + M12 = convertFrame(2,3); + //std::cout << "Matrix M12" << std::endl << setw(5) << M12 << std::endl; + xyz2 = M12*xyz1; + //std::cout << xyz2(1) << " " << xyz2(2) << " " << xyz2(3) << std::endl; + qtmp(3)=atan2(xyz2(2),xyz2(1)); + set_q(qtmp); + +//Now I have to check to see if the angles lie within the ranges of the pan and tilt +//If not, set angles to closest min/max value. + if( qtmp(2) < links[2].get_theta_min() ) + qtmp(2) = links[2].get_theta_min(); + if( qtmp(2) > links[2].get_theta_max() ) + qtmp(2) = links[2].get_theta_max(); + if( qtmp(3) < links[3].get_theta_min() ) + qtmp(3) = links[3].get_theta_min(); + if( qtmp(3) > links[3].get_theta_max() ) + qtmp(3) = links[3].get_theta_max(); + //std::cout << "inv_kin_pan_tilt computed the values:" << endl; + //std::cout << "Pan: "<< qtmp(2) << " Tilt: " << qtmp(3) << std::endl; + qout = qtmp; + converge=true; + return qout; +} + +ReturnMatrix Robot::inv_kin_goose_neck(const Matrix & Tobj) +/* +*/ +{ + //std::cout << "inv_kin_goose_neck was called!" << std::endl; + ColumnVector qout, Pobj(3); + Real phi; + Pobj(1) = Tobj(1,4); + Pobj(2) = Tobj(2,4); + Pobj(3) = Tobj(3,4); + phi = atan2(Tobj(3,3),Tobj(1,3)); + qout = goose_neck_angles(Pobj, phi); + return qout; +} + +ReturnMatrix Robot::inv_kin_goose_neck_pos(const ColumnVector & Pobj) +/* +*/ +{ + //std::cout << "inv_kin_goose_neck_pos was called!" << std::endl; + ColumnVector qout; + qout = goose_neck_angles(Pobj, -1.57079632679); + return qout; +} + +/*ReturnMatrix Robot::inv_kin_goose_neck_orientation(const Matrix & Robj) +{ + +} +*/ + +ReturnMatrix Robot::goose_neck_angles(const ColumnVector & Pobj, Real phi) +/* +*/ +{ + Real c2, + qp, q1, q2, q3, //phi=-1.57079632679, //phi is the Tool Orientation + //this phi puts the tool above the target + K1, K2, + L1=links[2].get_a(),//Planar Link Lengths + L2=links[3].get_a(), + L3=links[5].get_d(); + ColumnVector qtmp, qout, + xyz0 = Pobj, + xyz_t,xyz_w; + Matrix M01, M12; + bool valid; + + qout = get_q(); + qtmp = qout; + qp = atan2(xyz0(2),xyz0(1)); + //std::cout << "Neck Pan: " << qp << std::endl; + qtmp(2)=qp; + set_q(qtmp); //This will make the base pan + + M01 = convertFrame(1,2); + + //std::cout << "Matrix M01" << std::endl << setw(5) << M01 << std::endl; + xyz_t = M01 * xyz0; //xyz_t are the tool tip coordinates + //std::cout << xyz_t(1) << " " << xyz_t(2) << " " << xyz_t(3) << std::endl; + //Compute the wrist position + xyz_w = xyz_t; //This makes xyz_w a 4x1 matrix + xyz_w(1)=xyz_t(1)-L3*cos(phi); + xyz_w(2)=xyz_t(2)-L3*sin(phi); + + //std::cout << "The wrist is to be placed at (" << xyz_w(1) << "," << xyz_w(2) << ")." << std::endl; + + c2 = ( ( (xyz_w(1)*xyz_w(1)) + (xyz_w(2)*xyz_w(2)) - ( (L1*L1) + (L2*L2) ) ) / ( 2 * L1 * L2 ) ); + //std::cout << "Cosine Theta2 is " << c2 << std::endl; + + if ( (c2*c2) > 1){ + c2 = sign(c2); + valid = false; + } + else + valid = true; +/* + s2plus = sqrt(1-(c2*c2)); + std::cout << "Sine Theta2 is " << s2plus << std::endl; + q2 = atan2(s2plus,c2); //Compute q2 +*/ + q2 = -acos(c2); + +// K1 = L1 + (L2 * c2); +// K2 = L2 * s2plus; + + K1 = L1 + (L2*cos(q2)); + K2 = L2 * sin(q2); + + q1 = atan2(xyz_w(2),xyz_w(1)) - atan2(K2,K1); //Compute q1 + + q3 = phi - q1 - q2; //Compute q3 + //std::cout << "The angles are " << qp << " " << q1 << " " << q2 << " " << q3 << std::endl; + qtmp(2)=qp; qtmp(3)=q1; qtmp(4)=q2; qtmp(5)=q3; + set_q(qtmp); + + if(valid) + return qtmp; + else + return qout; +} + ReturnMatrix Robot::inv_kin_ers_pos(const ColumnVector & Pobj, const int endlink, const ColumnVector& Plink, bool & converge) { + //std::cout << "Called inv_kin_ers_pos!" << std::endl; bool converges[3]; bool third_invert=(robotType==ERS7_HEAD || robotType==ERS2XX_HEAD); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/quaternion.cpp ./Motion/roboop/quaternion.cpp --- ../Tekkotsu_3.0/Motion/roboop/quaternion.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/quaternion.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -55,6 +55,8 @@ #include "quaternion.h" +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/robot.cpp ./Motion/roboop/robot.cpp --- ../Tekkotsu_3.0/Motion/roboop/robot.cpp 2005-07-25 23:22:08.000000000 -0400 +++ ./Motion/roboop/robot.cpp 2007-11-11 18:57:24.000000000 -0500 @@ -99,6 +99,7 @@ #include #endif +using namespace std; #ifdef use_namespace namespace ROBOOP { @@ -1408,21 +1409,27 @@ Identify the inverse kinematics analytic solution based on the similarity of the robot DH parameters and - the DH parameters of know robots (ex: Puma, Rhino, ...). + the DH parameters of known robots (ex: Puma, Rhino, ...). The inverse kinematics will be based on a numerical alogorithm if there is no match . */ { - if ( Puma_DH(this)) + if ( Puma_DH(this) ) robotType = PUMA; - else if ( Rhino_DH(this)) + else if ( Rhino_DH(this) ) robotType = RHINO; - else if ( ERS_Leg_DH(this)) + else if ( ERS_Leg_DH(this) ) robotType = ERS_LEG; - else if ( ERS2xx_Head_DH(this)) + else if ( ERS2xx_Head_DH(this) ) robotType = ERS2XX_HEAD; - else if ( ERS7_Head_DH(this)) + else if ( ERS7_Head_DH(this) ) robotType = ERS7_HEAD; + else if ( PanTilt_DH(this) ) + robotType = PANTILT; + else if ( Goose_Neck_DH(this) ) + robotType = GOOSENECK; + else if ( Crab_Arm_DH(this) ) + robotType = CRABARM; else robotType = DEFAULT; } @@ -1752,6 +1759,51 @@ return false; } +bool PanTilt_DH(const Robot_basic *robot) +/* + @brief Return true if robot is like PanTilt on DH notation + + Compare the robot DH table with the PanTilt DH table. The function returns + true if the two are similar. +*/ +{ + if(robot->get_available_dof()==2) + for(int i=1; i < robot->get_dof(); i++) + if( robot->links[i].get_immobile()==false && + robot->links[i+1].get_immobile()==false && + robot->links[i+1].get_alpha() != 0 ) + return true; + return false; +} + +bool Goose_Neck_DH(const Robot_basic *robot) +/* +*/ +{ + if(robot->get_dof()==5) + if( robot->links[1].get_alpha() != 0 && + robot->links[2].get_alpha() == 0 && + robot->links[3].get_alpha() == 0 && + robot->links[4].get_immobile() == 1 && + robot->links[5].get_theta() > 0 ) + return true; + return false; +} + +bool Crab_Arm_DH(const Robot_basic *robot) +{ + if(robot->get_available_dof()==5) + if( robot->links[1].get_immobile() == 1 && + robot->links[1].get_theta() > 0 && + robot->links[1].get_alpha() > 0 && + robot->links[2].get_alpha() > 0 && + robot->links[3].get_theta() > 0 && + robot->links[4].get_alpha() == 0 && robot->links[4].get_theta() == 0 && + robot->links[5].get_theta() < 0 && robot->links[5].get_alpha() < 0 && + robot->links[6].get_theta() < 0 ) + return true; + return false; +} bool Puma_mDH(const Robot_basic *robot) /*! @@ -1768,7 +1820,7 @@ for (int j = 1; j <= 6; j++) { if (robot->links[j].get_joint_type()) // All joints are rotoide - return false; + return false; a[j] = robot->links[j].get_a(); d[j] = robot->links[j].get_d(); alpha[j] = robot->links[j].get_alpha(); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/robot.h ./Motion/roboop/robot.h --- ../Tekkotsu_3.0/Motion/roboop/robot.h 2005-07-25 23:22:08.000000000 -0400 +++ ./Motion/roboop/robot.h 2007-11-11 18:57:24.000000000 -0500 @@ -226,7 +226,7 @@ const bool min_inertial_para = false); explicit Robot_basic(const Matrix & initrobot, const Matrix & initmotor, const bool dh_parameter = false, const bool min_inertial_para = false); - explicit Robot_basic(const Config & robData, const string & robotName, + explicit Robot_basic(const Config & robData, const std::string & robotName, const bool dh_parameter = false, const bool min_inertial_para = false); Robot_basic(const Robot_basic & x); virtual ~Robot_basic(); @@ -309,7 +309,7 @@ ReturnMatrix dtau_dqp(const ColumnVector & q, const ColumnVector & qp); virtual ReturnMatrix G() = 0; virtual ReturnMatrix C(const ColumnVector & qp) = 0; - void error(const string & msg1) const; + void error(const std::string & msg1) const; //! useful for fixing x to be at least min or at most max static Real limit_range(Real x, Real min, Real max) { return x>max?max:(x + +using namespace std; #ifdef use_namespace namespace ROBOOP { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/trajectory.h ./Motion/roboop/trajectory.h --- ../Tekkotsu_3.0/Motion/roboop/trajectory.h 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/trajectory.h 2007-11-11 18:57:25.000000000 -0500 @@ -111,7 +111,7 @@ #define CARTESIAN_SPACE 2 //! @brief Data at control points. -typedef map< Real, ColumnVector, less< Real > > point_map; +typedef std::map< Real, ColumnVector, std::less< Real > > point_map; /*! @@ -122,7 +122,7 @@ { public: Spl_path():Spl_cubic(){}; - Spl_path(const string & filename); + Spl_path(const std::string & filename); Spl_path(const Matrix & x); Spl_path(const Spl_path & x); Spl_path & operator=(const Spl_path & x); @@ -140,7 +140,7 @@ //! @brief Data at control points. -typedef map< Real, Quaternion, less< Real > > quat_map; +typedef std::map< Real, Quaternion, std::less< Real > > quat_map; /*! @@ -151,7 +151,7 @@ { public: Spl_Quaternion(){} - Spl_Quaternion(const string & filename); + Spl_Quaternion(const std::string & filename); Spl_Quaternion(const quat_map & quat); Spl_Quaternion(const Spl_Quaternion & x); Spl_Quaternion & operator=(const Spl_Quaternion & x); @@ -170,11 +170,11 @@ { public: Trajectory_Select(); - Trajectory_Select(const string & filename); + Trajectory_Select(const std::string & filename); Trajectory_Select(const Trajectory_Select & x); Trajectory_Select & operator=(const Trajectory_Select & x); - void set_trajectory(const string & filename); + void set_trajectory(const std::string & filename); short type; //!< Cartesian or joint space Spl_path path; //!< Spl_path instance. diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/utils.cpp ./Motion/roboop/utils.cpp --- ../Tekkotsu_3.0/Motion/roboop/utils.cpp 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/utils.cpp 2007-11-11 18:57:25.000000000 -0500 @@ -53,6 +53,8 @@ #include "robot.h" #include +using namespace std; + #ifdef use_namespace namespace ROBOOP { using namespace NEWMAT; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/utils.h ./Motion/roboop/utils.h --- ../Tekkotsu_3.0/Motion/roboop/utils.h 2005-07-25 23:22:09.000000000 -0400 +++ ./Motion/roboop/utils.h 2007-11-11 18:57:25.000000000 -0500 @@ -77,12 +77,8 @@ using namespace NEWMAT; #endif //! @brief RCS/CVS version. - static const char header_utils_rcsid[] __UNUSED__ = "$Id: utils.h,v 1.5 2005/07/26 03:22:09 ejt Exp $"; + static const char header_utils_rcsid[] __UNUSED__ = "$Id: utils.h,v 1.6 2007/11/11 23:57:25 ejt Exp $"; -#ifndef __WATCOMC__ -using namespace std; -#endif - #ifndef M_PI #define M_PI 3.14159265358979 #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/README ./README --- ../Tekkotsu_3.0/README 2005-08-09 19:10:47.000000000 -0400 +++ ./README 2007-11-09 14:01:19.000000000 -0500 @@ -1,7 +1,7 @@ Welcome to the Tekkotsu framework. Unless otherwise noted, all source code and related files are -Copyright 2005, Carnegie Mellon University Tekkotsu Lab -Released under the LGPL. +Copyright 2007, Carnegie Mellon University Tekkotsu Lab +Released under the LGPL, see LICENSE. Documentation and Usage Guides: ------------------------------ @@ -24,14 +24,6 @@ ------------------ project - project template directory, copy to another location for local development - * Non-Source Framework Files * - -------------------------- - contrib - additional code which either hasn't been inlined, or the - original submissions of code that has been imported (thanks!) - docs - scripts, configuration, and other files for the doxygen documentation - tools - build scripts, utilities, and PC-side tools. - deprecated - archaic source, but may still be of some interest - * Source Files * ------------ @@ -40,11 +32,13 @@ aperios - provides support for Sony AIBO robots (through OPEN-R SDK) (includes MMCombo, which forks into Main and Motion processes, in addition to Sound and TinyFTPD processes) - local - provides simulation support for the host platform (UNIX variants) + local - provides simulation support for the host platform (UNIX variants), + as well as communication and device drivers for various hardware. -General Source Code- ------------------- Behaviors - Base classes and demo code + DualCoding - Vision processing package, see http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/vr-intro.shtml Events - Base classes and 'custom' events IPC - Inter-Process Communication, mutual exclusion and message passing Motion - Most motion related classes @@ -52,3 +46,11 @@ Sound - Handles mixing and sending sound buffers to system Vision - Vision processing code Wireless - Networking code + + * Non-Source Framework Files * + -------------------------- + contrib - additional code which either hasn't been inlined, or the + original submissions of code that has been imported (thanks!) + docs - scripts, configuration, and other files for the doxygen documentation + tools - build scripts, utilities, and PC-side tools. + deprecated - archaic source, but may still be of some interest diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Buffer.h ./Shared/Buffer.h --- ../Tekkotsu_3.0/Shared/Buffer.h 2006-09-16 02:28:08.000000000 -0400 +++ ./Shared/Buffer.h 2007-11-09 13:08:29.000000000 -0500 @@ -42,7 +42,7 @@ //! Tries to fill the buffer from current position up to the limit mark. Advances the position, src and srcLen. Returns true if the buffer has been filled. bool Fill(const char*&src, int& srcLen); //! Tries to fill the buffer from current position up to the limit mark. Advances the position, src and srcLen. Returns true if the buffer has been filled. - bool Fill(char*& src, int& srcLen) { return Fill((const char*&) src, srcLen); } + bool Fill(char*& src, int& srcLen) { return Fill(const_cast(src), srcLen); } //! Checks whether the buffer is full, that is position == limit. bool IsFull() const { return (position >= limit); } private: @@ -51,7 +51,7 @@ int limit; //!< Position is the index of the current element in the buffer (used only by buffer filling operations at the moment) int position; //!< Limit is the virtual size of the buffer. Operations such as filling up the buffer, seeking and so on never go over the limit mark of the buffer. - //! returns the lesser of @a or @b + //! returns the lesser of @a a or @a b static int min(int a, int b) { return ((a < b) ? a : b); } }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/CommonERSInfo.h ./Shared/CommonERSInfo.h --- ../Tekkotsu_3.0/Shared/CommonERSInfo.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/CommonERSInfo.h 2007-11-09 13:08:29.000000000 -0500 @@ -0,0 +1,48 @@ +//-*-c++-*- +#ifndef INCLUDED_CommonERSInfo_h +#define INCLUDED_CommonERSInfo_h + +#include +#ifndef PLATFORM_APERIOS +typedef unsigned short word; //!< otherwise defined in Types.h +#else +#include +#endif + +#include "CommonInfo.h" +using namespace RobotInfo; + +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags + +#if defined(TGT_ERS210) || defined(TGT_ERS220) || defined(TGT_ERS2xx) || defined(TGT_ERS7) + +//! Should only be used to specialize/optimize for the Aibo +# define TGT_IS_AIBO + +# define TGT_HAS_LEGS 4 +# define TGT_HAS_LED_PANEL 1 +# define TGT_HAS_ACCELEROMETERS 3 +# ifndef TGT_ERS220 +# define TGT_HAS_MOUTH 1 +# define TGT_HAS_TAIL 1 +# endif +# define TGT_HAS_POWER_STATUS +# define TGT_HAS_CAMERA 1 +# define TGT_HAS_HEAD 1 +# define TGT_HAS_MICROPHONE 2 +# define TGT_HAS_SPEAKERS 1 + +#endif + +/*! @file + * @brief Defines some capabilities common to all Aibo robots + * @author ejt (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.11 $ + * $State: Exp $ + * $Date: 2007/11/09 18:08:29 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/CommonInfo.h ./Shared/CommonInfo.h --- ../Tekkotsu_3.0/Shared/CommonInfo.h 2006-10-03 22:42:03.000000000 -0400 +++ ./Shared/CommonInfo.h 2007-11-09 14:01:13.000000000 -0500 @@ -2,34 +2,175 @@ #ifndef INCLUDED_CommonInfo_h_ #define INCLUDED_CommonInfo_h_ +#include +#include +#include +#include + namespace RobotInfo { - //! the ordering of legs - enum LegOrder_t { - LFrLegOrder = 0, //!< left front leg - RFrLegOrder, //!< right front leg - LBkLegOrder, //!< left back leg - RBkLegOrder //!< right back leg - }; + //! Defines the indexes to use as indices to access the min and max entries of joint limit specifications (e.g. ERS7Info::outputRanges and ERS7Info::mechanicalLimits) + enum MinMaxRange_t { MinRange,MaxRange }; - //! The offsets within appendages (the legs) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the head's TPROffset_t's) - enum REKOffset_t { - RotatorOffset=0, //!< moves leg forward or backward along body - ElevatorOffset, //!< moves leg toward or away from body - KneeOffset //!< moves knee - }; + //! Some target models, such as ERS2xxInfo, may be dual-booting compatability modes. This function returns the actual robot name (e.g. ERS210Info::TargetName or ERS220Info::TargetName) + /*! This function should return the actual RobotInfo::TargetName and not a hard coded string. + * This way, we can rely on testing equality with a direct pointer comparison instead of strcmp(). + * (Also eliminates chance of typo or missing refactorization if renamed!). + * + * The result of this function is stored in #RobotName, so you don't need to call + * this function -- the only reason it's declared in the header is so you can call + * it during static initialization, when you can't rely on RobotName having been + * initialized yet. */ + const char* const detectModel(); - //! The offsets of appendages with tilt (elevation), pan (heading), and roll or nod joints (i.e. head) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the leg's REKOffset_t's) - enum TPROffset_t { - TiltOffset = 0, //!< tilt/elevation (vertical) - PanOffset, //!< pan/heading (horizontal) - RollOffset, //!< roll (rotational) - NodOffset=RollOffset //!< nod (second tilt) + //! Name of the robot which is actually running + /*! This is usually set to the TargetName, but if the target model is a "compatability" target, + * where the actual host hardware may be a different (more restrictive) configuration, + * then RobotName will be set to the TargetName of that configuration. + * + * Note that you should be able to rely on doing pointer comparisons + * between RobotName and various TargetNames to test for different robot models, + * instead of using strcmp() for each. + * + * However, a std::string is used on Aperios to transparently trigger the strcmp because + * of the way the process model is handled there screws up the pointer comparison + * (a different process does the static initialization, so we get a pointer relative to its + * memory space instead of the one we're executing in. Unix-based platforms don't + * have this problem by using a "real" fork() operation.) */ +#ifndef PLATFORM_APERIOS + extern const char* const RobotName; +#else // have to use a string because aperios is annoying like that + extern const std::string RobotName; +#endif + + //! Allows behaviors to lookup output/button/sensor names from other models to support basic cross-model portability + /*! Use the getCapabilities() function to look up the Capabalities instance for a given model based on its string robot name */ + class Capabilities { + friend Capabilities* getCapabilities(const std::string& robName); + public: + //! constructor, pass the robot name this is regarding, and outputs, buttons, and sensor names + Capabilities(const char* robName, size_t numOut, const char * const outNames[], size_t numBut, const char * const butNames[], size_t numSen, const char * const senNames[], size_t pidOff, size_t numPID, size_t ledOff, size_t numLED); + //! shallow copy (explicit to satisfy warning) + Capabilities(const Capabilities& cap) + : name(cap.name), numOutputs(cap.numOutputs), numButtons(cap.numButtons), numSensors(cap.numSensors), + outputs(cap.outputs), buttons(cap.buttons), sensors(cap.sensors), + outputToIndex(cap.outputToIndex), buttonToIndex(cap.buttonToIndex), sensorToIndex(cap.sensorToIndex), + pidJointOffset(cap.pidJointOffset), numPIDJoints(cap.numPIDJoints), ledOffset(cap.ledOffset), numLEDs(cap.numLEDs), + fakeOutputs() {} + //! shallow assign (explicit to satisfy warning) + Capabilities& operator=(const Capabilities& cap) { + name=cap.name; + numOutputs=cap.numOutputs; numButtons=cap.numButtons; numSensors=cap.numSensors; + outputs=cap.outputs; buttons=cap.buttons; sensors=cap.sensors; + outputToIndex=cap.outputToIndex; buttonToIndex=cap.buttonToIndex; sensorToIndex=cap.sensorToIndex; + pidJointOffset=cap.pidJointOffset; numPIDJoints=cap.numPIDJoints; ledOffset=cap.ledOffset; numLEDs=cap.numLEDs; + fakeOutputs=cap.fakeOutputs; + return *this; + } + //! destructor, explicit just to avoid warning when used as base class + virtual ~Capabilities() {} + + //! returns the name of the robot this corresponds to + inline const char * getRobotName() const { return name; } + + //! returns the number of unique outputs (i.e. not counting aliases) + inline unsigned int getNumOutputs() const { return numOutputs; } + //! returns the number of unique buttons (i.e. not counting aliases) + inline unsigned int getNumButtons() const { return numButtons; } + //! returns the number of unique sensors (i.e. not counting aliases) + inline unsigned int getNumSensors() const { return numSensors; } + + //! look up the name corresponding to an offset, returns NULL if not found/available + inline const char * getOutputName(unsigned int i) const { return i& getFakeOutputs() const { return fakeOutputs; } + + protected: + //! helper function, does the work of the get..Offset functions + inline unsigned int lookupT(const char * errStr, const std::map& nameToIndex, const char * capname) const { + std::map::const_iterator it=nameToIndex.find(capname); + if(it==nameToIndex.end()) { + std::string str; str.append(name).append("::capabilities could not find ").append(errStr).append(" named ").append(capname); + throw std::invalid_argument(str); + } + return it->second; + } + //! helper function, does the work of the find..Offset functions + inline unsigned int lookup(const std::map& nameToIndex, const char * capname) const { + std::map::const_iterator it=nameToIndex.find(capname); + return it==nameToIndex.end() ? -1U : it->second; + } + + const char* name; //!< name of robot model + size_t numOutputs; //!< length of #outputs + size_t numButtons; //!< length of #buttons + size_t numSensors; //!< length of #sensors + const char * const * outputs; //!< array of names for outputs -- this is the "primary" name for each output, #outputToIndex may contain additional aliases + const char * const * buttons; //!< array of names for buttons -- this is the "primary" name for each button, #buttonToIndex may contain additional aliases + const char * const * sensors; //!< array of names for sensors -- this is the "primary" name for each sensor, #sensorToIndex may contain additional aliases + std::map outputToIndex; //!< maps output names to offset values + std::map buttonToIndex; //!< maps button names to offset values + std::map sensorToIndex; //!< maps sensor names to offset values + + size_t pidJointOffset; //!< the offset of the PID joints + size_t numPIDJoints; //!< the number of PID joints + size_t ledOffset; //!< the offset of the LEDs + size_t numLEDs; //!< the number of LEDs + + //! Offsets of "fake" outputs, which don't correspond to any physical device on the robot + /*! This is used in compatability modes, where some outputs may not be available on the + * host hardware, or for meta-outputs, which control the interpretation of other outputs. + * (such as the A/B LED mode setting for the ERS-7, where a "virtual" LED switches + * the system's intepretation of the face panel LEDs). + * + * Most robots can probably just leave this empty -- on Aperios the "fake" outputs are + * skipped when interfacing with the system and their values receive feedback from + * the motion process. When using the tekkotsu executable under unix-based systems, + * the HAL layer handles this functionality via its own configuration settings, and these + * values are ignored. */ + std::set fakeOutputs; + + //! returns a static map from robot names to capability instances, which are externally allocated + /*! The Capabilties base class will automatically insert entries into this collection. */ + static std::map& getCaps(); }; - //! Defines the indexes to use as indices to access the min and max entries of joint limit specifications (e.g. ERS7Info::outputRanges and ERS7Info::mechanicalLimits) - enum MinMaxRange_t { MinRange,MaxRange }; - } /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Config.cc ./Shared/Config.cc --- ../Tekkotsu_3.0/Shared/Config.cc 2006-09-27 16:36:06.000000000 -0400 +++ ./Shared/Config.cc 2007-11-16 10:53:49.000000000 -0500 @@ -1,36 +1,255 @@ -#include "Shared/Config.h" -#include "Shared/ProjectInterface.h" -#include "Behaviors/Mon/RawCamBehavior.h" -#include "Vision/RawCameraGenerator.h" -#include "Vision/SegmentedColorGenerator.h" -#include -#include +#include "Config.h" +#include +#include +#include +#include +#include +#include #include -#include -#include "Wireless/Socket.h" +#include +#include #ifdef PLATFORM_APERIOS -# include # include #else #include #include -typedef unsigned int OSpeakerVolume; -const OSpeakerVolume ospkvolinfdB = 0x8000; -const OSpeakerVolume ospkvol25dB = 0xe700; -const OSpeakerVolume ospkvol18dB = 0xee00; -const OSpeakerVolume ospkvol10dB = 0xf600; #endif +#include "Shared/ProjectInterface.h" +#include "Shared/string_util.h" +//#include "Behaviors/Mon/RawCamBehavior.h" +#include "Vision/RawCameraGenerator.h" +//#include "Vision/SegmentedColorGenerator.h" +//#include "Wireless/Socket.h" +#include "Shared/debuget.h" -using namespace std; +/*! Explicitly declaring these values allows us to relegate storage to a +* single translation unit instead of having it reallocated every time +* the class is referenced. This actually adds up to megabytes of +* symbols (especially with debugging info). */ +//! @name plist::NamedEnumeration statics +//! provides string names for enumeration values (see plist::NamedEnumeration and #INSTANTIATE_NAMEDENUMERATION_STATICS) +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::main_config::consoleMode_t); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::sound_config::volume_levels); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::transports); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::vision_config::RawCamConfig::compression_t); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::vision_config::RawCamConfig::encoding_t); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::vision_config::SegCamConfig::compression_t); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::vision_config::gain_levels); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::vision_config::shutter_speeds); +INSTANTIATE_NAMEDENUMERATION_STATICS(Config::vision_config::white_balance_levels); +INSTANTIATE_NAMEDENUMERATION_STATICS(J_DCT_METHOD); +//@} Config* config=NULL; +const std::locale& Config::curLocale=std::locale::classic(); + +const std::string ConfigDictionary::msPrefix="Model"; +const std::string ConfigDictionary::msSep=":"; +//const std::string ConfigDictionary::msNum="#"; +std::string ConfigDictionary::curModel; + +const char * Config::xmlIntro1="& seen) const { + // if not a model specific key, just load it normally + if(key.substr(0,msPrefix.size())!=msPrefix) + return plist::Dictionary::saveOverXMLNode(k,val,key,comment,indentStr,seen); + + //otherwise, strip off enumeration serial number (if any) + //std::string ks=key.substr(0,key.find(msNum)); + const std::string& ks=key; + + //see if additional parameters in the key + if(ks.size()<=msPrefix.size() || ks.substr(msPrefix.size(),msSep.size())!=msSep) { + // not a valid model specific string, treat as normal key + return plist::Dictionary::saveOverXMLNode(k,val,key,comment,indentStr,seen); + } + + //prefix plus pattern (at least) -- check pattern + std::string::size_type patStart=msPrefix.size()+msSep.size(); + std::string::size_type patEnd=ks.find(msSep,patStart); + std::string pattern=ks.substr(patStart,patEnd-patStart); + if(!matchNoCase(curModel,pattern)) + return true; //doesn't apply to the current model (still return true though because it's not an error, just a no-op) + if(patEnd==std::string::npos) { + // prefix plus pattern only -- save subnodes + saveXML(val,true,seen); + return true; + } else { + // prefix plus pattern plus single item -- save over it + const std::string skey=ks.substr(patEnd+1); + return plist::Dictionary::saveOverXMLNode(k,val,skey,comment,indentStr,seen); + } +} + +bool ConfigDictionary::matchNoCase(const std::string& model, const std::string& pattern) { + unsigned int i=0; + if(i==pattern.size() && i==model.size()) + return true; + if(i==pattern.size() || i==model.size()) + return false; + while(pattern[i]!='*') { + if(toupper(pattern[i])!=toupper(model[i])) + return false; + i++; + if(i==pattern.size() && i==model.size()) + return true; + if(i==pattern.size() || i==model.size()) + return false; + } + i=pattern.size()-1; + unsigned int j=model.size()-1; + while(pattern[i]!='*') { + if(toupper(pattern[i])!=toupper(model[j])) + return false; + i--; j--; + } + return true; +} + +void Config::saveXML(xmlNode* node, bool onlyOverwrite, std::set& seen) const { + if(node==NULL) + return; + if(node->children==NULL) { + std::string indentStr=getIndentationPrefix(node); + const char* headerComment="\n" + "##################################################################\n" + "###################### Tekkotsu config #######################\n" + "##################################################################\n" + //note the use of "s to break the string to avoid keyword substitution in the header... + "##################### $" "Revision: $ ######################\n" + "################ $" "Date: $ ################\n" + "##################################################################\n" + "\n" + "This is an XML-based format using the Property List (plist) layout.\n" + "\n" + "As a slight extension to standard plists, you can specify\n" + "model-specific settings by prepending a key with:\n" + " Model:MODEL_PATTERN:KEY_NAME\n" + "For example, to use different 'thresh' settings on the ERS-2xx\n" + "series vs. the ERS-7 model, you would use the keys:\n" + " Model:ERS-2*:thresh\n" + " Model:ERS-7:thresh\n" + "You can filter several items in a group by leaving off the second\n" + "':' and name, and providing a dictionary as the value. If the\n" + "model matches, all entries from the dictionary are imported into\n" + "the parent dictionary.\n" + "\n" + "You can change these settings at run time from the Controller\n" + "by entering the command:\n" + " !set section_name.variable=value\n" + "or by using the configuration editor found in the \"File Access\"\n" + "menu. Paths are assumed to be relative to the 'project/ms/'\n" + "directory. For example, the primary configuration file would be\n" + "referenced as 'config/tekkotsu.xml'\n" + "\n" + "See also the 'simulator.xml' file, which provides you the ability\n" + "to override settings when running in the simulator\n"; + xmlAddChild(node,xmlNewComment((const xmlChar*)headerComment)); + xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); + } + ConfigDictionary::saveXML(node,onlyOverwrite,seen); +} + +unsigned int Config::loadBuffer(const char buf[], unsigned int len) { + if(strncmp(buf,xmlIntro1,strlen(xmlIntro1))==0 || strncmp(buf,xmlIntro2,strlen(xmlIntro2))==0 || strncmp(buf,xmlIntro3,strlen(xmlIntro3))==0) + return plist::Dictionary::loadBuffer(buf,len); + return loadOldFormat(buf,len); +} + +unsigned int Config::loadFile(const char* filename) { + std::string path=portPath(filename); + bool isXML; + { + std::ifstream in(path.c_str()); + std::string line; + std::getline(in,line); + isXML = (strncmp(line.c_str(),xmlIntro1,strlen(xmlIntro1))==0 || strncmp(line.c_str(),xmlIntro2,strlen(xmlIntro2))==0 || strncmp(line.c_str(),xmlIntro3,strlen(xmlIntro3))==0); + } + if(isXML) + return plist::Dictionary::loadFile(path.c_str()); + FILE* fp = fopen(path.c_str(), "r"); + if (fp==NULL) { + std::cerr << "ERROR: Config could not open file '" << path.c_str() << "' for loading." << std::endl; + return 0; + } + try { + unsigned int ans=loadOldFormat(fp); + fclose(fp); + return ans; + } catch(...) { + fclose(fp); + throw; + } +} + +unsigned int Config::loadFileStream(FILE* f) { + std::string line; + char c=fgetc(f); + while(c!='\n' && c!=EOF) { + line+=c; + c=fgetc(f); + } + bool isXML = (strncmp(line.c_str(),xmlIntro1,strlen(xmlIntro1))==0 || strncmp(line.c_str(),xmlIntro2,strlen(xmlIntro2))==0 || strncmp(line.c_str(),xmlIntro3,strlen(xmlIntro3))==0); + if(fseek(f,line.size()+1,SEEK_CUR)!=0) { +#ifdef PLATFORM_APERIOS + int merrno=errno; + std::cerr << "Warning: error on seek: " << strerror(merrno) << std::endl; +#else + char err[100]; + strerror_r(errno,err,100); + std::cerr << "Warning: error on seek: " << err << std::endl; +#endif + } + if(isXML) + return plist::Dictionary::loadFileStream(f); + return loadOldFormat(f); +} void Config::setFileSystemRoot(const std::string& fsr) { #ifdef PLATFORM_APERIOS - if(fsr[0]=='/') - fsRoot="/ms"+fsr; - else - fsRoot="/ms/"+fsr; + fsRoot=fsr; #else char buf[MAXPATHLEN+2]; if(getcwd(buf,MAXPATHLEN+2)==NULL) @@ -67,635 +286,252 @@ } } -void* Config::setValue(section_t section, const char *key, const char *value, bool /*updated*/) { - switch (section) { - case sec_wireless: - if (strncasecmp(key,"id",29)==0) { - wireless.id=atoi(value); - return &wireless.id; - } - break; - case sec_vision: - if (strncasecmp(key,"white_balance",29)==0) { - if (strncasecmp(value,"indoor",49)==0) { - vision.white_balance=1; - } else if (strncasecmp(value,"flourescent",49)==0) { - std::cout << "Your tekkotsu.cfg file uses deprecated 'flourescent' (misspelled) -- use 'fluorescent' instead" << std::endl; - vision.white_balance=3; - } else if (strncasecmp(value,"fluorescent",49)==0) { - vision.white_balance=3; - } else if (strncasecmp(value,"outdoor",49)==0) { - vision.white_balance=2; - } -#ifdef PLATFORM_APERIOS - //this will actually send the new setting to the system - OPrimitiveID fbkID = 0; - if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){ - std::cout << "Open FbkImageSensor failure." << std::endl; - } else { - OPrimitiveControl_CameraParam owb(vision.white_balance); - if(OPENR::ControlPrimitive(fbkID, oprmreqCAM_SET_WHITE_BALANCE, &owb, sizeof(owb), 0, 0) != oSUCCESS){ - std::cout << "CAM_SET_WHITE_BALANCE : Failed!" << std::endl; - } - OPENR::ClosePrimitive(fbkID); - } -#endif - return &vision.white_balance; - } else if (strncasecmp(key,"gain",29)==0) { - if (strncasecmp(value,"low",49)==0) { - vision.gain=1; - } else if (strncasecmp(value,"mid",49)==0) { - vision.gain=2; - } else if (strncasecmp(value,"high",49)==0) { - vision.gain=3; - } -#ifdef PLATFORM_APERIOS - //this will actually send the new setting to the system - OPrimitiveID fbkID = 0; - if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){ - std::cout << "Open FbkImageSensor failure." << std::endl; - } else { - OPrimitiveControl_CameraParam ogain(vision.gain); - if(OPENR::ControlPrimitive(fbkID, oprmreqCAM_SET_GAIN, &ogain, sizeof(ogain), 0, 0) != oSUCCESS) - std::cout << "CAM_SET_GAIN : Failed!" << std::endl; - OPENR::ClosePrimitive(fbkID); - } -#endif - return &vision.gain; - } else if (strncasecmp(key,"shutter_speed",29)==0) { - if (strncasecmp(value,"slow",49)==0) { - vision.shutter_speed=1; - } else if (strncasecmp(value,"mid",49)==0) { - vision.shutter_speed=2; - } else if (strncasecmp(value,"fast",49)==0) { - vision.shutter_speed=3; - } -#ifdef PLATFORM_APERIOS - //this will actually send the new setting to the system - OPrimitiveID fbkID = 0; - if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){ - std::cout << "Open FbkImageSensor failure." << std::endl; - } else { - OPrimitiveControl_CameraParam oshutter(vision.shutter_speed); - if(OPENR::ControlPrimitive(fbkID,oprmreqCAM_SET_SHUTTER_SPEED, &oshutter, sizeof(oshutter), 0, 0) != oSUCCESS) - std::cout << "CAM_SET_SHUTTER_SPEED : Failed!" << std::endl; - OPENR::ClosePrimitive(fbkID); - } -#endif - return &vision.shutter_speed; - } else if (strncasecmp(key,"resolution",29)==0) { - if (strncasecmp(value,"full",49)==0) { - vision.resolution=1; - } else if (strncasecmp(value,"half",49)==0) { - vision.resolution=2; - } else if (strncasecmp(value,"quarter",49)==0) { - vision.resolution=3; - } - return &vision.resolution; - } else if (strncasecmp(key,"thresh",29)==0) { - vision.thresh.push_back(value); - return &vision.thresh; - } else if (strncasecmp(key,"colors",29)==0) { - strncpy(vision.colors,value,49); - return &vision.colors; - } else if (strncasecmp(key,"rawcam_port",29)==0 || strncasecmp(key,"raw_port",29)==0) { - if(strncasecmp(key,"raw_port",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated raw_port -- use rawcam_port instead" << std::endl; - vision.rawcam_port=atoi(value); - return &vision.rawcam_port; - } else if (strncasecmp(key,"rawcam_transport",29)==0 || strncasecmp(key,"raw_transport",29)==0) { - if(strncasecmp(key,"raw_transport",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated raw_transport -- use rawcam_transport instead" << std::endl; - if (strncasecmp(value,"udp",49)==0) - vision.rawcam_transport=0; - else if (strncasecmp(value,"tcp",49)==0) - vision.rawcam_transport=1; - return &vision.rawcam_transport; - } else if (strncasecmp(key,"rawcam_interval",29)==0) { - vision.rawcam_interval=(unsigned int)atoi(value); - return &vision.rawcam_interval; - } else if (strncasecmp(key,"segcam_port",29)==0 || strncasecmp(key,"rle_port",29)==0) { - if(strncasecmp(key,"rle_port",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated rle_port -- use segcam_port instead" << std::endl; - vision.segcam_port=atoi(value); - return &vision.segcam_port; - } else if (strncasecmp(key,"segcam_transport",29)==0 || strncasecmp(key,"rle_transport",29)==0) { - if(strncasecmp(key,"rle_transport",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated rle_transport -- use segcam_transport instead" << std::endl; - if (strncasecmp(value,"udp",49)==0) - vision.segcam_transport=0; - else if (strncasecmp(value,"tcp",49)==0) - vision.segcam_transport=1; - return &vision.segcam_transport; - } else if (strncasecmp(key,"segcam_interval",29)==0 || strncasecmp(key,"rle_interval",29)==0) { - if(strncasecmp(key,"rle_interval",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated rle_interval -- use segcam_interval instead" << std::endl; - vision.segcam_interval=(unsigned int)atoi(value); - return &vision.segcam_interval; - } else if (strncasecmp(key,"region_port",29)==0) { - vision.region_port=atoi(value); - return &vision.region_port; - } else if (strncasecmp(key,"region_transport",29)==0) { - if (strncasecmp(value,"udp",49)==0) - vision.region_transport=0; - else if (strncasecmp(value,"tcp",49)==0) - vision.region_transport=1; - return &vision.region_transport; - } else if (strncasecmp(key,"obj_port",29)==0) { - vision.obj_port=atoi(value); - return &vision.obj_port; - } else if (strncasecmp(key,"restore_image",29)==0) { - vision.restore_image=atoi(value); - return &vision.restore_image; - } else if (strncasecmp(key,"region_calc_total",29)==0) { - vision.region_calc_total=atoi(value); - return &vision.region_calc_total; - } else if (strncasecmp(key,"jpeg_dct_method",29)==0) { - if (strncasecmp(value,"islow",49)==0) { - vision.jpeg_dct_method=JDCT_ISLOW; - } else if (strncasecmp(value,"ifast",49)==0) { - vision.jpeg_dct_method=JDCT_IFAST; - } else if (strncasecmp(value,"float",49)==0) { - vision.jpeg_dct_method=JDCT_FLOAT; - } - return &vision.jpeg_dct_method; - } else if (strncasecmp(key,"rawcam_encoding",29)==0) { - if (strncasecmp(value,"color",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_COLOR; - vision.rawcam_channel=RawCameraGenerator::CHAN_Y; - } else if (strncasecmp(value,"y_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_SINGLE_CHANNEL; - vision.rawcam_channel=RawCameraGenerator::CHAN_Y; - } else if (strncasecmp(value,"uv_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_COLOR; - vision.rawcam_channel=-1; - } else if (strncasecmp(value,"u_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_SINGLE_CHANNEL; - vision.rawcam_channel=RawCameraGenerator::CHAN_U; - } else if (strncasecmp(value,"v_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_SINGLE_CHANNEL; - vision.rawcam_channel=RawCameraGenerator::CHAN_V; - } else if (strncasecmp(value,"y_dx_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_SINGLE_CHANNEL; - vision.rawcam_channel=RawCameraGenerator::CHAN_Y_DX; - } else if (strncasecmp(value,"y_dy_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_SINGLE_CHANNEL; - vision.rawcam_channel=RawCameraGenerator::CHAN_Y_DY; - } else if (strncasecmp(value,"y_dxdy_only",49)==0) { - vision.rawcam_encoding=vision_config::ENCODE_SINGLE_CHANNEL; - vision.rawcam_channel=RawCameraGenerator::CHAN_Y_DXDY; - } - return &vision.rawcam_encoding; - } else if (strncasecmp(key,"rawcam_compression",29)==0) { - if (strncasecmp(value,"none",49)==0) { - vision.rawcam_compression=vision_config::COMPRESS_NONE; - } else if (strncasecmp(value,"jpeg",49)==0) { - vision.rawcam_compression=vision_config::COMPRESS_JPEG; - } else if (strncasecmp(value,"png",49)==0) { - vision.rawcam_compression=vision_config::COMPRESS_PNG; - } - return &vision.rawcam_compression; - } else if (strncasecmp(key,"rawcam_compress_quality",29)==0) { - vision.rawcam_compress_quality=atoi(value); - return &vision.rawcam_compress_quality; - } else if (strncasecmp(key,"rawcam_y_skip",29)==0) { - vision.rawcam_y_skip=atoi(value); - if(ProjectInterface::defRawCameraGenerator!=NULL && vision.rawcam_y_skip>(int)ProjectInterface::defRawCameraGenerator->getNumLayers()-1) - vision.rawcam_y_skip=ProjectInterface::defRawCameraGenerator->getNumLayers()-1; - return &vision.rawcam_y_skip; - } else if (strncasecmp(key,"rawcam_uv_skip",29)==0) { - vision.rawcam_uv_skip=atoi(value); - if(ProjectInterface::defRawCameraGenerator!=NULL && vision.rawcam_uv_skip>(int)ProjectInterface::defRawCameraGenerator->getNumLayers()-1) - vision.rawcam_uv_skip=ProjectInterface::defRawCameraGenerator->getNumLayers()-1; - return &vision.rawcam_uv_skip; - } else if (strncasecmp(key,"segcam_skip",29)==0 || strncasecmp(key,"rlecam_skip",29)==0) { - if(strncasecmp(key,"rlecam_skip",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated rlecam_skip -- use segcam_skip instead" << std::endl; - vision.segcam_skip=atoi(value); - if(ProjectInterface::defSegmentedColorGenerator!=NULL && vision.segcam_skip>(int)ProjectInterface::defSegmentedColorGenerator->getNumLayers()-1) - vision.segcam_skip=ProjectInterface::defSegmentedColorGenerator->getNumLayers()-1; - return &vision.segcam_skip; - } else if (strncasecmp(key,"segcam_channel",29)==0 || strncasecmp(key,"rlecam_channel",29)==0) { - if(strncasecmp(key,"rlecam_channel",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated rlecam_channel -- use segcam_channel instead" << std::endl; - vision.segcam_channel=atoi(value); - return &vision.segcam_channel; - } else if (strncasecmp(key,"segcam_compression",29)==0 || strncasecmp(key,"rlecam_compression",29)==0) { - if(strncasecmp(key,"rlecam_compression",29)==0) - std::cout << "Your tekkotsu.cfg file uses deprecated rlecam_compression -- use segcam_compression instead" << std::endl; - if (strncasecmp(value,"none",49)==0) { - vision.segcam_compression=vision_config::COMPRESS_NONE; - } else if (strncasecmp(value,"rle",49)==0) { - vision.segcam_compression=vision_config::COMPRESS_RLE; - } else if (strncasecmp(value,"png",49)==0) { - vision.segcam_compression=vision_config::COMPRESS_PNG; - } - return &vision.segcam_compression; - } else if (strncasecmp(key,"regioncam_skip",29)==0) { - vision.regioncam_skip=atoi(value); - return &vision.regioncam_skip; - } else if (strncasecmp(key,"focal_len_x",29)==0) { - vision.focal_len_x=atof(value); - return &vision.focal_len_x; - } else if (strncasecmp(key,"focal_len_y",29)==0) { - vision.focal_len_y=atof(value); - return &vision.focal_len_y; - } else if (strncasecmp(key,"principle_point_x",29)==0) { - vision.principle_point_x=atof(value); - return &vision.principle_point_x; - } else if (strncasecmp(key,"principle_point_y",29)==0) { - vision.principle_point_y=atof(value); - return &vision.principle_point_y; - } else if (strncasecmp(key,"skew",29)==0) { - vision.skew=atof(value); - return &vision.skew; - } else if (strncasecmp(key,"kc1_r2",29)==0) { - vision.kc1_r2=atof(value); - return &vision.kc1_r2; - } else if (strncasecmp(key,"kc2_r4",29)==0) { - vision.kc2_r4=atof(value); - return &vision.kc2_r4; - } else if (strncasecmp(key,"kc5_r6",29)==0) { - vision.kc5_r6=atof(value); - return &vision.kc5_r6; - } else if (strncasecmp(key,"kc3_tan1",29)==0) { - vision.kc3_tan1=atof(value); - return &vision.kc3_tan1; - } else if (strncasecmp(key,"kc4_tan2",29)==0) { - vision.kc4_tan2=atof(value); - return &vision.kc4_tan2; - } else if (strncasecmp(key,"calibration_res_x",29)==0) { - vision.calibration_res_x=atoi(value); - return &vision.kc4_tan2; - } else if (strncasecmp(key,"calibration_res_y",29)==0) { - vision.calibration_res_y=atoi(value); - return &vision.calibration_res_y; - } - break; - case sec_main: - if (strncasecmp(key,"seed_rng",29)==0) { - main.seed_rng=atoi(value); - return &main.console_port; - } else if (strncasecmp(key,"console_port",29)==0) { - main.console_port=atoi(value); - return &main.console_port; - } else if (strncasecmp(key,"consoleMode",29)==0) { - if (strncasecmp(value,"controller",49)==0) { - main.consoleMode=main_config::CONTROLLER; - } else if (strncasecmp(value,"textmsg",49)==0) { - main.consoleMode=main_config::TEXTMSG; - } else if (strncasecmp(value,"auto",49)==0) { - main.consoleMode=main_config::AUTO; - } - return &main.consoleMode; - } else if (strncasecmp(key,"stderr_port",29)==0) { - main.stderr_port=atoi(value); - return &main.stderr_port; - } else if (strncasecmp(key,"error_level",29)==0) { - main.error_level=atoi(value); - return &main.error_level; - } else if (strncasecmp(key,"debug_level",29)==0) { - main.debug_level=atoi(value); - return &main.debug_level; - } else if (strncasecmp(key,"verbose_level",29)==0) { - main.verbose_level=atoi(value); - return &main.verbose_level; - } else if (strncasecmp(key,"wsjoints_port",29)==0) { - main.wsjoints_port=atoi(value); - return &main.wsjoints_port; - } else if (strncasecmp(key,"wspids_port",29)==0) { - main.wspids_port=atoi(value); - return &main.wspids_port; - } else if (strncasecmp(key,"headControl_port",29)==0) { - main.headControl_port=atoi(value); - return &main.headControl_port; - } else if (strncasecmp(key,"walkControl_port",29)==0) { - main.walkControl_port=atoi(value); - return &main.walkControl_port; - } else if (strncasecmp(key,"estopControl_port",29)==0) { - main.estopControl_port=atoi(value); - return &main.estopControl_port; - } else if (strncasecmp(key,"aibo3d_port",29)==0) { - main.aibo3d_port=atoi(value); - return &main.aibo3d_port; - } else if (strncasecmp(key,"wmmonitor_port",29)==0) { - main.wmmonitor_port=atoi(value); - return &main.wmmonitor_port; - } else if (strncasecmp(key,"use_VT100",29)==0) { - main.use_VT100=extractBool(value); - return &main.use_VT100; - } - break; - case sec_behaviors: - if (strncasecmp(key,"flash_bytes",29)==0) { - behaviors.flash_bytes = atoi(value); - return &behaviors.flash_bytes; - } else if (strncasecmp(key,"flash_on_start",29)==0) { - behaviors.flash_on_start = atoi(value); - return &behaviors.flash_on_start; +void* Config::setValue(const std::string& section, std::string key, const std::string& value) { + if(section=="vision") { + if (key=="resolution") { + if (value=="full") { + vision.resolution=1; + } else if (value=="half") { + vision.resolution=2; + } else if (value=="quarter") { + vision.resolution=3; } - break; - case sec_controller: - if (strncasecmp(key,"gui_port",29)==0) { - controller.gui_port = atoi(value); - return &controller.gui_port ; - } else if (strncasecmp(key,"select_snd",29)==0) { - strncpy(controller.select_snd,value,49); - return &controller.select_snd; - } else if (strncasecmp(key,"next_snd",29)==0) { - strncpy(controller.next_snd,value,49); - return &controller.next_snd; - } else if (strncasecmp(key,"prev_snd",29)==0) { - strncpy(controller.prev_snd,value,49); - return &controller.prev_snd; - } else if (strncasecmp(key,"read_snd",29)==0) { - strncpy(controller.read_snd,value,49); - return &controller.read_snd; - } else if (strncasecmp(key,"cancel_snd",29)==0) { - strncpy(controller.cancel_snd,value,49); - return &controller.cancel_snd; - } else if (strncasecmp(key,"error_snd",29)==0) { - strncpy(controller.error_snd,value,49); - return &controller.error_snd; + return &vision.resolution; + } else if (key=="rawcam_encoding") { + if (value=="color") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_COLOR; + vision.rawcam.channel=RawCameraGenerator::CHAN_Y; + } else if (value=="y_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL; + vision.rawcam.channel=RawCameraGenerator::CHAN_Y; + } else if (value=="uv_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_COLOR; + vision.rawcam.channel=-1; + } else if (value=="u_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL; + vision.rawcam.channel=RawCameraGenerator::CHAN_U; + } else if (value=="v_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL; + vision.rawcam.channel=RawCameraGenerator::CHAN_V; + } else if (value=="y_dx_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL; + vision.rawcam.channel=RawCameraGenerator::CHAN_Y_DX; + } else if (value=="y_dy_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL; + vision.rawcam.channel=RawCameraGenerator::CHAN_Y_DY; + } else if (value=="y_dxdy_only") { + vision.rawcam.encoding=vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL; + vision.rawcam.channel=RawCameraGenerator::CHAN_Y_DXDY; } - break; - case sec_motion: - if (strncasecmp(key,"root",29)==0) { - motion.root=value; - return &motion.root; - } else if (strncasecmp(key,"walk",29)==0) { - motion.walk=value; - return &motion.walk; - } else if (strncasecmp(key,"kinematics",29)==0) { - motion.kinematics=value; - return &motion.walk; - } else if (strncasecmp(key,"kinematic_chains",29)==0) { - motion.kinematic_chains.push_back(value); - return &motion.kinematic_chains; - } else if (strncasecmp(key,"calibrate:",10)==0) { - for(unsigned int i=PIDJointOffset; i10?&key[10]:key) << "' as calibration parameter" << std::endl; + return &vision.rawcam.encoding; + } else if (key=="focal_len_x" || key=="focal_len_y" + || key=="principle_point_x" || key=="principle_point_y" + || key=="skew" || key=="kc1_r2" || key=="kc2_r4" + || key=="kc5_r6" || key=="kc3_tan1" || key=="kc4_tan2" + || key=="calibration_res_x" || key=="calibration_res_y" ) + { + key="calibration."+key; + } else if (key.compare(0,7,"rawcam_")==0) { + key[6]='.'; + } else if (key.compare(0,7,"segcam_")==0) { + key[6]='.'; + } else if (key.compare(0,10,"regioncam_")==0) { + key[9]='.'; + } else if (key=="region_port" || key=="region_transport") { + key.replace(0,7,"regioncam."); + } + } else if(section=="motion") { + std::string calibratePrefix="calibrate:"; + if (key.substr(0,calibratePrefix.size())==calibratePrefix) { + std::string keyval = key.substr(calibratePrefix.size()); + OutputConfig >::const_iterator it = motion.calibration_scale.findEntry(keyval); + plist::Primitive* prim = NULL; + if(it!=motion.calibration_scale.end()) + prim = dynamic_cast *>(it->second); + if(prim==NULL) { + std::cout << "WARNING: Could not match '" << key.substr(10) << "' as calibration parameter" << std::endl; return NULL; - } else if (strncasecmp(key,"estop_on_snd",29)==0) { - strncpy(motion.estop_on_snd,value,49); - return &motion.estop_on_snd; - } else if (strncasecmp(key,"estop_off_snd",29)==0) { - strncpy(motion.estop_off_snd,value,49); - return &motion.estop_off_snd; - } else if (strncasecmp(key,"max_head_tilt_speed",29)==0) { - motion.max_head_tilt_speed=atof(value); - return &motion.max_head_tilt_speed; - } else if (strncasecmp(key,"max_head_pan_speed",29)==0) { - motion.max_head_pan_speed=atof(value); - return &motion.max_head_pan_speed; - } else if (strncasecmp(key,"max_head_roll_speed",29)==0) { - motion.max_head_roll_speed=atof(value); - return &motion.max_head_roll_speed; - } else if (strncasecmp(key,"inf_walk_accel",29)==0) { - motion.inf_walk_accel = atoi(value); - return &motion.inf_walk_accel; - } else if (strncasecmp(key,"console_port",29)==0) { - motion.console_port = atoi(value); - return &motion.console_port; - } else if (strncasecmp(key,"stderr_port",29)==0) { - motion.stderr_port = atoi(value); - return &motion.stderr_port ; - } - break; - case sec_sound: - if (strncasecmp(key,"root",29)==0) { - sound.root=value; - return &sound.root; - } else if (strncasecmp(key,"volume",29)==0) { - if(strncasecmp(value,"mute",49)==0) - sound.volume=ospkvolinfdB; - else if(strncasecmp(value,"level_1",49)==0) - sound.volume=ospkvol25dB; - else if(strncasecmp(value,"level_2",49)==0) - sound.volume=ospkvol18dB; - else if(strncasecmp(value,"level_3",49)==0) - sound.volume=ospkvol10dB; - else - return NULL; - return &sound.volume; - } else if (strncasecmp(key,"sample_rate",29)==0) { - sound.sample_rate = atoi(value); - return &sound.sample_rate ; - } else if (strncasecmp(key,"sample_bits",29)==0) { - sound.sample_bits = atoi(value); - return &sound.sample_bits ; - } else if (strncasecmp(key,"preload",29)==0) { - sound.preload.push_back(value); - return &sound.preload ; - } else if (strncasecmp(key,"pitchConfidenceThreshold",29)==0) { - sound.pitchConfidenceThreshold=atof(value); - return &sound.pitchConfidenceThreshold ; - } else if (strncasecmp(key,"streaming.mic_port",29)==0) { - sound.streaming.mic_port = atoi(value); - return &sound.streaming.mic_port; - } else if (strncasecmp(key,"streaming.mic_sample_rate",29)==0) { - sound.streaming.mic_sample_rate = atoi(value); - return &sound.streaming.mic_sample_rate; - } else if (strncasecmp(key,"streaming.mic_bits",29)==0) { - sound.streaming.mic_sample_bits = atoi(value); - return &sound.streaming.mic_sample_bits; - } else if (strncasecmp(key,"streaming.mic_stereo",29)==0) { - sound.streaming.mic_stereo = extractBool(value); - return &sound.streaming.mic_stereo; - } else if (strncasecmp(key,"streaming.speaker_port",29)==0) { - sound.streaming.speaker_port = atoi(value); - return &sound.streaming.speaker_port; - } else if (strncasecmp(key,"streaming.speaker_frame_len",29)==0) { - sound.streaming.speaker_frame_length = atoi(value); - return &sound.streaming.speaker_frame_length; - } else if (strncasecmp(key,"streaming.speaker_max_delay",29)==0) { - sound.streaming.speaker_max_delay = atoi(value); - return &sound.streaming.speaker_max_delay; } - break; - case sec_invalid: - break; + //std::cout << "setting " << key.substr(10) << " to " << value << std::endl; + prim->set(value); + *prim = 1 / *(prim); + return prim; + } + } else if(section=="sound") { + if (key=="streaming.mic_bits") { + key="streaming.mic_sample_bits"; + } else if (key=="streaming.speaker_frame_len") { + key="streaming.speaker_frame_length"; + } + } else if(section=="main") { + if (key=="debug_level" || key=="error_level" || key=="verbose_level") + return NULL; //drop, unused items } - return NULL; -} - -Config::section_t Config::parseSection(const char* key) { - if (strncasecmp(key,"wireless",29)==0) { - return sec_wireless; - } else if (strncasecmp(key,"vision",29)==0) { - return sec_vision; - } else if (strncasecmp(key,"main",29)==0) { - return sec_main; - } else if (strncasecmp(key,"behaviors",29)==0) { - return sec_behaviors; - } else if (strncasecmp(key,"controller",29)==0) { - return sec_controller; - } else if (strncasecmp(key,"motion",29)==0) { - return sec_motion; - } else if (strncasecmp(key,"sound",29)==0) { - return sec_sound; + + plist::Collection * sct=dynamic_cast(resolveEntry(section)); + if(sct==NULL) + return NULL; + plist::ObjectBase * entry=sct->resolveEntry(key); + if(entry==NULL) { + std::cerr << "Unknown " << section << " key '" << key << "' for value " << value << std::endl; + return NULL; + } else if(plist::PrimitiveBase * prim=dynamic_cast(entry)) { + try { + prim->set(value); + } catch(...) { + std::cerr << "Error setting " << section << " key '" << key << "' to value " << value << std::endl; + return NULL; + } + return prim; + } else if(plist::ArrayBase::StringConversion * arr=dynamic_cast(entry)) { + try { + arr->addValue(value); + } catch(...) { + std::cerr << "Error setting " << section << " key '" << key << "' to value " << value << std::endl; + return NULL; + } + return arr; } else { - return sec_invalid; + std::cerr << "Unknown type of " << section << " key '" << key << "' for value " << value << std::endl; + return NULL; } } -void Config::readConfig(const std::string& filename) { - FILE* fp = fopen(portPath(filename).c_str(), "r"); - if (fp==NULL) - return; - - char buf[256], key[30], value[50]; - section_t section=sec_invalid; +unsigned int Config::loadOldFormat(const char buf[], unsigned int len) { + if (buf==NULL) return 0; + unsigned int numRead=0, used=0; + char line[256]; + unsigned int lineno=0; + std::vector modelStack; bool ignoring=false; - - std::vector curmodel; -#ifdef PLATFORM_APERIOS - char rdStr[orobotdesignNAME_MAX + 1]; - memset(rdStr, 0, sizeof(rdStr)); - if (OPENR::GetRobotDesign(rdStr) != oSUCCESS) { - printf("OPENR::GetRobotDesign() failed.\n"); - rdStr[0]='\0'; + std::string section="invalid"; + while (numRead undefined - defaulting to ERS7" - char rdStr[]="ERS-7"; -# endif -#endif - - + return numRead; +} + +unsigned int Config::loadOldFormat(FILE* fp) { + if (fp==NULL) return 0; + unsigned int numRead=0; + char line[256]; unsigned int lineno=0; - while (fgets(buf,256,fp)!=NULL) { - lineno++; - char * p=buf; - while(*p!='\0' && isspace(*p)) - p++; - if(*p=='\0' || *p=='#') - continue; //empty line or comment - - if (sscanf(buf,"<%29[^>]>",key)>0) { - if(key[0]=='/') { - if(curmodel.size()==0) { - printf("WARNING: not in a model specific section, line %d\n",lineno); - continue; - } - bool subset=matchNoCase(&key[1],curmodel.back()); - bool superset=matchNoCase(curmodel.back(),&key[1]); - if(subset && superset) { - //printf("leaving modelsection %s\n",curmodel.back().c_str()); - curmodel.pop_back(); - } else if(superset) { - while(curmodel.size()>0) { - //printf("leaving modelsection %s (==%s)\n",curmodel.back().c_str(),&key[1]); - curmodel.pop_back(); - if(!matchNoCase(curmodel.back(),&key[1])) - break; - } - } else - printf("WARNING: config model mismatch, line %d\n",lineno); - - ignoring=false; //scan through current model selection stack, see if we're still ignoring - for(unsigned int i=0; i0) { - section=parseSection(key); - if(section==sec_invalid) - std::cerr << "WARNING: Reading " << filename << ", unknown section " << key << " at line number " << lineno << endl; - //std::cout << "now parsing section " << section << std::endl; - } else if (sscanf(buf,"%29[^ =] =%49s",key,value)>1) { - //printf("setValue(%d,'%s','%s');\n",section,key,value); - if(section!=sec_invalid) - if(setValue(section, key, value)==NULL) - std::cerr << "WARNING: Reading " << filename << ", illegal key/value " << key << '/' << value << " at line number " << lineno << endl; - } else { - std::cerr << "WARNING: Reading " << filename << ", parse error on key/value " << key << '/' << value << " at line number " << lineno << endl; - } - } + std::vector modelStack; + bool ignoring=false; + std::string section="invalid"; + while (fgets(line,256,fp)!=NULL) { + numRead+=strlen(line); + parseLine(line,++lineno,modelStack,ignoring,section); } - fclose(fp); + return numRead; } -bool Config::matchNoCase(const std::string& model, const std::string& pattern) { - unsigned int i=0; - if(i==pattern.size() && i==model.size()) - return true; - if(i==pattern.size() || i==model.size()) - return false; - while(pattern[i]!='*') { - if(toupper(pattern[i])!=toupper(model[i])) - return false; - i++; - if(i==pattern.size() && i==model.size()) - return true; - if(i==pattern.size() || i==model.size()) - return false; - } - i=pattern.size()-1; - unsigned int j=model.size()-1; - while(pattern[i]!='*') { - if(toupper(pattern[i])!=toupper(model[j])) - return false; - i--; j--; +void Config::parseLine(const char buf[], unsigned int lineno, std::vector& modelStack, bool& ignoring, std::string& section) { + char key[30], value[50]; + while(std::isspace(*buf)) + buf++; + if(buf[0]=='#') + return; + if (sscanf(buf,"<%29[^>]>",key)>0) { + if(key[0]=='/') { + if(modelStack.size()==0) { + printf("WARNING: not in a model specific section, line %d\n",lineno); + return; + } + bool subset=matchNoCase(&key[1],modelStack.back()); + bool superset=matchNoCase(modelStack.back(),&key[1]); + if(subset && superset) { + //printf("leaving modelsection %s\n",modelStack.back().c_str()); + modelStack.pop_back(); + } else if(superset) { + while(modelStack.size()>0) { + //printf("leaving modelsection %s (==%s)\n",modelStack.back().c_str(),&key[1]); + modelStack.pop_back(); + if(!matchNoCase(modelStack.back(),&key[1])) + break; + } + } else + printf("WARNING: config model mismatch, line %d\n",lineno); + + ignoring=false; //scan through current model selection stack, see if we're still ignoring + for(unsigned int i=0; i0) { + section=key; + std::transform(section.begin(), section.end(), section.begin(), (int(*)(int)) std::tolower); + //std::cout << "now parsing section " << section << std::endl; + plist::Collection * sct=dynamic_cast(resolveEntry(section)); + if(sct==NULL) + std::cerr << "ERROR: Unknown configuration section " << section << std::endl; + } else if (sscanf(buf,"%29[^ =] =%49s",key,value)>1) { + //printf("setValue(%d,'%s','%s');\n",section,key,value); + //void * var= + setValue(section, string_util::trim(key), string_util::trim(value)); + /*if(var==NULL) { + std::cerr << "WARNING: Config::setValue(\"" << section << "\", \"" << string_util::trim(key) << "\", \"" << string_util::trim(key) << "\") returned NULL" << std::endl; + std::cerr << " This probably indicates the section or key is invalid." << std::endl; + }*/ + } } - return true; +} + +void Config::vision_config::computeRay(float x, float y, float& r_x, float& r_y, float& r_z) { + x=(x+1)*calibration.calibration_res_x/2; + y=(y+1)*calibration.calibration_res_y/2; + float yd=(y-calibration.principle_point_y)/calibration.focal_len_y; + float xd=(x-calibration.principle_point_x)/calibration.focal_len_x-calibration.skew*yd; + float r2=xd*xd+yd*yd; //estimate of original + float radial=(1 + calibration.kc1_r2*r2 + calibration.kc2_r4*r2*r2 + calibration.kc5_r6*r2*r2*r2); + r_x=(xd - 2*calibration.kc3_tan1*xd*yd - calibration.kc4_tan2*(r2+2*xd*xd))/radial; //estimating tangential component + r_y=(yd - calibration.kc3_tan1*(r2+2*yd*yd) - 2*calibration.kc4_tan2*xd*yd)/radial; //estimating tangential component + r_z=1; } -bool Config::extractBool(const char * value) { - int i=0; - while(isspace(value[i])) i++; - if(strncasecmp(&value[i],"t",29)==0) - return true; - else if(strncasecmp(&value[i],"f",29)==0) - return false; - else if(strncasecmp(&value[i],"true",29)==0) - return true; - else if(strncasecmp(&value[i],"false",29)==0) - return false; - else if(strncasecmp(&value[i],"y",29)==0) - return true; - else if(strncasecmp(&value[i],"n",29)==0) - return false; - else if(strncasecmp(&value[i],"yes",29)==0) - return true; - else if(strncasecmp(&value[i],"no",29)==0) - return false; - else - return atoi(value); +//!provides a pixel hit in image by a ray going through the camera frame +/*! @param[in] r_x x value of the ray +* @param[in] r_y y value of the ray +* @param[in] r_z z value of the ray +* @param[out] x x position in range [-1,1] +* @param[out] y y position in range [-1,1] */ +void Config::vision_config::computePixel(float r_x, float r_y, float r_z, float& x, float& y) { + if(r_z==0) { + x=y=0; + return; + } + r_x/=r_z; + r_y/=r_z; + float r2 = r_x*r_x + r_y*r_y; //'r2' for 'radius squared', not 'ray number 2' + float radial=(1 + calibration.kc1_r2*r2 + calibration.kc2_r4*r2*r2 + calibration.kc5_r6*r2*r2*r2); + float xd = radial*r_x + 2*calibration.kc3_tan1*r_x*r_y + calibration.kc4_tan2*(r2+2*r_x*r_x); + float yd = radial*r_y + calibration.kc3_tan1*(r2+2*r_y*r_y) + 2*calibration.kc4_tan2*r_x*r_y; + x=calibration.focal_len_x*(xd+calibration.skew*yd)+calibration.principle_point_x; + y=calibration.focal_len_y*yd+calibration.principle_point_y; + x=2*x/calibration.calibration_res_x-1; + y=2*y/calibration.calibration_res_y-1; } /*! @file * @brief Implements Config, which provides global access to system configuration information - * @author alokl (Creator) + * @author ejt (Creator) + * @author alokl (Original configuration system) * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.59 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.71 $ * $State: Exp $ - * $Date: 2006/09/27 20:36:06 $ + * $Date: 2007/11/16 15:53:49 $ */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Config.h ./Shared/Config.h --- ../Tekkotsu_3.0/Shared/Config.h 2006-09-21 17:26:08.000000000 -0400 +++ ./Shared/Config.h 2007-11-16 10:53:49.000000000 -0500 @@ -2,255 +2,555 @@ #ifndef INCLUDED_Config_h #define INCLUDED_Config_h -#include -#include -#include "RobotInfo.h" +#include "Shared/plist.h" +#include "Shared/RobotInfo.h" extern "C" { #include } +#ifdef PLATFORM_APERIOS +# include +#else +typedef unsigned int OSpeakerVolume; //!< provides an OPEN-R type of the same name for compatability, see Config::sound_config::volume +const OSpeakerVolume ospkvolinfdB = 0x8000; //!< 'muted' volume level, see Config::sound_config::volume +const OSpeakerVolume ospkvol25dB = 0xe700; //!< low volume, see Config::sound_config::volume +const OSpeakerVolume ospkvol18dB = 0xee00; //!< mid volume, see Config::sound_config::volume +const OSpeakerVolume ospkvol10dB = 0xf600; //!< high volume, see Config::sound_config::volume +#endif +#include +#include -//!provides global access to system configuration information -class Config { - public: - //!constructor - Config() - : wireless(), vision(), main(), behaviors(), controller(), motion(this), - sound(this), fsRoot() - {setFileSystemRoot("");} - //!constructor - Config(const std::string& filename) - : wireless(), vision(), main(), behaviors(), controller(), motion(this), - sound(this), fsRoot() - { setFileSystemRoot(""); readConfig(filename); } - //!destructor - ~Config() {} +//! a subclass of plist::Dictionary which adds support for filtering settings by robot model, each configuration section is based on this +/*! As a slight extension to standard plists, you can specify + * model-specific settings by prepending a key with: + * Model:MODEL_PATTERN:KEY_NAME + * For example, to use different 'thresh' settings on the ERS-2xx + * series vs. the ERS-7 model, you would use the keys: + * - Model:ERS-2*:thresh + * - Model:ERS-7:thresh + * You can filter several items as a group by leaving off the second + * ':' and name, and providing a dictionary as the value. If the + * model matches, all entries from the dictionary are imported into + * the parent dictionary. + */ +class ConfigDictionary : public plist::Dictionary { +public: + ConfigDictionary() : plist::Dictionary(false) + { + if(curModel.size()==0) + curModel=RobotName; + } + +protected: + + virtual bool loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment); + virtual bool saveOverXMLNode(xmlNode* k, xmlNode* val, const std::string& key, std::string comment, const std::string& indentStr, std::set& seen) const; + + //! returns true if pattern matches model - pattern may have up to 1 '*', case insensitive + static bool matchNoCase(const std::string& model, const std::string& pattern); + + static const std::string msPrefix; //!< the prefix indicating a model-specific key + static const std::string msSep; //!< the separator string which splits the key into the prefix, model pattern, and (optionally) a single key name + //static const std::string msNum; + static std::string curModel; //!< will be set to the model identifier of the currently running hardware + static void initCurModel(); //!< function to initialize #curModel +}; +//! Stores an item for each joint, can be accessed via joint name or array offset +/*! Two main reasons for this class are to keep outputs in offset order (not alphabetic by name), + * and to strip '~' from output names for backward compatability (used to pad output names + * to ensure constant string length. */ +template +class OutputConfig : public ConfigDictionary { +public: + //! constructor + OutputConfig(unsigned int firstOffset, unsigned int numOutputsToStore, const T& defValue) + : ConfigDictionary(), offset(firstOffset), outputs(numOutputsToStore,defValue) + { + for(unsigned int i=0; i& seen) const; + using ConfigDictionary::saveXML; + +protected: + //! strips trailing '~' characters from name before doing usual lookup + bool loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment) { + std::string::size_type n = key.find_last_not_of('~')+1; + return ConfigDictionary::loadXMLNode((n==key.size()) ? key : key.substr(0,n), val, comment); + } + + unsigned int offset; //!< the index offset of the first entry in #outputs + std::vector outputs; //!< storage of data for each output +}; + +//! the root configuration object, provides some global functionality like porting pathnames (portPath()) +class Config : public ConfigDictionary { +public: + Config(const std::string& filename="") : ConfigDictionary(), + behaviors(), wireless(), main(), controller(), vision(), motion(this), sound(this), fsRoot() + { + addEntry("wireless",wireless); + addEntry("vision",vision); + addEntry("main",main); + addEntry("behaviors",behaviors); + addEntry("controller",controller); + addEntry("motion",motion); + addEntry("sound",sound); + if(filename.size()!=0) + loadFile(filename.c_str()); + } + + enum transports { UDP, TCP }; //!< types of network transport protocols supported + static const unsigned int NUM_TRANSPORTS=2; //!< number of #transports available + static const char * transport_names[NUM_TRANSPORTS+1]; //!< string names for #transports + void setFileSystemRoot(const std::string& fsr); //!< sets #fsRoot const std::string& getFileSystemRoot() const { return fsRoot; } //!< returns #fsRoot std::string portPath(const std::string& path) const; //!< returns a portable version of @a path which should be usable on either the simulator or the robot - //!section IDs - enum section_t { - sec_wireless=0, //!< denotes wireless section of config file - sec_vision, //!< denotes vision section of config file - sec_main, //!< denotes main section of config file, for misc. settings - sec_behaviors, //!< denotes behaviors section of config file - sec_controller, //!< denotes controller section of config file - sec_motion, //!< denotes motion section of config file - sec_sound, //!< denotes sound section of config file - sec_invalid //!< denotes an invalid section of config file - }; + + + // **************************************** // + //! place for users to put their own configuration + // **************************************** // + /*! you can dynamically "link in" external configuration settings by passing them to the addEntry() of the + * plist::Dictionary superclass. You may want to call writeParseTree() first to flush current settings, + * and then readParseTree() afterward to pull any pre-existing values from the configuration + * file into the instances you've just registered. + * + * Of course, you could also just write your values into the configuration file first, and just rely + * on getEntry/setEntry to read/write the value. This may be more convenient if you use the + * value infrequently and don't need an instance of it sitting around. */ + class behaviors_config : public ConfigDictionary { + public: + //! constructor + behaviors_config() : ConfigDictionary(), flash_bytes(4), flash_on_start(true) + { + //users may want to dynamically link in their own settings when running, so don't warn if there are + // unused items in this section + setUnusedWarning(false); + + addEntry("flash_bytes",flash_bytes,"how many bytes of the address to flash\n" + "You probably already know the first 3 bytes for your network,\n" + "so you might only want the last byte for brevity.\n" + "(valid values are 1 through 4) "); + addEntry("flash_on_start",flash_on_start,"whether or not to automatically trigger on boot\n" + "Will use a priority of kEmergencyPriority+1 in order to override\n" + "the emergency stop's status animation "); + } + plist::Primitive flash_bytes; //!< how many bytes of the IP to flash + plist::Primitive flash_on_start; //!< whether or not to trigger flashing when initially started + } behaviors; - //!wirless information - struct wireless_config { - int id; //!< id number (in case you have more than one AIBO) - - wireless_config () : id(1) {} //!< constructor + + + // **************************************** // + //! wireless configuration options + // **************************************** // + class wireless_config : public ConfigDictionary { + public: + //! constructor + wireless_config () : ConfigDictionary(), id(1) { + addEntry("id",id,"id number (in case you have more than one AIBO)"); + } + plist::Primitive id; //!< id number (in case you have more than one AIBO) } wireless; + + + + // **************************************** // + //! general configuration options + // **************************************** // + class main_config : public ConfigDictionary { + public: + //!constructor + main_config() + : ConfigDictionary(), seed_rng(true), console_port(10001), consoleMode(CONTROLLER,consoleModeNames), stderr_port(10002), + wsjoints_port(10031),wspids_port(10032),headControl_port(10052), + walkControl_port(10050),estopControl_port(10053),stewart_port(10055),aibo3d_port(10051), + wmmonitor_port(10061), use_VT100(true), worldState_interval(0) + { + addEntry("seed_rng",seed_rng,"if true, will call srand with timestamp data, mangled by current sensor data"); + addEntry("console_port",console_port,"port to send/receive \"console\" information on (separate from system console)"); + addEntry("consoleMode",consoleMode,"determines how input on console_port is interpreted\n"+consoleMode.getDescription()+"\n" + " 'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)\n" + " 'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)\n" + " 'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise "); + addEntry("stderr_port",stderr_port,"port to send error information to"); + addEntry("wsjoints_port",wsjoints_port,"port to send joint positions on"); + addEntry("wspids_port",wspids_port,"port to send pid info on"); + addEntry("headControl_port",headControl_port,"port for receiving head commands"); + addEntry("walkControl_port",walkControl_port,"port for receiving walk commands"); + addEntry("estopControl_port",estopControl_port,"port for receiving walk commands"); + addEntry("stewart_port",stewart_port,"port for running a stewart platform style of control"); + addEntry("aibo3d_port",aibo3d_port,"port for send/receive of joint positions from Aibo 3D GUI"); + addEntry("wmmonitor_port",wmmonitor_port,"port for monitoring Watchable Memory"); + addEntry("use_VT100",use_VT100,"if true, enables VT100 console codes (currently only in Controller menus - 1.3)"); + addEntry("worldState_interval",worldState_interval,"time (in milliseconds) to wait between sending WorldState updates over wireless"); + } + plist::Primitive seed_rng; //!< if true, will call srand with timestamp data, mangled by current sensor data + plist::Primitive console_port; //!< port to send/receive "console" information on (separate from system console) + //! types that #consoleMode can take on + enum consoleMode_t { + CONTROLLER, //!< all input is interpreted as Controller commands, using same syntax as the GUI sends + TEXTMSG, //!< all input is broadcast as a text message event + AUTO //!< if the GUI is connected, interpret as text messages, otherwise as controller commands. This was the historical behavior, but seems to be more confusing than helpful. + }; + static const unsigned int NUM_CONSOLE_MODES=3; //!< the number of consoleMode_t values available + static const char* consoleModeNames[NUM_CONSOLE_MODES+1]; //!< string names for #consoleMode_t + //! determines how input on #console_port is interpreted + plist::NamedEnumeration consoleMode; + plist::Primitive stderr_port; //!< port to send error information to + plist::Primitive wsjoints_port; //!< port to send joint positions on + plist::Primitive wspids_port; //!< port to send pid info on + plist::Primitive headControl_port; //!< port for receiving head commands + plist::Primitive walkControl_port; //!< port for receiving walk commands + plist::Primitive estopControl_port; //!< port for receiving walk commands + plist::Primitive stewart_port; //!< port for running a stewart platform style of control + plist::Primitive aibo3d_port; //!< port for send/receive of joint positions from Aibo 3D GUI + plist::Primitive wmmonitor_port; //!< port for monitoring Watchable Memory + plist::Primitive use_VT100; //!< if true, enables VT100 console codes (currently only in Controller menus - 1.3) + plist::Primitive worldState_interval; //!< time (in milliseconds) to wait between sending WorldState updates over wireless + } main; - //!vision information - struct vision_config { - int white_balance; //!< white balance - int gain; //!< gain - int shutter_speed; //!< shutter speed - int resolution; //!< resolution - std::vector thresh; //!< thresholds - char colors[50]; //!< colors - int rawcam_port; //!< port to send raw frames on - int rawcam_transport; //!< transport protocol: 0 for udp, 1 for tcp - unsigned int rawcam_interval; //!< interval between images: 0 for fast-as-possible, 100 for 10 FPS, 200 for 5 FPS, etc. - int segcam_port; //!< port to send segmented color frames on - int segcam_transport; //!< transport protocol: 0 for udp, 1 for tcp - unsigned int segcam_interval; //!< interval between images: 0 for fast-as-possible, 100 for 10 FPS, 200 for 5 FPS, etc. - int region_port; //!< port to send Region information on - int region_transport; //!< transport protocol: 0 for udp, 1 for tcp - int obj_port; //!< port to send object info on - bool restore_image; //!< if true, replaces pixels holding image info with actual image pixels (as much as possible anyway) - bool region_calc_total; //!< if true, RegionGenerator will calculate total area for each color (has to run through the region list for each color) - J_DCT_METHOD jpeg_dct_method; //!< pick between dct methods for jpeg compression - float aspectRatio; //!< ratio of width to height (x_res/y_res); this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received) - float x_range; //!< range of values for the x axis when using generalized coordinates; this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received) - float y_range; //!< range of values for the x axis when using generalized coordinates; this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received) + + + // **************************************** // + //! controller information + // **************************************** // + class controller_config : public ConfigDictionary { + public: + //!constructor + controller_config() : ConfigDictionary(), gui_port(10020), select_snd(), next_snd(), prev_snd(), read_snd(), cancel_snd(), error_snd() + { + addEntry("gui_port",gui_port,"port to listen for the GUI to connect to aibo on"); + addEntry("select_snd",select_snd,"sound file to use for \"select\" action"); + addEntry("next_snd",next_snd,"sound file to use for \"next\" action"); + addEntry("prev_snd",prev_snd,"sound file to use for \"prev\" action"); + addEntry("read_snd",read_snd,"sound file to use for \"read from std-in\" action"); + addEntry("cancel_snd",cancel_snd,"sound file to use for \"cancel\" action"); + addEntry("error_snd",error_snd,"sound file to use to signal errors"); + } + + plist::Primitive gui_port; //!< port to listen for the GUI to connect to aibo on + plist::Primitive select_snd; //!< sound file to use for "select" action + plist::Primitive next_snd; //!< sound file to use for "next" action + plist::Primitive prev_snd; //!< sound file to use for "prev" action + plist::Primitive read_snd; //!< sound file to use for "read from std-in" action + plist::Primitive cancel_snd; //!< sound file to use for "cancel" action + plist::Primitive error_snd; //!< sound file to use to signal errors + } controller; - //! type of information to send, stored in Config::vision_config::rawcam_encoding - enum encoding_t { - ENCODE_COLOR, //!< send Y, U, and V channels - ENCODE_SINGLE_CHANNEL, //!< send only a single channel (which channel to send is stored in Config::vision_config::rawcam_channel) This is also used for all seg cam images + + + // **************************************** // + //! vision configuration options (this is a *big* section, with sub-sections) + // **************************************** // + class vision_config : public ConfigDictionary { + public: + //!constructor + vision_config() : ConfigDictionary(), + white_balance(WB_FLUORESCENT), gain(GAIN_MID), shutter_speed(SHUTTER_MID), + resolution(1), + thresh(), colors("config/default.col"), restore_image(true), region_calc_total(true), + jpeg_dct_method(JDCT_IFAST,dct_method_names), aspectRatio(CameraResolutionX/(float)CameraResolutionY), + x_range(aspectRatio>1?1:*aspectRatio), y_range(aspectRatio>1?1/aspectRatio:1), + rawcam(), segcam(), regioncam(), calibration() + { + white_balance.addNameForVal("indoor",WB_INDOOR); + white_balance.addNameForVal("outdoor",WB_OUTDOOR); + white_balance.addNameForVal("fluorescent",WB_FLUORESCENT); + white_balance.addNameForVal("flourescent",WB_FLUORESCENT); //catch common typo + addEntry("white_balance",white_balance,"white balance shifts color spectrum in the image\n"+white_balance.getDescription()); + + gain.addNameForVal("low",GAIN_LOW); + gain.addNameForVal("mid",GAIN_MID); + gain.addNameForVal("med",GAIN_MID); + gain.addNameForVal("medium",GAIN_MID); + gain.addNameForVal("high",GAIN_HIGH); + addEntry("gain",gain,"Increasing gain will brighten the image, at the expense of more graininess/noise\n"+gain.getDescription()); + + shutter_speed.addNameForVal("slow",SHUTTER_SLOW); + shutter_speed.addNameForVal("low",SHUTTER_SLOW); + shutter_speed.addNameForVal("mid",SHUTTER_MID); + shutter_speed.addNameForVal("med",SHUTTER_MID); + shutter_speed.addNameForVal("medium",SHUTTER_MID); + shutter_speed.addNameForVal("fast",SHUTTER_FAST); + shutter_speed.addNameForVal("high",SHUTTER_FAST); + addEntry("shutter_speed",shutter_speed,"slower shutter will brighten image, but increases motion blur\n"+shutter_speed.getDescription()); + + addEntry("resolution",resolution,"the resolution that object recognition system will run at.\nThis counts down from the maximum resolution layer, so higher numbers mean lower resolution. "); + addEntry("thresh",thresh,"Threshold (.tm) files define the mapping from full color to indexed color.\n" + "You can uncomment more than one of these - they will be loaded into separate\n" + "channels of the segmenter. The only cost of loading multiple threshold files is\n" + "memory - the CPU cost of performing segmentation is only incurred if/when\n" + "the channel is actually accessed for the first time for a given frame. "); + addEntry("colors",colors,"The colors definition (.col) file gives names and a \"typical\" color for display.\n" + "The indexes numbers it contains correspond to indexes in the .tm file\n" + "This file is common to all .tm files; when doing new color segmentations,\n" + "make sure you define colors in the same order as listed here! "); + addEntry("restore_image",restore_image,"Apparently someone at Sony thought it would be a good idea to replace some\n" + "pixels in each camera image with information like the frame number and CDT count.\n" + "If non-zero, will replace those pixels with the actual image pixel value in RawCamGenerator "); + addEntry("region_calc_total",region_calc_total,"When true, this will fill in the CMVision::color_class_state::total_area\n" + "field for each color following region labeling. If false, the total_area\n" + "will stay 0 (or whatever the last value was), but you save a little CPU. "); + addEntry("jpeg_dct_method",jpeg_dct_method,"pick between dct methods for jpeg compression\n"+jpeg_dct_method.getDescription()); + //addEntry("aspectRatio",aspectRatio,"ratio of width to height (x_res/y_res); this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received)"); + //addEntry("x_range",x_range,"range of values for the x axis when using generalized coordinates; this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received)"); + //addEntry("y_range",y_range,"range of values for the x axis when using generalized coordinates; this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received)"); + + addEntry("calibration",calibration,"Lens distortion correction parameters\nComputated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet"); + addEntry("rawcam",rawcam); + addEntry("segcam",segcam); + addEntry("regioncam",regioncam); + } + +#ifdef PLATFORM_APERIOS + //! white balance levels supported by the Aibo's camera + enum white_balance_levels { + WB_INDOOR=ocamparamWB_INDOOR_MODE, + WB_OUTDOOR=ocamparamWB_OUTDOOR_MODE, + WB_FLUORESCENT=ocamparamWB_FL_MODE }; - encoding_t rawcam_encoding; //!< holds whether to send color or single channel - int rawcam_channel; //!< RawCameraGenerator::channel_id_t, if raw_encoding is single channel, this holds the channel to send (computed from rawcam_encoding, not set directly) +#else + //! white balance levels supported by the Aibo's camera + enum white_balance_levels { WB_INDOOR=1, WB_OUTDOOR, WB_FLUORESCENT }; +#endif + plist::NamedEnumeration white_balance; //!< white balance shifts color spectrum in the image - //! compression format to use, stored in Config::vision_config::rawcam_compression - enum compression_t { - COMPRESS_NONE, //!< no compression (other than subsampling) - COMPRESS_JPEG, //!< JPEG compression - COMPRESS_PNG, //!< PNG compression - COMPRESS_RLE //!< RLE compression +#ifdef PLATFORM_APERIOS + //! gain levels supported by the Aibo's camera + enum gain_levels { + GAIN_LOW=ocamparamGAIN_LOW, + GAIN_MID=ocamparamGAIN_MID, + GAIN_HIGH=ocamparamGAIN_HIGH }; - compression_t rawcam_compression;//!< holds whether to send jpeg compression +#else + //! gain levels supported by the Aibo's camera + enum gain_levels { GAIN_LOW=1, GAIN_MID, GAIN_HIGH }; +#endif + plist::NamedEnumeration gain; //!< Increasing gain will brighten the image, at the expense of more graininess/noise - int rawcam_compress_quality;//!< 0-100, compression quality (currently only used by jpeg) - int rawcam_y_skip; //!< resolution level to transmit y channel at - int rawcam_uv_skip; //!< resolution level to transmit uv channel at - int segcam_skip; //!< resolution level to transmit segmented images at - int segcam_channel; //!< channel to send (which color threshold map to use) - compression_t segcam_compression; //!< what compression to use on the segmented image - int regioncam_skip; //!< resolution level to transmit segmented images at +#ifdef PLATFORM_APERIOS + //! shutter speeds supported by the Aibo's camera + enum shutter_speeds { + SHUTTER_SLOW=ocamparamSHUTTER_SLOW, + SHUTTER_MID=ocamparamSHUTTER_MID, + SHUTTER_FAST=ocamparamSHUTTER_FAST + }; +#else + //! shutter speeds supported by the Aibo's camera + enum shutter_speeds { SHUTTER_SLOW=1, SHUTTER_MID, SHUTTER_FAST }; +#endif + plist::NamedEnumeration shutter_speed; //!< slower shutter will brighten image, but increases motion blur + + plist::Primitive resolution; //!< the resolution that object recognition system will run at -- this counts down from the maximum resolution layer, so higher numbers mean lower resolution + plist::ArrayOf > thresh; //!< threshold file names + plist::Primitive colors; //!< colors definition (.col) file + plist::Primitive restore_image; //!< if true, replaces pixels holding image info with actual image pixels (as much as possible anyway) + plist::Primitive region_calc_total; //!< if true, RegionGenerator will calculate total area for each color (has to run through the region list for each color) + static const char * dct_method_names[]; //!< string names for #J_DCT_METHOD + plist::NamedEnumeration jpeg_dct_method; //!< pick between dct methods for jpeg compression + plist::Primitive aspectRatio; //!< ratio of width to height (x_res/y_res); this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received) + plist::Primitive x_range; //!< range of values for the x axis when using generalized coordinates; this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received) + plist::Primitive y_range; //!< range of values for the x axis when using generalized coordinates; this is *not* read from configuration file, but set from most recent camera image (or RobotInfo namespace values if no camera image has been received) + + //! contains settings related to streaming video over the network + class StreamingConfig : public ConfigDictionary { + public: + explicit StreamingConfig(int portNum) : ConfigDictionary(), port(portNum), transport(Config::UDP,transport_names), interval(0) + { + addEntry("port",port,"the port number to open for sending data over"); + addEntry("transport",transport,"the IP protocol to use when sending data"); + addEntry("interval",interval,"minimum amount of time (in milliseconds) which must pass between frames\nE.g. 200 yields just under 5 frames per second, 0 is as fast as possible"); + } + plist::Primitive port; + plist::NamedEnumeration transport; + plist::Primitive interval; + }; + + //! contains settings specific to the "RawCam" (original camera images) for streaming video over the network + class RawCamConfig : public StreamingConfig { + public: + RawCamConfig() : StreamingConfig(10011), + encoding(ENCODE_COLOR,encoding_names), channel(0), compression(COMPRESS_JPEG,compression_names), compress_quality(85), y_skip(2), uv_skip(3) + { + addEntry("encoding",encoding,"holds whether to send color or single channel\n"+encoding.getDescription()); + addEntry("channel",channel,"if encoding is single channel, this indicates the channel to send"); + addEntry("compression",compression,"the type of compression to apply the image\n"+compression.getDescription()); + addEntry("compress_quality",compress_quality,"0-100, compression quality (currently only used by jpeg)"); + addEntry("y_skip",y_skip,"resolution level to transmit y channel\nAlso used as the resolution level when in single-channel encoding mode "); + addEntry("uv_skip",uv_skip,"resolution level to transmit uv channel at when using 'color' encoding mode"); + } + //! type of information to send, stored in #encoding + enum encoding_t { + ENCODE_COLOR, //!< send Y, U, and V channels + ENCODE_SINGLE_CHANNEL, //!< send only a single channel (which channel to send is stored in #channel) This is also used for all seg cam images + }; + static const unsigned int NUM_ENCODINGS=2; //!< number of encodings available + static const char * encoding_names[NUM_ENCODINGS+1]; //!< string names for #encoding_t + plist::NamedEnumeration encoding; //!< holds whether to send color or single channel + plist::Primitive channel; //!< RawCameraGenerator::channel_id_t, if #encoding is single channel, this indicates the channel to send + //! compression format to use, stored in Config::vision_config::RawCamConfig::compression + enum compression_t { + COMPRESS_NONE, //!< no compression (other than subsampling) + COMPRESS_JPEG, //!< JPEG compression + COMPRESS_PNG, //!< PNG compression + }; + static const unsigned int NUM_COMPRESSIONS=4; //!< number of compression algorithms available + static const char * compression_names[NUM_COMPRESSIONS+1]; //!< string names for #compression_t + plist::NamedEnumeration compression;//!< holds whether to send jpeg compression + + plist::Primitive compress_quality;//!< 0-100, compression quality (currently only used by jpeg) + plist::Primitive y_skip; //!< resolution level to transmit y channel at + plist::Primitive uv_skip; //!< resolution level to transmit uv channel at + } rawcam; + + //! contains settings specific to the "SegCam" (segmented color images) for streaming video over the network + class SegCamConfig : public StreamingConfig { + public: + SegCamConfig() : StreamingConfig(10012), skip(1), channel(0), compression(COMPRESS_RLE, compression_names) + { + addEntry("skip",skip,"resolution level to transmit segmented images at"); + addEntry("channel",channel,"channel of RLEGenerator to send (i.e. which threshold map to use"); + addEntry("compression",compression,"what compression to use on the segmented image"+compression.getDescription()); + } + plist::Primitive skip; //!< resolution level to transmit segmented images at + plist::Primitive channel; //!< channel of RLEGenerator to send (i.e. which threshold map to use) + + //! compression format to use, stored in Config::vision_config::RawCamConfig::compression + enum compression_t { + COMPRESS_NONE, //!< no compression (other than subsampling) + COMPRESS_RLE //!< RLE compression + }; + static const unsigned int NUM_COMPRESSIONS=4; //!< number of compression algorithms available + static const char * compression_names[NUM_COMPRESSIONS+1]; //!< string names for #compression_t + plist::NamedEnumeration compression;//!< what compression to use on the segmented image + } segcam; + + //! contains settings specific to the "RegionCam" (only display a box for each blob of color) for streaming over the network + class RegionCamConfig : public StreamingConfig { + public: + RegionCamConfig() : StreamingConfig(10013), skip(1) { + addEntry("skip",skip,"resolution level to extract regions from"); + } + plist::Primitive skip; //!< resolution level to transmit segmented images at + } regioncam; + //!These values represent a "Plumb Bob" model introduced by Brown in 1966 /*!Lens Distortion for Close-Range Photogrammetry - D.C. Brown, Photometric Engineering, pages 855-866, Vol. 37, No. 8, 1971. * * Can be computated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet: * http://www.vision.caltech.edu/bouguetj/calib_doc/ */ - //!@name Intrinsic Parameters - float focal_len_x; //!< focal length of camera, in pixels, K11 - float focal_len_y; //!< focal length of camera, in pixels, K22 - float principle_point_x; //!< center of optical projection, K13 - float principle_point_y; //!< center of optical projection, K23 - float skew; //!< CCD skew, K12 = skew*focal_len_x - float kc1_r2; //!< r-squared radial distortion - float kc2_r4; //!< r to the 4 radial distortion - float kc5_r6; //!< r to the 6 radial distortion - float kc3_tan1; //!< first tangential correction term - float kc4_tan2; //!< second tangential correctiont term - unsigned int calibration_res_x; // x resolution of images used during calibration - unsigned int calibration_res_y; // y resolution of images used during calibration - + class CameraCalibration : public ConfigDictionary { + public: + CameraCalibration() : ConfigDictionary(), + focal_len_x(CameraResolutionX),focal_len_y(CameraResolutionX),principle_point_x(CameraResolutionX/2), + principle_point_y(CameraResolutionY/2),skew(0),kc1_r2(0),kc2_r4(0),kc5_r6(0),kc3_tan1(0),kc4_tan2(0), + calibration_res_x(CameraResolutionX), calibration_res_y(CameraResolutionY) + { + addEntry("focal_len_x",focal_len_x,"focal length of camera, in pixels, K11"); + addEntry("focal_len_y",focal_len_y,"focal length of camera, in pixels, K22"); + addEntry("principle_point_x",principle_point_x,"center of optical projection, K13"); + addEntry("principle_point_y",principle_point_y,"center of optical projection, K23"); + addEntry("skew",skew,"CCD skew, K12 = skew*focal_len_x"); + addEntry("kc1_r2",kc1_r2,"r-squared radial distortion"); + addEntry("kc2_r4",kc2_r4,"r to the 4 radial distortion"); + addEntry("kc5_r6",kc5_r6,"r to the 6 radial distortion"); + addEntry("kc3_tan1",kc3_tan1,"first tangential correction term"); + addEntry("kc4_tan2",kc4_tan2,"second tangential correctiont term"); + addEntry("calibration_res_x",calibration_res_x,"x resolution of images used during calibration"); + addEntry("calibration_res_y",calibration_res_y,"y resolution of images used during calibration"); + } + plist::Primitive focal_len_x; //!< focal length of camera, in pixels, K11 + plist::Primitive focal_len_y; //!< focal length of camera, in pixels, K22 + plist::Primitive principle_point_x; //!< center of optical projection, K13 + plist::Primitive principle_point_y; //!< center of optical projection, K23 + plist::Primitive skew; //!< CCD skew, K12 = skew*focal_len_x + plist::Primitive kc1_r2; //!< r-squared radial distortion + plist::Primitive kc2_r4; //!< r to the 4 radial distortion + plist::Primitive kc5_r6; //!< r to the 6 radial distortion + plist::Primitive kc3_tan1; //!< first tangential correction term + plist::Primitive kc4_tan2; //!< second tangential correctiont term + plist::Primitive calibration_res_x; //!< x resolution of images used during calibration + plist::Primitive calibration_res_y; //!< y resolution of images used during calibration + } calibration; + //!provides a ray from camera through pixel in image; where possible, use computePixel for better accuracy (i.e. try to always move from world to camera instead of the other way around) - /*! We can't undo some terms of the distortion model -- this is an estimate. + /*! We can't precisely undo some terms of the distortion model -- this is an estimate. + * @todo Might be able to redo the vision calibration in reverse to get another set of parameters dedicated to the inverse computation? * @param[in] x x position in range [-1,1] * @param[in] y y position in range [-1,1] * @param[out] r_x x value of the ray * @param[out] r_y y value of the ray * @param[out] r_z z value of the ray (always 1) */ - void computeRay(float x, float y, float& r_x, float& r_y, float& r_z) { - x=(x+1)*calibration_res_x/2; - y=(y+1)*calibration_res_y/2; - float yd=(y-principle_point_y)/focal_len_y; - float xd=(x-principle_point_x)/focal_len_x-skew*yd; - float r2=xd*xd+yd*yd; //estimate of original - float radial=(1 + kc1_r2*r2 + kc2_r4*r2*r2 + kc5_r6*r2*r2*r2); - r_x=(xd - 2*kc3_tan1*xd*yd - kc4_tan2*(r2+2*xd*xd))/radial; //estimating tangential component - r_y=(yd - kc3_tan1*(r2+2*yd*yd) - 2*kc4_tan2*xd*yd)/radial; //estimating tangential component - r_z=1; - } + void computeRay(float x, float y, float& r_x, float& r_y, float& r_z); //!provides a pixel hit in image by a ray going through the camera frame - /*! Hopefully we'll eventually upgrade this to account for lens distortion - * @param[in] r_x x value of the ray + /*! @param[in] r_x x value of the ray * @param[in] r_y y value of the ray * @param[in] r_z z value of the ray * @param[out] x x position in range [-1,1] * @param[out] y y position in range [-1,1] */ - void computePixel(float r_x, float r_y, float r_z, float& x, float& y) { - if(r_z==0) { - x=y=0; - return; - } - r_x/=r_z; - r_y/=r_z; - float r2 = r_x*r_x + r_y*r_y; //'r2' for 'radius squared', not 'ray number 2' - float radial=(1 + kc1_r2*r2 + kc2_r4*r2*r2 + kc5_r6*r2*r2*r2); - float xd = radial*r_x + 2*kc3_tan1*r_x*r_y + kc4_tan2*(r2+2*r_x*r_x); - float yd = radial*r_y + kc3_tan1*(r2+2*r_y*r_y) + 2*kc4_tan2*r_x*r_y; - x=focal_len_x*(xd+skew*yd)+principle_point_x; - y=focal_len_y*yd+principle_point_y; - x=2*x/calibration_res_x-1; - y=2*y/calibration_res_y-1; - } + void computePixel(float r_x, float r_y, float r_z, float& x, float& y); //@} - - //!constructor - vision_config() - : white_balance(3), gain(2), shutter_speed(2), resolution(2), - thresh(), rawcam_port(10011), rawcam_transport(0), rawcam_interval(0), - segcam_port(10012), segcam_transport(0), segcam_interval(0), region_port(0), region_transport(0), obj_port(0), restore_image(true), region_calc_total(true), - jpeg_dct_method(JDCT_IFAST), aspectRatio(CameraResolutionX/(float)CameraResolutionY), - x_range(aspectRatio>1?1:aspectRatio), y_range(aspectRatio>1?1/aspectRatio:1), - rawcam_encoding(ENCODE_COLOR), rawcam_channel(0), - rawcam_compression(COMPRESS_NONE), rawcam_compress_quality(75), rawcam_y_skip(0), - rawcam_uv_skip(0), segcam_skip(1), segcam_channel(0), segcam_compression(COMPRESS_RLE), regioncam_skip(1), - focal_len_x(CameraResolutionX),focal_len_y(CameraResolutionX),principle_point_x(CameraResolutionX/2), - principle_point_y(CameraResolutionY/2),skew(0),kc1_r2(0),kc2_r4(0),kc5_r6(0),kc3_tan1(0),kc4_tan2(0), - calibration_res_x(CameraResolutionX), calibration_res_y(CameraResolutionY) - {colors[0]='\0';} + } vision; - //!core functionality information - struct main_config { - bool seed_rng; //!< if true, will call srand with timestamp data, mangled by current sensor data - int console_port; //!< port to send/receive "console" information on (separate from system console) - //! types that #consoleMode can take on - enum consoleMode_t { - CONTROLLER, //!< all input is interpreted as Controller commands, using same syntax as the GUI sends - TEXTMSG, //!< all input is broadcast as a text message event - AUTO //!< if the GUI is connected, interpret as text messages, otherwise as controller commands. This was the historical behavior, but seems to be more confusing than helpful. - }; - //! determines how input on #console_port is interpreted - consoleMode_t consoleMode; - int stderr_port; //!< port to send error information to - int error_level; //!< controls amount of info to error port - int debug_level; //!< controls amount of debug info - int verbose_level; //!< controls verbosity of info - int wsjoints_port; //!< port to send joint positions on - int wspids_port; //!< port to send pid info on - int headControl_port; //!< port for receiving head commands - int walkControl_port; //!< port for receiving walk commands - int estopControl_port; //!< port for receiving walk commands - int stewart_port; //!< port for running a stewart platform style of control - int aibo3d_port; //!< port for send/receive of joint positions from Aibo 3D GUI - int wmmonitor_port; //!< port for monitoring Watchable Memory - bool use_VT100; //!< if true, enables VT100 console codes (currently only in Controller menus - 1.3) - unsigned int worldState_interval; //!< time (in milliseconds) to wait between sending WorldState updates over wireless - //!constructor - main_config() - : seed_rng(true), console_port(10001), consoleMode(CONTROLLER), stderr_port(10002), error_level(0), debug_level(0), - verbose_level(0),wsjoints_port(10031),wspids_port(10032),headControl_port(10052), - walkControl_port(10050),estopControl_port(10053),stewart_port(10055),aibo3d_port(10051), - wmmonitor_port(10061), use_VT100(true), worldState_interval(0) - { } - } main; - - //!placeholder - struct behaviors_config { - unsigned int flash_bytes; //!< how many bytes of the IP to flash - bool flash_on_start; //!< whether or not to trigger flashing when initially started - behaviors_config() : flash_bytes(4), flash_on_start(true) {} //!< constructor - } behaviors; - - //!controller information - struct controller_config { - int gui_port; //!< port to listen for the GUI to connect to aibo on - char select_snd[50]; //!< sound file to use for "select" action - char next_snd[50]; //!< sound file to use for "next" action - char prev_snd[50]; //!< sound file to use for "prev" action - char read_snd[50]; //!< sound file to use for "read from std-in" action - char cancel_snd[50]; //!< sound file to use for "cancel" action - char error_snd[50]; //!< sound file to use to signal errors - + + + //!motion information + class motion_config : public ConfigDictionary { + public: //!constructor - controller_config() : gui_port(10020) { - select_snd[0]=next_snd[0]=prev_snd[0]=read_snd[0]=cancel_snd[0]=error_snd[0]='\0'; + motion_config(Config* c) + : ConfigDictionary(), thisconfig(c), root("data/motion"), walk("walk.prm"), kinematics(), kinematic_chains(), + calibration_scale(PIDJointOffset, NumPIDJoints,1), calibration_offset(PIDJointOffset, NumPIDJoints, 0), + estop_on_snd(), estop_off_snd(), + max_head_tilt_speed(0), max_head_pan_speed(0), max_head_roll_speed(0), inf_walk_accel(false), + console_port(10003), stderr_port(10004) +#ifdef TGT_HAS_WHEELS + , wheelBaseWidth(140), wheelRadius(26) +#endif + { + addEntry("root",root,"path on memory stick to \"motion\" files - for instance, position (.pos) and motion sequence (.mot)\n" + "Any motion related paths which are not absolute (i.e. do not start with '/')\n" + "will be assumed to be relative to this directory "); + addEntry("walk",walk,"the walk parameter file to load by default for new WalkMC's"); + addEntry("kinematics",kinematics,"the ROBOOP format kinematics description file to load"); + addEntry("kinematic_chains",kinematic_chains,"list of chain names to load from the file specified by 'kinematics'"); + addEntry("calibration_scale",calibration_scale,"Multiplier from desired position to command for each PID joint, applied after calibration_offset."); + addEntry("calibration_offset",calibration_offset,"These values indicate the offset from user specified zero point to the\n" + "physical system's zero point. Added before calibration_scale when\n" + "converting from user's desired position to command to send to hardware."); + addEntry("estop_on_snd",estop_on_snd,"sound file to use when e-stop turned on"); + addEntry("estop_off_snd",estop_off_snd,"sound file to use when e-stop turned off"); + addEntry("max_head_tilt_speed",max_head_tilt_speed,"max speed for the head joints, used by HeadPointerMC; rad/s"); + addEntry("max_head_pan_speed",max_head_pan_speed,"max speed for the head joints, used by HeadPointerMC; rad/s"); + addEntry("max_head_roll_speed",max_head_roll_speed,"max speed for the head joints, used by HeadPointerMC; rad/s"); + addEntry("inf_walk_accel",inf_walk_accel,"if true, walks should attempt to switch directions immediately; otherwise they should do some kind of software acceleration to more smoothly switch direction"); + addEntry("console_port",console_port,"port to send/receive \"console\" information on (separate from system console)"); + addEntry("stderr_port",stderr_port,"port to send error information to"); +#ifdef TGT_HAS_WHEELS + addEntry("wheelBaseWidth",wheelBaseWidth,"distance between left and right wheel, in millimeters"); + addEntry("wheelRadius",wheelRadius,"radius of drive wheels, in millimeters"); +#endif } - } controller; - - //!motion information - struct motion_config { - Config* thisconfig; //! kinematic_chains; //!< list of chains to load from #kinematics - float calibration[NumPIDJoints]; //!< multiplier from desired to command for PID joints - char estop_on_snd[50]; //!< sound file to use when e-stop turned on - char estop_off_snd[50]; //!< sound file to use when e-stop turned off - float max_head_tilt_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s - float max_head_pan_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s - float max_head_roll_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s - bool inf_walk_accel; //!< if true, walks should attempt to switch directions immediately; otherwise they should do some kind of software acceleration to more smoothly switch direction - int console_port; //!< port to send/receive "console" information on (separate from system console) - int stderr_port; //!< port to send error information to - + //!returns an absolute path if @a is relative (to root), otherwise just @a name std::string makePath(const std::string& name) { if(name[0]=='/') @@ -260,31 +560,63 @@ else return thisconfig->portPath(root+"/"+name); } - - //!constructor - motion_config(Config* c) - : thisconfig(c), root(), walk(), kinematics(), kinematic_chains(), max_head_tilt_speed(0), - max_head_pan_speed(0), max_head_roll_speed(0), inf_walk_accel(false), console_port(10003), stderr_port(10004) - { - estop_on_snd[0]=estop_off_snd[0]='\0'; - for(unsigned int i=0; i root; //!< path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot) + plist::Primitive walk; //!< the walk parameter file to load by default for new WalkMC's + plist::Primitive kinematics; //!< the kinematics description file to load + plist::ArrayOf > kinematic_chains; //!< list of chain names to load from #kinematics + OutputConfig > calibration_scale; //!< Multiplier from desired position to command for each PID joint, applied after calibration_offset. + OutputConfig > calibration_offset; //!< Indicates the offset from user specified zero point to the physical system's zero point. Added before calibration_scale when converting from user's desired position to command to send to hardware. + plist::Primitive estop_on_snd; //!< sound file to use when e-stop turned on + plist::Primitive estop_off_snd; //!< sound file to use when e-stop turned off + plist::Primitive max_head_tilt_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s + plist::Primitive max_head_pan_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s + plist::Primitive max_head_roll_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s + plist::Primitive inf_walk_accel; //!< if true, walks should attempt to switch directions immediately; otherwise they should do some kind of software acceleration to more smoothly switch direction + plist::Primitive console_port; //!< port to send/receive "console" information on (separate from system console) + plist::Primitive stderr_port; //!< port to send error information to +#ifdef TGT_HAS_WHEELS + plist::Primitive wheelBaseWidth; //!< distance between left and right wheel, in millimeters + plist::Primitive wheelRadius; //!< radius of drive wheels, in millimeters +#endif + + private: motion_config(const motion_config&); //!< don't call motion_config& operator=(const motion_config&); //!< don't call } motion; + + //!sound information - struct sound_config { - Config* thisconfig; //! preload; //!< list of sounds to preload at boot - float pitchConfidenceThreshold; //!< confidence threshold required to generate a pitch event [0-1] - + class sound_config : public ConfigDictionary { + public: + //!constructor + sound_config(Config* c) : ConfigDictionary(), thisconfig(c), root("data/sound"), volume(HIGH), sample_rate(16000), + sample_bits(16), preload(), pitchConfidenceThreshold(.6f), streaming() + { + addEntry("root",root,"path to sound clips"); + volume.addNameForVal("mute",MUTE); + volume.addNameForVal("low",LOW); + volume.addNameForVal("level_1",LOW); + volume.addNameForVal("mid",MID); + volume.addNameForVal("level_2",MID); + volume.addNameForVal("high",HIGH); + volume.addNameForVal("level_3",HIGH); + volume.setStrict(false); + addEntry("volume",volume,"volume in decibels - the value is interpreted as a signed short, where\n" + "0x8000 is mute, 0xFFFF is full volume (low=0xE700, mid=0xEE00, high=0xF600)\n" + "If you directly set the decibel level, be warned sony recommends against going above 0xF600\n" + "However, I believe the commercial software on the ERS-7 runs at 0xFF00.\n" + "Going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.\n"+volume.getDescription()); + addEntry("sample_rate",sample_rate,"sample rate to send to system, currently only 8000 or 16000 supported"); + addEntry("sample_bits",sample_bits,"sample bit depth, either 8 or 16"); + addEntry("preload",preload,"list of sounds to preload at boot"); + addEntry("pitchConfidenceThreshold",pitchConfidenceThreshold,"confidence threshold required to generate a pitch event [0-1]"); + addEntry("streaming",streaming); + } + //!returns an absolute path if @a is relative (to root), otherwise just @a name std::string makePath(const std::string& name) { if(name[0]=='/') @@ -294,64 +626,118 @@ else return thisconfig->portPath(root+"/"+name); } + + Config* thisconfig; //! root; //!< path to sound clips + + //! Provides some symbolic volume levels, although values are based on actual volume in decibels. + /*! The value is interpreted as a signed short, where 0 is full volume, 0x8000 is mute */ + enum volume_levels { MUTE=ospkvolinfdB, LOW=ospkvol25dB, MID=ospkvol18dB, HIGH=ospkvol10dB }; + plist::NamedEnumeration volume; //!< volume in decibels - the value is interpreted as a signed short, where 0 is full volume, 0x8000 is mute + + plist::Primitive sample_rate; //!< sample rate to send to system, currently only 8000 or 16000 supported + plist::Primitive sample_bits; //!< sample bit depth, either 8 or 16 + plist::ArrayOf > preload; //!< list of sounds to preload at boot + plist::Primitive pitchConfidenceThreshold; //!< confidence threshold required to generate a pitch event [0-1] //! audio streaming configuration - struct streaming_config { - unsigned int mic_port; //!< port for streaming microphone samples - unsigned int mic_sample_rate; //!< sample rate from the microphone - unsigned int mic_sample_bits; //!< sample bit depth from the microphone (either 8 or 16) - bool mic_stereo; //!< whether to stream stereo or mono from the microphone - - unsigned int speaker_port; //!< port for streaming speaker samples - unsigned int speaker_frame_length; //!< length of frame sent to the speaker (ms) - unsigned int speaker_max_delay; //!< maximum delay (ms) during playback - + class streaming_config : public ConfigDictionary { + public: //! constructor - streaming_config() : mic_port(10070), mic_sample_rate(16000), - mic_sample_bits(16), mic_stereo(true), - speaker_port(10071), speaker_frame_length(64), - speaker_max_delay(1000) {} + streaming_config() : ConfigDictionary(), mic_port(10070), mic_sample_rate(16000), + mic_sample_bits(16), mic_stereo(true), + speaker_port(10071), speaker_frame_length(64), + speaker_max_delay(1000) + { + addEntry("mic_port",mic_port,"port for streaming microphone samples"); + addEntry("mic_sample_rate",mic_sample_rate,"sample rate from the microphone"); + addEntry("mic_sample_bits",mic_sample_bits,"sample bit depth from the microphone (either 8 or 16)"); + addEntry("mic_stereo",mic_stereo,"whether to stream stereo or mono from the microphone"); + + addEntry("speaker_port",speaker_port,"port for streaming speaker samples"); + addEntry("speaker_frame_length",speaker_frame_length,"length of frame sent to the speaker (ms)"); + addEntry("speaker_max_delay",speaker_max_delay,"maximum delay (ms) during playback"); + } + plist::Primitive mic_port; //!< port for streaming microphone samples + plist::Primitive mic_sample_rate; //!< sample rate from the microphone + plist::Primitive mic_sample_bits; //!< sample bit depth from the microphone (either 8 or 16) + plist::Primitive mic_stereo; //!< whether to stream stereo or mono from the microphone + + plist::Primitive speaker_port; //!< port for streaming speaker samples + plist::Primitive speaker_frame_length; //!< length of frame sent to the speaker (ms) + plist::Primitive speaker_max_delay; //!< maximum delay (ms) during playback } streaming; - - //!constructor - sound_config(Config* c) : thisconfig(c), root(), volume(0xF600), sample_rate(0), sample_bits(0), preload(), pitchConfidenceThreshold(.6f), streaming() {} private: sound_config(const sound_config&); //!< don't call sound_config& operator=(const sound_config&); //!< don't call } sound; - //! call this function when it's time to read the configuration file - void readConfig(const std::string& filename); - //! returns the section structure corresponding to the section name given - section_t parseSection(const char* key); + + + virtual void saveXML(xmlNode* node, bool onlyOverwrite, std::set& seen) const; + using ConfigDictionary::saveXML; + virtual unsigned int loadBuffer(const char buf[], unsigned int len); + virtual unsigned int loadFile(const char* filename); + virtual unsigned int loadFileStream(FILE* f); + //! pass the section, item name string, item value string - sets the value and returns pointer to the item changed - void* setValue(section_t section, const char *key, const char *value, bool updated=false); - - + /*! this is the older deprecated interface -- use the inherited resolveEntry() instead to support sub-sections */ + void* setValue(const std::string& section, std::string key, const std::string& value); + protected: - //! returns true if pattern matches model - pattern may have up to 1 '*', case insensitive - bool matchNoCase(const std::string& model, const std::string& pattern); - - //! returns bool value corresponding to a @a value of "t", "f", "true", "false", "y", "n", "yes", "no", or zero/nonzero number - static bool extractBool(const char* value); + static const char * xmlIntro1; + static const char * xmlIntro2; + static const char * xmlIntro3; + + static const std::locale& curLocale; + static char localeToLower(char c) { return std::tolower(c,curLocale); }; + + unsigned int loadOldFormat(const char buf[], unsigned int len); + unsigned int loadOldFormat(FILE* f); + void parseLine(const char buf[], unsigned int lineno, std::vector& modelStack, bool& ignoring, std::string& section); //! a prefix representing the file system root, usually indicating the robot's storage root. /*! When running in the simulator, this is used to pretend that a subdirectory in the project folder (e.g. 'ms') is the root file system */ std::string fsRoot; }; +template +void OutputConfig::saveXML(xmlNode* node, bool onlyOverwrite, std::set& seen) const { + // first just overwrite what's already there as we normally do + ConfigDictionary::saveXML(node,true,seen); + // now if there's anything left... + if(!onlyOverwrite && seen.size()!=dict.size()) { + // clear text nodes from end of dictionary back to last entry + for(xmlNode* cur=xNodeGetLastChild(node); cur!=NULL && xNodeIsText(cur); cur=xNodeGetLastChild(node)) { + xmlUnlinkNode(cur); + xmlFreeNode(cur); + } + std::string indentStr=getIndentationPrefix(node); + // this is the customized part -- save in "natural" output order instead of alphabetically by key + for(unsigned int i=0; i=perIndent().size()) + parentIndent=indentStr.substr(perIndent().size()); + xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+parentIndent).c_str())); + } +} + //!allows global access to current settings extern Config* config; /*! @file * @brief Describes Config, which provides global access to system configuration information - * @author alokl (Creator) + * @author ejt (Creator) + * @author alokl (Original configuration system) * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.55 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.64 $ * $State: Exp $ - * $Date: 2006/09/21 21:26:08 $ + * $Date: 2007/11/16 15:53:49 $ */ #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/CreateInfo.h ./Shared/CreateInfo.h --- ../Tekkotsu_3.0/Shared/CreateInfo.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/CreateInfo.h 2007-11-19 16:52:41.000000000 -0500 @@ -0,0 +1,285 @@ +//-*-c++-*- +#ifndef INCLUDED_CreateInfo_h +#define INCLUDED_CreateInfo_h + +#include +#include +#include "CommonInfo.h" +using namespace RobotInfo; + +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_CREATE) +# define TGT_HAS_WHEELS 2 +# define TGT_HAS_LEDS 2 +#endif + +//! Contains information about an iRobot Create, such as number of joints, timing information, etc. +namespace CreateInfo { + + // ******************************* + // ROBOT CONFIGURATION + // ******************************* + + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs + + const unsigned int FrameTime=15; //!< time between frames in the motion system (milliseconds) + const unsigned int NumFrames=1; //!< the number of frames per buffer (don't forget also double buffered) + const unsigned int SoundBufferTime=32; //!< the number of milliseconds per sound buffer... I'm not sure if this can be changed + + //!@name Output Types Information + const unsigned NumWheels = 2; + + const unsigned JointsPerArm = 0; + const unsigned NumArms = 0; + const unsigned NumArmJoints = JointsPerArm*NumArms; + + const unsigned JointsPerLeg = 0; //!< The number of joints per leg + const unsigned NumLegs = 0; //!< The number of legs + const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs + const unsigned NumHeadJoints = 0; //!< The number of joints in the neck + const unsigned NumTailJoints = 0; //!< The number of joints assigned to the tail + const unsigned NumMouthJoints = 0; //!< the number of joints that control the mouth + const unsigned NumEarJoints = 0; //!< The number of joints which control the ears (NOT per ear, is total) + const unsigned NumButtons = 0; //!< the number of buttons that are available, 2 head, 4 paws, 3 back, 1 underbelly see ERS7Info::ButtonOffset_t + const unsigned NumSensors = 18; //!< the number of sensors available + const unsigned NumLEDs = 2; //!< The number of LEDs which can be controlled + const unsigned NumFacePanelLEDs = 0; //!< The number of face panel LEDs + + const unsigned NumPIDJoints = 0; //!< servo pins + const unsigned NumOutputs = NumWheels + NumLEDs; //!< the total number of outputs + const unsigned NumReferenceFrames = NumOutputs + 1 + NumArms + 1; //!< for the base, gripper (* NumArms), and camera reference frames + + // webcam ? + const float CameraHorizFOV=56.9/180*M_PI; //!< horizontal field of view (radians) + const float CameraVertFOV=45.2/180*M_PI; //!< vertical field of view (radians) + const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV + const unsigned int CameraResolutionX=320; //!< the number of pixels available in the 'full' layer + const unsigned int CameraResolutionY=240; //!< the number of pixels available in the 'full' layer + //@} + + + // ******************************* + // OUTPUT OFFSETS + // ******************************* + + //!Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file + //!@name Output Offsets + + + const unsigned PIDJointOffset = 0; //!< The beginning of the PID Joints + const unsigned WheelOffset = PIDJointOffset; + + const unsigned LEDOffset = PIDJointOffset + NumPIDJoints; //!< the offset of LEDs in WorldState::outputs and MotionCommand functions, see LedOffset_t for specific offsets + + const unsigned MODE_OFFSET = LEDOffset + NumLEDs; + const unsigned DEMO_OFFSET = MODE_OFFSET+1; + + const unsigned BaseFrameOffset = NumOutputs; //!< Use with kinematics to refer to base reference frame + + enum WheelOffset_t { + LWheelOffset=WheelOffset, + RWheelOffset + }; + + //! The offsets of the individual LEDs on the head and tail. Note that left/right are robot's point of view. See also LEDBitMask_t + /*! @hideinitializer */ + enum LEDOffset_t { + }; + + typedef unsigned int LEDBitMask_t; //!< So you can be clear when you're refering to a LED bitmask + //! LEDs for the face panel (all FaceLEDPanelMask<<(0:NumFacePanelLEDs-1) entries) + const LEDBitMask_t FaceLEDMask = 0; + //! selects all of the leds + const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; + //@} + + enum InterfaceMode_t { + MODE_SAFE, + MODE_FULL, + MODE_PASSIVE, + MODE_OFF, + }; + + // ******************************* + // INPUT OFFSETS + // ******************************* + + + //! The order in which inputs should be stored + //!@name Input Offsets + + //! holds offsets to different buttons in WorldState::buttons[] + /*! Should be a straight mapping to the ButtonSourceIDs + * + * @see WorldState::buttons + * @hideinitializer */ + enum ButtonOffset_t { + PLAY_OFFSET, //!< 1 if play button is down + ADVANCE_OFFSET, //!< 1 if advance button is down + WALL_OFFSET, //!< 1 if wall is detected (note correspondence to WALL_SIGNAL_OFFSET's value, avoiding problems if the two are swapped) + DROP_CASTER_OFFSET, //!< 1 if caster detects dropoff + DROP_LEFT_WHEEL_OFFSET, //!< 1 if left wheel detects dropoff + DROP_RIGHT_WHEEL_OFFSET, //!< 1 if right wheel detects dropoff + BUMP_LEFT_OFFSET, //!< 1 if left bumper is pressed + BUMP_RIGHT_OFFSET, //!< 1 if right bumper is pressed + OVERCURRENT_LEFT_WHEEL_OFFSET, //!< 1 if the left wheel is drawing more than 1 amp + OVERCURRENT_RIGHT_WHEEL_OFFSET, //!< 1 if the right wheel is drawing more than 1 amp + LOW_SIDE_DRIVER_0_OFFSET, //!< 1 if low side driver 0 is pulling more than 0.5 amps + LOW_SIDE_DRIVER_1_OFFSET, //!< 1 if low side driver 1 is pulling more than 0.5 amps + LOW_SIDE_DRIVER_2_OFFSET, //!< 1 if low side driver 2 is pulling more than 1.6 amps + BASE_CHARGER_OFFSET, //!< 1 if the home base charger is available + INTERNAL_CHARGER_OFFSET //!< 1 if the internal charger is available + }; + + //! Provides a string name for each button + const char* const buttonNames[NumButtons+1] = { NULL }; // non-empty array to avoid gcc 3.4.2 internal error + + //! holds offset to different sensor values in WorldState::sensors[] + /*! @see WorldState::sensors[] */ + enum SensorOffset_t { + DIGITAL0_INPUTS_OFFSET, //!< the digital input pins in bits 0 through 4 + DIGITAL1_INPUTS_OFFSET, //!< the digital input pins in bits 0 through 4 + DIGITAL2_INPUTS_OFFSET, //!< the digital input pins in bits 0 through 4 + DIGITAL3_INPUTS_OFFSET, //!< the digital input pins in bits 0 through 4 + ANALOG_SIGNAL_OFFSET, //!< voltage on cargo bay pin 4 + WALL_SIGNAL_OFFSET, //!< strength of the wall sensor's signal (note correspondence to WALL_OFFSET's value, avoid problems if the two are swapped) + IR_COMM_OFFSET, //!< value received by the infrared communication receiver, see IRComm_t for values sent by standard hardware + CLIFF_LEFT_SIGNAL_OFFSET, //!< strength of the left cliff sensor + CLIFF_FRONT_LEFT_SIGNAL_OFFSET, //!< strength of the front left cliff sensor + CLIFF_FRONT_RIGHT_SIGNAL_OFFSET, //!< strength of the front right cliff sensor + CLIFF_RIGHT_SIGNAL_OFFSET, //!< strength of the right cliff sensor + ENCODER_DISTANCE_OFFSET, //!< average distance (mm) traveled by the wheels since last update + ENCODER_ANGLE_OFFSET, //!< average angle (radians) rotated since the last update + VOLTAGE_OFFSET, //!< mV measured at battery + CURRENT_OFFSET, //!< mA flowing into battery (negative when discharging) + BATTERY_CHARGE_OFFSET, //!< mAh remaining in battery (may not be accurate with alkaline battery pack) + BATTERY_TEMP_OFFSET, //!< degrees celsius + CHARGING_STATE_OFFSET //!< one of #ChargingState_t + }; + + enum IRComm_t { + IR_REMOTE_LEFT=129, + IR_REMOTE_FORWARD, + IR_REMOTE_RIGHT, + IR_REMOTE_SPOT, + IR_REMOTE_MAX, + IR_REMOTE_SMALL, + IR_REMOTE_MEDIUM, + IR_REMOTE_LARGE, + IR_REMOTE_PAUSE, + IR_REMOTE_POWER, + IR_REMOTE_ARC_LEFT, + IR_REMOTE_ARC_RIGHT, + IR_REMOTE_STOP, + IR_REMOTE_SEND, + IR_REMOTE_DOCK, + IR_BASE_RED=248, + IR_BASE_GREEN=244, + IR_BASE_FORCE=242, + IR_BASE_RED_GREEN=252, + IR_BASE_RED_FORCE=250, + IR_BASE_GREEN_FORCE=246, + IR_BASE_RED_GREEN_FORCE=254 + }; + /*const unsigned IR_BASE_MASK=240; + const unsigned IR_BASE_RED_MASK=8; + const unsigned IR_BASE_GREEN_MASK=4; + const unsigned IR_BASE_FORCE_MASK=2;*/ + + enum ChargingState_t { + CHARGING_OFF, + CHARGING_RECONDITIONING, + CHARGING_FULL, + CHARGING_TRICKLE, + CHARGING_WAITING, + CHARGING_FAULT + }; + + //! Provides a string name for each sensor + const char* const sensorNames[NumSensors] = { + "DigitalIn0", + "DigitalIn1", + "DigitalIn2", + "DigitalIn3", + "AnalogIn", + "WallSignal", + "IR", + "CliffLeftSignal", + "CliffFrontLeftSignal", + "CliffFrontRightSignal", + "CliffRight", + "Distance", + "Angle", + "BatteryVoltage", + "BatteryCurrent", + "BatteryCharge", + "BatteryTemp", + "ChargingState", + }; // non-empty array to avoid gcc 3.4.2 internal error + + //@} + + + //! Names for each of the outputs + const char* const outputNames[NumOutputs] = { + "WHEEL:L", + "WHEEL:R", + "LED:00000", + "LED:00001", + }; + + //! allocation declared in RobotInfo.cc + extern Capabilities capabilities; + + //! This table holds the default PID values for each joint. see PIDMC + const float DefaultPIDs[NumPIDJoints+1][3] = { + {0,0,0} // extra value to avoid error in older versions of gcc (doesn't like empty array + }; + + //!These values are our recommended maximum joint velocities, in rad/ms + /*! a value <= 0 means infinite speed (e.g. LEDs) + * + * These limits are not enforced by the framework. They are simply available for you to use as you see fit. + * HeadPointerMC and PostureMC are primary examples of included classes which do respect these values (although they can be overridden) + * + * These values were obtained from the administrators of the Sony OPEN-R BBS */ + const float MaxOutputSpeed[NumOutputs] = { + 1<<8, + 1<<8, + 1<<8, + 1<<8, + }; + + #ifndef RAD + //!Just a little macro for converting degrees to radians + #define RAD(deg) (((deg) * M_PI ) / 180.0) + //!a flag so we undef these after we're done - do you have a cleaner solution? + #define __RI_RAD_FLAG + #endif + + //! This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + const double outputRanges[NumOutputs][2] = + { + { -1 , 1 }, + { -1 , 1 }, + { RAD(-90) , RAD(90) }, + { RAD(-90) , RAD(90) }, + }; + + //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + /*! Same as #outputRanges, don't know actual values because they were never specified by Sony */ + const double mechanicalLimits[NumOutputs][2] = + { + { -1 , 1 }, + { -1 , 1 }, + { RAD(-90) , RAD(90) }, + { RAD(-90) , RAD(90) }, + }; + +#ifdef __RI_RAD_FLAG +#undef RAD +#undef __RI_RAD_FLAG +#endif +} + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ERS210Info.h ./Shared/ERS210Info.h --- ../Tekkotsu_3.0/Shared/ERS210Info.h 2006-10-03 22:41:51.000000000 -0400 +++ ./Shared/ERS210Info.h 2007-11-09 14:01:14.000000000 -0500 @@ -2,31 +2,23 @@ #ifndef INCLUDED_ERS210Info_h #define INCLUDED_ERS210Info_h -#include -#ifndef PLATFORM_APERIOS -typedef unsigned short word; //!< otherwise defined in Types.h -#else -#include -#endif - -#include "CommonInfo.h" -using namespace RobotInfo; +#include "CommonERSInfo.h" -#if TGT_ERS2xx -#include "ERS2xxInfo.h" +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_ERS210) +# define TGT_HAS_LEDS 9 +# define TGT_HAS_BUTTONS 8 +# define TGT_HAS_IR_DISTANCE 1 #endif //! Contains information about the ERS-210 Robot, such as number of joints, PID defaults, timing information, etc. namespace ERS210Info { -#if TGT_ERS2xx - using namespace ERS2xxInfo; -#else // ******************************* // ROBOT CONFIGURATION // ******************************* - const char* const RobotName="ERS-210"; //!< the name of the model, to be used for logging and remote GUIs + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs const unsigned int FrameTime=8; //!< time between frames in the motion system (milliseconds) const unsigned int NumFrames=4; //!< the number of frames per buffer (don't forget also double buffered) @@ -37,6 +29,12 @@ //!Corresponds to entries in ERS210Info::PrimitiveName, defined at the end of this file, these are the primary grouping /*!Right now all binary joints are slow, but perhaps this won't always be the case... hence the IsFast/Slow bitmasks to select which type, in order to be more general */ //!@name Output Types Information + const unsigned NumWheels = 0; //!< no wheels, just legs + + const unsigned JointsPerArm = 0; //!< no arms, just legs + const unsigned NumArms = 0; //!< no arms, just legs + const unsigned NumArmJoints = JointsPerArm*NumArms; + const unsigned JointsPerLeg = 3; //!< The number of joints per leg const unsigned NumLegs = 4; //!< The number of legs const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs @@ -49,7 +47,7 @@ const unsigned NumLEDs = 9; //!< The number of LEDs which can be controlled const unsigned NumPIDJoints = NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints; //!< The number of joints which use PID motion - everything except ears - const unsigned NumBinJoints = NumEarJoints; //!< The number of binary joints - just the ears + const unsigned NumBinJoints = NumEarJoints; //!< The number of binary joints - just the ears (Aperios only) const unsigned NumOutputs = NumPIDJoints + NumBinJoints + NumLEDs; //!< the total number of outputs const unsigned NumReferenceFrames = NumOutputs + 1 + NumLegs + 1 + 1; //!< for the base, paw, camera, and IR sensor reference frames @@ -64,12 +62,10 @@ //! true for joints which can be updated every 32 ms (all but the ears) /*! @hideinitializer */ const bool IsFastOutput[NumOutputs] = { true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,false,false }; - //! we need this so you can tell programmatically which joints are "real" and which are "fake" in ERS-2xx target mode - /*! @hideinitializer */ - const bool IsRealERS210[NumOutputs] = { true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true }; //@} - - + + + // ******************************* // OUTPUT OFFSETS // ******************************* @@ -94,6 +90,29 @@ const unsigned CameraFrameOffset = PawFrameOffset+NumLegs; //!< Use with kinematics to refer to camera reference frame const unsigned IRFrameOffset = CameraFrameOffset+1; //!< Use with kinematics to refer to infrared (distance) sensor reference frame + //! the ordering of legs + enum LegOrder_t { + LFrLegOrder = 0, //!< left front leg + RFrLegOrder, //!< right front leg + LBkLegOrder, //!< left back leg + RBkLegOrder //!< right back leg + }; + + //! The offsets within appendages (the legs) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the head's TPROffset_t's) + enum REKOffset_t { + RotatorOffset=0, //!< moves leg forward or backward along body + ElevatorOffset, //!< moves leg toward or away from body + KneeOffset //!< moves knee + }; + + //! The offsets of appendages with tilt (elevation), pan (heading), and roll or nod joints (i.e. head) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the leg's REKOffset_t's) + enum TPROffset_t { + TiltOffset = 0, //!< tilt/elevation (vertical) + PanOffset, //!< pan/heading (horizontal) + RollOffset, //!< roll (rotational) + NodOffset=RollOffset //!< nod (second tilt) + }; + //! The offsets of the individual legs enum LegOffset_t { LFrLegOffset = LegOffset+LFrLegOrder*JointsPerLeg, //!< beginning of left front leg @@ -159,8 +178,9 @@ const LEDBitMask_t TailLEDMask = TlRedLEDMask|TlBluLEDMask; //!< LEDs on tail const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; //!< selects all of the leds //@} - - + + + // ******************************* // INPUT OFFSETS // ******************************* @@ -175,7 +195,7 @@ * Note that the chest (power) button is not a normal button. It kills * power to the motors at a hardware level, and isn't sensed in the * normal way. If you want to know when it is pressed (and you are - * about to shut down) see PowerSourceID::PauseSID. + * about to shut down) see PowerSrcID::PauseSID. * * @see WorldState::buttons @see ButtonSourceID_t */ enum ButtonOffset_t { @@ -223,48 +243,64 @@ //@} - //! The length of the strings used for each of the outputs in outputNames (doesn't include null term) - const unsigned outputNameLen = 9; - //! A name of uniform length for referring to joints - handy for posture files, etc. + //! Names for each of the outputs const char* const outputNames[NumOutputs] = { "LFr:rotor", "LFr:elvtr", - "LFr:knee~", + "LFr:knee", "RFr:rotor", "RFr:elvtr", - "RFr:knee~", + "RFr:knee", "LBk:rotor", "LBk:elvtr", - "LBk:knee~", + "LBk:knee", "RBk:rotor", "RBk:elvtr", - "RBk:knee~", + "RBk:knee", "NECK:tilt", - "NECK:pan~", + "NECK:pan", "NECK:roll", "TAIL:tilt", - "TAIL:pan~", + "TAIL:pan", - "MOUTH~~~~", + "MOUTH", - "LED:botL~", - "LED:botR~", - "LED:midL~", - "LED:midR~", - "LED:topL~", - "LED:topR~", + "LED:botL", + "LED:botR", + "LED:midL", + "LED:midR", + "LED:topL", + "LED:topR", "LED:topBr", "LED:tlRed", "LED:tlBlu", - "EAR:left~", + "EAR:left", "EAR:right" }; - + + //! provides polymorphic robot capability detection/mapping + class ERS210Capabilities : public Capabilities { + public: + //! constructor + ERS210Capabilities() + : Capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs) + { + // ers-7 button alias + buttonToIndex["HeadBut"]=HeadButOffset; + // 220 led aliases + outputToIndex["LED:bkL1"]=TailLeftLEDOffset; + outputToIndex["LED:bkL2"]=TailRightLEDOffset; + } + }; + //! allocation declared in RobotInfo.cc + extern ERS210Capabilities capabilities; + + //! the joint identifier strings used to refer to specific joints in OPEN-R (but not needed for others) /*!@showinitializer * @warning IMPORTANT!!!! DO NOT CHANGE THE ORDER OF ITEMS IN THIS TABLE!!!\n @@ -457,41 +493,39 @@ #undef __RI_RAD_FLAG #endif -#endif //TGT_ERS2xx check - /*! @name CPC IDs * values defined by OPEN-R, used to interface with lower level OPEN-R code to read sensors - DOESN'T correspond to ERS210Info::PrimitiveName */ - static const int CPCJointNeckTilt = 0; // Head - static const int CPCJointNeckPan = 1; - static const int CPCJointNeckRoll = 2; - static const int CPCSensorHeadBackPressure = 3; - static const int CPCSensorHeadFrontPressure = 4; - static const int CPCSensorPSD = 5; - static const int CPCJointMouth = 6; - static const int CPCSensorChinSwitch = 7; - static const int CPCJointLFRotator = 8; // Left front leg - static const int CPCJointLFElevator = 9; - static const int CPCJointLFKnee = 10; - static const int CPCSensorLFPaw = 11; - static const int CPCJointLHRotator = 12; // Left hind leg - static const int CPCJointLHElevator = 13; - static const int CPCJointLHKnee = 14; - static const int CPCSensorLHPaw = 15; - static const int CPCJointRFRotator = 16; // Right front leg - static const int CPCJointRFElevator = 17; - static const int CPCJointRFKnee = 18; - static const int CPCSensorRFPaw = 19; - static const int CPCJointRHRotator = 20; // Right hind leg - static const int CPCJointRHElevator = 21; - static const int CPCJointRHKnee = 22; - static const int CPCSensorRHPaw = 23; - static const int CPCJointTailPan = 24; // Tail - static const int CPCJointTailTilt = 25; - static const int CPCSensorThermoSensor = 26; - static const int CPCSensorBackSwitch = 27; - static const int CPCSensorAccelFB = 28; //!< Front-back; see RobotInfo::BAccelOffset - static const int CPCSensorAccelLR = 29; //!< Left-right; see RobotInfo::LAccelOffset - static const int CPCSensorAccelUD = 30; //!< Up-down; see RobotInfo::DAccelOffset + const int CPCJointNeckTilt = 0; // Head + const int CPCJointNeckPan = 1; + const int CPCJointNeckRoll = 2; + const int CPCSensorHeadBackPressure = 3; + const int CPCSensorHeadFrontPressure = 4; + const int CPCSensorPSD = 5; + const int CPCJointMouth = 6; + const int CPCSensorChinSwitch = 7; + const int CPCJointLFRotator = 8; // Left front leg + const int CPCJointLFElevator = 9; + const int CPCJointLFKnee = 10; + const int CPCSensorLFPaw = 11; + const int CPCJointLHRotator = 12; // Left hind leg + const int CPCJointLHElevator = 13; + const int CPCJointLHKnee = 14; + const int CPCSensorLHPaw = 15; + const int CPCJointRFRotator = 16; // Right front leg + const int CPCJointRFElevator = 17; + const int CPCJointRFKnee = 18; + const int CPCSensorRFPaw = 19; + const int CPCJointRHRotator = 20; // Right hind leg + const int CPCJointRHElevator = 21; + const int CPCJointRHKnee = 22; + const int CPCSensorRHPaw = 23; + const int CPCJointTailPan = 24; // Tail + const int CPCJointTailTilt = 25; + const int CPCSensorThermoSensor = 26; + const int CPCSensorBackSwitch = 27; + const int CPCSensorAccelFB = 28; //!< Front-back; see RobotInfo::BAccelOffset + const int CPCSensorAccelLR = 29; //!< Left-right; see RobotInfo::LAccelOffset + const int CPCSensorAccelUD = 30; //!< Up-down; see RobotInfo::DAccelOffset //@} } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ERS220Info.h ./Shared/ERS220Info.h --- ../Tekkotsu_3.0/Shared/ERS220Info.h 2006-10-03 22:41:51.000000000 -0400 +++ ./Shared/ERS220Info.h 2007-11-09 14:01:14.000000000 -0500 @@ -5,31 +5,23 @@ #ifndef INCLUDED_ERS220Info_h #define INCLUDED_ERS220Info_h -#include -#ifndef PLATFORM_APERIOS -typedef unsigned short word; //!< otherwise defined in Types.h -#else -#include -#endif - -#include "CommonInfo.h" -using namespace RobotInfo; +#include "CommonERSInfo.h" -#if TGT_ERS2xx -#include "ERS2xxInfo.h" +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_ERS220) +# define TGT_HAS_LEDS 20 +# define TGT_HAS_BUTTONS 11 +# define TGT_HAS_IR_DISTANCE 1 #endif //! Contains information about the ERS-220 Robot, such as number of joints, PID defaults, timing information, etc. namespace ERS220Info { -#if TGT_ERS2xx - using namespace ERS2xxInfo; -#else // ******************************* // ROBOT CONFIGURATION // ******************************* - const char* const RobotName="ERS-220"; //!< the name of the model, to be used for logging and remote GUIs + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs const unsigned int FrameTime=8; //!< time between frames in the motion system (milliseconds) const unsigned int NumFrames=4; //!< the number of frames per buffer (don't forget also double buffered) @@ -40,6 +32,12 @@ //!Corresponds to entries in ERS220Info::PrimitiveName, defined at the end of this file, these are the primary grouping /*!Right now all binary joints are slow, but perhaps this won't always be the case... hence the IsFast/Slow bitmasks to select which type, in order to be more general */ //!@name Output Types Information + const unsigned NumWheels = 0; //!< no wheels, just legs + + const unsigned JointsPerArm = 0; //!< no arms, just legs + const unsigned NumArms = 0; //!< no arms, just legs + const unsigned NumArmJoints = JointsPerArm*NumArms; + const unsigned JointsPerLeg = 3; //!< The number of joints per leg const unsigned NumLegs = 4; //!< The number of legs const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs @@ -52,7 +50,7 @@ const unsigned NumLEDs = 20; //!< The number of LEDs which can be controlled const unsigned NumPIDJoints = NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints; //!< The number of joints which use PID motion - everything - const unsigned NumBinJoints = NumEarJoints; //!< The number of binary joints - just the ears (which the 220 doesn't have) + const unsigned NumBinJoints = NumEarJoints; //!< The number of binary joints - just the ears (which the 220 doesn't have) (Aperios only) const unsigned NumOutputs = NumPIDJoints + NumBinJoints + NumLEDs; //!< the total number of outputs const unsigned NumReferenceFrames = NumOutputs + 1 + NumLegs + 1 + 1; //!< for the base, paw, camera, and IR sensor reference frames @@ -84,25 +82,6 @@ // for binary joints (none supported/exist on 220) }; - //! we need this so you can tell programmatically which joints are "real" and which are "fake" in ERS-2xx target mode - const bool IsRealERS220[NumOutputs] = { - // for PID joints - true, true, true, - true, true, true, - true, true, true, - true, true, true, - true, true, true, - // for LEDs - true, true, true, // face left side LEDs x3 - true, true, true, // face right side LEDs x3 - true, // head mode LED x1 - true, true, true, // back left multi LEDs x3 - true, true, true, // back right multi LEDs x3 - true, true, true, // tail LEDs x3 - true, true, true, // face front LEDs x3 - true, // retractable head light x1 - // for binary joints (none supported/exist on 220) - }; // ******************************* @@ -125,6 +104,29 @@ const unsigned CameraFrameOffset = PawFrameOffset+NumLegs; //!< Use with kinematics to refer to camera reference frame const unsigned IRFrameOffset = CameraFrameOffset+1; //!< Use with kinematics to refer to infrared (distance) sensor reference frame + //! the ordering of legs + enum LegOrder_t { + LFrLegOrder = 0, //!< left front leg + RFrLegOrder, //!< right front leg + LBkLegOrder, //!< left back leg + RBkLegOrder //!< right back leg + }; + + //! The offsets within appendages (the legs) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the head's TPROffset_t's) + enum REKOffset_t { + RotatorOffset=0, //!< moves leg forward or backward along body + ElevatorOffset, //!< moves leg toward or away from body + KneeOffset //!< moves knee + }; + + //! The offsets of appendages with tilt (elevation), pan (heading), and roll or nod joints (i.e. head) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the leg's REKOffset_t's) + enum TPROffset_t { + TiltOffset = 0, //!< tilt/elevation (vertical) + PanOffset, //!< pan/heading (horizontal) + RollOffset, //!< roll (rotational) + NodOffset=RollOffset //!< nod (second tilt) + }; + //! The offsets of the individual legs enum LegOffset_t { LFrLegOffset = LegOffset+LFrLegOrder*JointsPerLeg, //!< beginning of left front leg @@ -240,8 +242,9 @@ //! selects all of the leds const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; //@} - - + + + // ******************************* // INPUT OFFSETS // ******************************* @@ -256,7 +259,7 @@ * Note that the chest (power) button is not a normal button. It kills * power to the motors at a hardware level, and isn't sensed in the * normal way. If you want to know when it is pressed (and you are - * about to shut down) see PowerSourceID::PauseSID. + * about to shut down) see PowerSrcID::PauseSID. * * @see WorldState::buttons @see ButtonSourceID_t */ enum ButtonOffset_t { @@ -307,41 +310,39 @@ //@} - //! The length of the strings used for each of the outputs in outputNames (doesn't include null term) - const unsigned outputNameLen = 9; - //! A name of uniform length for referring to joints - handy for posture files, etc. + //! Names for each of the outputs const char* const outputNames[NumOutputs] = { "LFr:rotor", "LFr:elvtr", - "LFr:knee~", + "LFr:knee", "RFr:rotor", "RFr:elvtr", - "RFr:knee~", + "RFr:knee", "LBk:rotor", "LBk:elvtr", - "LBk:knee~", + "LBk:knee", "RBk:rotor", "RBk:elvtr", - "RBk:knee~", + "RBk:knee", "NECK:tilt", - "NECK:pan~", + "NECK:pan", "NECK:roll", - "LED:botL~", - "LED:botR~", - "LED:midL~", - "LED:midR~", - "LED:topL~", - "LED:topR~", + "LED:botL", + "LED:botR", + "LED:midL", + "LED:midR", + "LED:topL", + "LED:topR", "LED:topBr", - "LED:bkL1~", // "LED:tlBlu" of ERS-210 - "LED:bkL2~", // "LED:tlRed" of ERS-210 - "LED:bkL3~", - "LED:bkR3~", - "LED:bkR2~", - "LED:bkR1~", + "LED:bkL1", // "LED:tlBlu" of ERS-210 + "LED:bkL2", // "LED:tlRed" of ERS-210 + "LED:bkL3", + "LED:bkR3", + "LED:bkR2", + "LED:bkR1", "LED:tailL", "LED:tailC", "LED:tailR", @@ -351,7 +352,25 @@ "LED:light", // retractable head light }; - + + //! provides polymorphic robot capability detection/mapping + class ERS220Capabilities : public Capabilities { + public: + //! constructor + ERS220Capabilities() + : Capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs) + { + // ers-7 button alias + buttonToIndex["HeadBut"]=HeadButOffset; + // 220 led aliases + outputToIndex["LED:tlBlu"]=TlBluLEDOffset; + outputToIndex["LED:tlRed"]=TlRedLEDOffset; + } + }; + //! allocation declared in RobotInfo.cc + extern ERS220Capabilities capabilities; + + //! the joint identifier strings used to refer to specific joints in OPEN-R (but not needed for others) /*!@showinitializer * @warning IMPORTANT!!!! DO NOT CHANGE THE ORDER OF ITEMS IN THIS TABLE!!!\n @@ -551,41 +570,39 @@ #undef __RI_RAD_FLAG #endif -#endif //TGT_ERS2xx check - /*! @name CPC IDs * values defined by OPEN-R, used to interface with lower level OPEN-R code to read sensors - DOESN'T correspond to ERS220Info::PrimitiveName */ - static const int CPCJointNeckTilt = 0; // PRM:/r1/c1-Joint2:j1 - static const int CPCJointNeckPan = 1; // PRM:/r1/c1/c2-Joint2:j2 - static const int CPCJointNeckRoll = 2; // PRM:/r1/c1/c2/c3-Joint2:j3 - static const int CPCSensorPSD = 3; // PRM:/r1/c1/c2/c3/p1-Sensor:p1 - static const int CPCSensorHeadBackPressure = 4; // PRM:/r1/c1/c2/c3/f1-Sensor:f1 - static const int CPCSensorHeadFrontPressure = 5; // PRM:/r1/c1/c2/c3/f2-Sensor:f2 - static const int CPCSensorChinSwitch = 6; // PRM:/r1/c1/c2/c3/c4/s5-Sensor:s5 - static const int CPCJointLFRotator = 7; // PRM:/r2/c1-Joint2:j1 - static const int CPCJointLFElevator = 8; // PRM:/r2/c1/c2-Joint2:j2 - static const int CPCJointLFKnee = 9; // PRM:/r2/c1/c2/c3-Joint2:j3 - static const int CPCSensorLFPaw = 10; // PRM:/r2/c1/c2/c3/c4-Sensor:s4 - static const int CPCJointLHRotator = 11; // PRM:/r3/c1-Joint2:j1 - static const int CPCJointLHElevator = 12; // PRM:/r3/c1/c2-Joint2:j2 - static const int CPCJointLHKnee = 13; // PRM:/r3/c1/c2/c3-Joint2:j3 - static const int CPCSensorLHPaw = 14; // PRM:/r3/c1/c2/c3/c4-Sensor:s4 - static const int CPCJointRFRotator = 15; // PRM:/r4/c1-Joint2:j1 - static const int CPCJointRFElevator = 16; // PRM:/r4/c1/c2-Joint2:j2 - static const int CPCJointRFKnee = 17; // PRM:/r4/c1/c2/c3-Joint2:j3 - static const int CPCSensorRFPaw = 18; // PRM:/r4/c1/c2/c3/c4-Sensor:s4 - static const int CPCJointRHRotator = 19; // PRM:/r5/c1-Joint2:j1 - static const int CPCJointRHElevator = 20; // PRM:/r5/c1/c2-Joint2:j2 - static const int CPCJointRHKnee = 21; // PRM:/r5/c1/c2/c3-Joint2:j3 - static const int CPCSensorRHPaw = 22; // PRM:/r5/c1/c2/c3/c4-Sensor:s4 - static const int CPCSensorThermoSensor = 23; // PRM:/r6/t1-Sensor:t1 - static const int CPCSensorBackSwitch = 24; // PRM:/r6/s1-Sensor:s1 - static const int CPCSensorTailLeftSwitch = 25; // PRM:/r6/s2-Sensor:s2 (ERS-220 only) - static const int CPCSensorTailCenterSwitch = 26; // PRM:/r6/s3-Sensor:s3 (ERS-220 only) - static const int CPCSensorTailRightSwitch = 27; // PRM:/r6/s4-Sensor:s4 (ERS-220 only) - static const int CPCSensorAccelFB = 28; // PRM:/a1-Sensor:a1 - static const int CPCSensorAccelLR = 29; // PRM:/a2-Sensor:a2 - static const int CPCSensorAccelUD = 30; // PRM:/a3-Sensor:a3 + const int CPCJointNeckTilt = 0; // PRM:/r1/c1-Joint2:j1 + const int CPCJointNeckPan = 1; // PRM:/r1/c1/c2-Joint2:j2 + const int CPCJointNeckRoll = 2; // PRM:/r1/c1/c2/c3-Joint2:j3 + const int CPCSensorPSD = 3; // PRM:/r1/c1/c2/c3/p1-Sensor:p1 + const int CPCSensorHeadBackPressure = 4; // PRM:/r1/c1/c2/c3/f1-Sensor:f1 + const int CPCSensorHeadFrontPressure = 5; // PRM:/r1/c1/c2/c3/f2-Sensor:f2 + const int CPCSensorChinSwitch = 6; // PRM:/r1/c1/c2/c3/c4/s5-Sensor:s5 + const int CPCJointLFRotator = 7; // PRM:/r2/c1-Joint2:j1 + const int CPCJointLFElevator = 8; // PRM:/r2/c1/c2-Joint2:j2 + const int CPCJointLFKnee = 9; // PRM:/r2/c1/c2/c3-Joint2:j3 + const int CPCSensorLFPaw = 10; // PRM:/r2/c1/c2/c3/c4-Sensor:s4 + const int CPCJointLHRotator = 11; // PRM:/r3/c1-Joint2:j1 + const int CPCJointLHElevator = 12; // PRM:/r3/c1/c2-Joint2:j2 + const int CPCJointLHKnee = 13; // PRM:/r3/c1/c2/c3-Joint2:j3 + const int CPCSensorLHPaw = 14; // PRM:/r3/c1/c2/c3/c4-Sensor:s4 + const int CPCJointRFRotator = 15; // PRM:/r4/c1-Joint2:j1 + const int CPCJointRFElevator = 16; // PRM:/r4/c1/c2-Joint2:j2 + const int CPCJointRFKnee = 17; // PRM:/r4/c1/c2/c3-Joint2:j3 + const int CPCSensorRFPaw = 18; // PRM:/r4/c1/c2/c3/c4-Sensor:s4 + const int CPCJointRHRotator = 19; // PRM:/r5/c1-Joint2:j1 + const int CPCJointRHElevator = 20; // PRM:/r5/c1/c2-Joint2:j2 + const int CPCJointRHKnee = 21; // PRM:/r5/c1/c2/c3-Joint2:j3 + const int CPCSensorRHPaw = 22; // PRM:/r5/c1/c2/c3/c4-Sensor:s4 + const int CPCSensorThermoSensor = 23; // PRM:/r6/t1-Sensor:t1 + const int CPCSensorBackSwitch = 24; // PRM:/r6/s1-Sensor:s1 + const int CPCSensorTailLeftSwitch = 25; // PRM:/r6/s2-Sensor:s2 (ERS-220 only) + const int CPCSensorTailCenterSwitch = 26; // PRM:/r6/s3-Sensor:s3 (ERS-220 only) + const int CPCSensorTailRightSwitch = 27; // PRM:/r6/s4-Sensor:s4 (ERS-220 only) + const int CPCSensorAccelFB = 28; // PRM:/a1-Sensor:a1 + const int CPCSensorAccelLR = 29; // PRM:/a2-Sensor:a2 + const int CPCSensorAccelUD = 30; // PRM:/a3-Sensor:a3 //@} } @@ -594,11 +611,13 @@ * @brief Defines RobotInfo namespace for ERS-220 models, gives some information about the robot's capabilities, such as joint counts, offsets, names and PID values * @author Daishi MORI (Creator) * + * Mad props to Daishi MORI, the 220 master chief, for porting to the 220 ;) + * * $Author: ejt $ - * $Name: tekkotsu-3_0 $ - * $Revision: 1.27 $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.38 $ * $State: Exp $ - * $Date: 2006/10/04 02:41:51 $ + * $Date: 2007/11/09 19:01:14 $ */ #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ERS2xxInfo.h ./Shared/ERS2xxInfo.h --- ../Tekkotsu_3.0/Shared/ERS2xxInfo.h 2006-10-03 22:41:51.000000000 -0400 +++ ./Shared/ERS2xxInfo.h 2007-11-09 14:01:14.000000000 -0500 @@ -5,15 +5,17 @@ #ifndef INCLUDED_ERS2xxInfo_h #define INCLUDED_ERS2xxInfo_h -#include -#ifndef PLATFORM_APERIOS -typedef unsigned short word; //!< otherwise defined in Types.h -#else -#include -#endif +#include "CommonERSInfo.h" +#include "ERS210Info.h" +#include "ERS220Info.h" +#include -#include "CommonInfo.h" -using namespace RobotInfo; +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_ERS2xx) +# define TGT_HAS_LEDS 22 +# define TGT_HAS_BUTTONS 11 +# define TGT_HAS_IR_DISTANCE 1 +#endif //! Contains information about the ERS-2xx series of robot, such as number of joints, PID defaults, timing information, etc. /*! This is a compatability mode, which allows dual-booting @@ -25,7 +27,7 @@ // ROBOT CONFIGURATION // ******************************* - const char* const RobotName="ERS-2xx"; //!< the name of the model, to be used for logging and remote GUIs + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs const unsigned int FrameTime=8; //!< time between frames in the motion system (milliseconds) const unsigned int NumFrames=4; //!< the number of frames per buffer (don't forget also double buffered) @@ -36,6 +38,12 @@ //!Corresponds to entries in ERS2xxInfo::PrimitiveName, defined at the end of this file, these are the primary grouping /*!Right now all binary joints are slow, but perhaps this won't always be the case... hence the IsFast/Slow bitmasks to select which type, in order to be more general */ //!@name Output Types Information + const unsigned NumWheels = 0; //!< no wheels, just legs + + const unsigned JointsPerArm = 0; //!< no arms, just legs + const unsigned NumArms = 0; //!< no arms, just legs + const unsigned NumArmJoints = JointsPerArm*NumArms; + const unsigned JointsPerLeg = 3; //!< The number of joints per leg const unsigned NumLegs = 4; //!< The number of legs const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs @@ -48,7 +56,7 @@ const unsigned NumLEDs = 22; //!< The number of LEDs which can be controlled const unsigned NumPIDJoints = NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints; //!< The number of joints which use PID motion - everything except ears - const unsigned NumBinJoints = NumEarJoints; //!< The number of binary joints - just the ears + const unsigned NumBinJoints = NumEarJoints; //!< The number of binary joints - just the ears (Aperios only) const unsigned NumOutputs = NumPIDJoints + NumBinJoints + NumLEDs; //!< the total number of outputs const unsigned NumReferenceFrames = NumOutputs + 1 + NumLegs + 1 + 1; //!< for the base, paw, camera, and IR sensor reference frames @@ -83,56 +91,9 @@ // for binary joints false, false }; - - //! we need this so you can tell programmatically which joints are "real" and which are "fake" in compatability mode - const bool IsRealERS210[NumOutputs] = { - // for PID joints - true, true, true, //legs - true, true, true, - true, true, true, - true, true, true, - true, true, true, //head - true, true, //tail - true, //mouth - // for LEDs - true, true, true, // face left side LEDs x3 - true, true, true, // face right side LEDs x3 - true, // head mode LED x1 - false, false, false, // back left multi LEDs x3 - false, false, false, // back right multi LEDs x3 - false, false, false, // tail LEDs x3 - false, false, false, // face front LEDs x3 - false, // retractable head light x1 - true, true, // tail red/blue from 210 - // for binary joints - true, true - }; - - //! we need this so you can tell programmatically which joints are "real" and which are "fake" in compatability mode - const bool IsRealERS220[NumOutputs] = { - // for PID joints - true, true, true, //legs - true, true, true, - true, true, true, - true, true, true, - true, true, true, //head - false, false, //tail - false, //mouth - // for LEDs - true, true, true, // face left side LEDs x3 - true, true, true, // face right side LEDs x3 - true, // head mode LED x1 - true, true, true, // back left multi LEDs x3 - true, true, true, // back right multi LEDs x3 - true, true, true, // tail LEDs x3 - true, true, true, // face front LEDs x3 - true, // retractable head light x1 - false, false, // tail red/blue from 210 - // for binary joints - false, false - }; - - + + + // ******************************* // OUTPUT OFFSETS // ******************************* @@ -156,6 +117,29 @@ const unsigned CameraFrameOffset = PawFrameOffset+NumLegs; //!< Use with kinematics to refer to camera reference frame const unsigned IRFrameOffset = CameraFrameOffset+1; //!< Use with kinematics to refer to infrared (distance) sensor reference frame + //! the ordering of legs + enum LegOrder_t { + LFrLegOrder = 0, //!< left front leg + RFrLegOrder, //!< right front leg + LBkLegOrder, //!< left back leg + RBkLegOrder //!< right back leg + }; + + //! The offsets within appendages (the legs) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the head's TPROffset_t's) + enum REKOffset_t { + RotatorOffset=0, //!< moves leg forward or backward along body + ElevatorOffset, //!< moves leg toward or away from body + KneeOffset //!< moves knee + }; + + //! The offsets of appendages with tilt (elevation), pan (heading), and roll or nod joints (i.e. head) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the leg's REKOffset_t's) + enum TPROffset_t { + TiltOffset = 0, //!< tilt/elevation (vertical) + PanOffset, //!< pan/heading (horizontal) + RollOffset, //!< roll (rotational) + NodOffset=RollOffset //!< nod (second tilt) + }; + //! The offsets of the individual legs enum LegOffset_t { LFrLegOffset = LegOffset+LFrLegOrder*JointsPerLeg, //!< beginning of left front leg @@ -275,13 +259,13 @@ //! selects all of the leds const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; //@} - - + + + // ******************************* // INPUT OFFSETS // ******************************* - //! The order in which inputs should be stored //!@name Input Offsets @@ -291,7 +275,7 @@ * Note that the chest (power) button is not a normal button. It kills * power to the motors at a hardware level, and isn't sensed in the * normal way. If you want to know when it is pressed (and you are - * about to shut down) see PowerSourceID::PauseSID. + * about to shut down) see PowerSrcID::PauseSID. * * @see WorldState::buttons @see ButtonSourceID_t */ enum ButtonOffset_t { @@ -342,46 +326,44 @@ //@} - //! The length of the strings used for each of the outputs in outputNames (doesn't include null term) - const unsigned outputNameLen = 9; - //! A name of uniform length for referring to joints - handy for posture files, etc. + //! Names for each of the outputs const char* const outputNames[NumOutputs] = { "LFr:rotor", "LFr:elvtr", - "LFr:knee~", + "LFr:knee", "RFr:rotor", "RFr:elvtr", - "RFr:knee~", + "RFr:knee", "LBk:rotor", "LBk:elvtr", - "LBk:knee~", + "LBk:knee", "RBk:rotor", "RBk:elvtr", - "RBk:knee~", + "RBk:knee", "NECK:tilt", - "NECK:pan~", + "NECK:pan", "NECK:roll", "TAIL:tilt", - "TAIL:pan~", + "TAIL:pan", - "MOUTH~~~~", + "MOUTH", - "LED:botL~", - "LED:botR~", - "LED:midL~", - "LED:midR~", - "LED:topL~", - "LED:topR~", + "LED:botL", + "LED:botR", + "LED:midL", + "LED:midR", + "LED:topL", + "LED:topR", "LED:topBr", - "LED:bkL1~", // "LED:tlBlu" of ERS-210 - "LED:bkL2~", // "LED:tlRed" of ERS-210 - "LED:bkL3~", - "LED:bkR3~", - "LED:bkR2~", - "LED:bkR1~", + "LED:bkL1", // "LED:tlBlu" of ERS-210 + "LED:bkL2", // "LED:tlRed" of ERS-210 + "LED:bkL3", + "LED:bkR3", + "LED:bkR2", + "LED:bkR1", "LED:tailL", "LED:tailC", "LED:tailR", @@ -393,11 +375,54 @@ "LED:tlRed", "LED:tlBlu", - "EAR:left~", + "EAR:left", "EAR:right" }; - + + //! provides polymorphic robot capability detection/mapping + class ERS2xxCapabilities : public Capabilities { + public: + //! constructor + ERS2xxCapabilities() + : Capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs) + { + // ers-7 button alias + buttonToIndex["HeadBut"]=HeadButOffset; +#ifdef TGT_ERS2xx + if(detectModel() == ERS210Info::TargetName) { + fakeOutputs.insert(BackLeft1LEDOffset); + fakeOutputs.insert(BackLeft2LEDOffset); + fakeOutputs.insert(BackLeft3LEDOffset); + fakeOutputs.insert(BackRight3LEDOffset); + fakeOutputs.insert(BackRight2LEDOffset); + fakeOutputs.insert(BackRight1LEDOffset); + fakeOutputs.insert(TailLeftLEDOffset); + fakeOutputs.insert(TailCenterLEDOffset); + fakeOutputs.insert(TailRightLEDOffset); + fakeOutputs.insert(FaceFrontBLEDOffset); + fakeOutputs.insert(FaceFrontALEDOffset); + fakeOutputs.insert(FaceFrontCLEDOffset); + fakeOutputs.insert(RetractableHeadLEDOffset); + } else if(detectModel() == ERS220Info::TargetName) { + for(unsigned int i=TailOffset; i -#ifndef PLATFORM_APERIOS -typedef unsigned short word; //!< otherwise defined in Types.h -#else -#include -#endif +#include "Shared/CommonERSInfo.h" -#include "CommonInfo.h" -using namespace RobotInfo; +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_ERS7) +# define TGT_HAS_LEDS 27 +# define TGT_HAS_BUTTONS 10 +# define TGT_HAS_IR_DISTANCE 3 +#endif //! Contains information about the ERS-7 Robot, such as number of joints, PID defaults, timing information, etc. /*! @@ -29,7 +28,7 @@ For most joints, the positive direction is "up", and the 0 position yields a forward looking, fully extended standing posture. -- {L,R}{FrBk}LegOffset - #NumLegs combinations, each with #JointsPerLeg items, add #REKOffset_t; see also #LegOffset_t +- {L,R}{FrBk}LegOffset - #NumLegs combinations, each with #JointsPerLeg items, add REKOffset_t; see also LegOffset_t - + #RotatorOffset: positive moves "out", away from body - + #ElevatorOffset: positive moves up, away from body - + #KneeOffset: positive bends knee (slight negative possible) @@ -51,7 +50,7 @@ - BinJointOffset - #NumBinJoints items, solenoids, such as the ears (if any) which flip between two positions - #NumOutputs - total number of outputs available -LEDs are often handled in groups to display patterns. Some functions take an #LEDBitMask_t +LEDs are often handled in groups to display patterns. Some functions take an LEDBitMask_t parameter, which allows you to specify a set of several LEDs in a single parameter. For any given LED offset @c fooLEDOffset, the corresponding bitmask constant is @c fooLEDMask. Alternatively, you could calculate the bitmask of @c fooLEDOffset by 1<<(fooLEDOffset-LEDOffset). @@ -64,7 +63,7 @@ // ROBOT CONFIGURATION // ******************************* - const char* const RobotName="ERS-7"; //!< the name of the model, to be used for logging and remote GUIs + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs const unsigned int FrameTime=8; //!< time between frames in the motion system (milliseconds) const unsigned int NumFrames=4; //!< the number of frames per buffer (don't forget also double buffered) @@ -75,6 +74,12 @@ //!Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file, these are the primary grouping /*!Right now all binary joints are slow, but perhaps this won't always be the case... hence the IsFast/Slow bitmasks to select which type, in order to be more general */ //!@name Output Types Information + const unsigned NumWheels = 0; //!< no wheels, just legs + + const unsigned JointsPerArm = 0; //!< no arms, just legs + const unsigned NumArms = 0; //!< no arms, just legs + const unsigned NumArmJoints = JointsPerArm*NumArms; + const unsigned JointsPerLeg = 3; //!< The number of joints per leg const unsigned NumLegs = 4; //!< The number of legs const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs @@ -106,15 +111,10 @@ true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true, //leds true,true //ears }; - //! we need this so you can tell programmatically which joints are "real" and which are "fake" in a compatability mode - /*! @hideinitializer */ - const bool IsRealERS7[NumOutputs] = { - true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true, //PID joints - true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,true,false, //leds - true,true //ears - }; //@} - + + + // ******************************* // OUTPUT OFFSETS // ******************************* @@ -141,7 +141,29 @@ const unsigned FarIRFrameOffset = NearIRFrameOffset+1; //!< Use with kinematics to refer to long-range infrared (distance) sensor reference frame const unsigned ChestIRFrameOffset = FarIRFrameOffset+1; //!< Use with kinematics to refer to chest-mounted infrared (distance) sensor reference frame - + //! the ordering of legs + enum LegOrder_t { + LFrLegOrder = 0, //!< left front leg + RFrLegOrder, //!< right front leg + LBkLegOrder, //!< left back leg + RBkLegOrder //!< right back leg + }; + + //! The offsets within appendages (the legs) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the head's TPROffset_t's) + enum REKOffset_t { + RotatorOffset=0, //!< moves leg forward or backward along body + ElevatorOffset, //!< moves leg toward or away from body + KneeOffset //!< moves knee + }; + + //! The offsets of appendages with tilt (elevation), pan (heading), and roll or nod joints (i.e. head) Note that the ordering matches the actual physical ordering of joints on the appendage (and not that of the leg's REKOffset_t's) + enum TPROffset_t { + TiltOffset = 0, //!< tilt/elevation (vertical) + PanOffset, //!< pan/heading (horizontal) + RollOffset, //!< roll (rotational) + NodOffset=RollOffset //!< nod (second tilt) + }; + //! The offsets of the individual legs, add #REKOffset_t value to access specific joint /*! @hideinitializer */ enum LegOffset_t { @@ -233,8 +255,9 @@ //! selects all of the leds const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; //@} - - + + + // ******************************* // INPUT OFFSETS // ******************************* @@ -249,7 +272,7 @@ * Note that the chest (power) button is not a normal button. It kills * power to the motors at a hardware level, and isn't sensed in the * normal way. If you want to know when it is pressed (and you are - * about to shut down) see PowerSourceID::PauseSID. + * about to shut down) see PowerSrcID::PauseSID. * * @see WorldState::buttons @see ButtonSourceID_t * @hideinitializer */ @@ -280,6 +303,7 @@ /*! @see WorldState::sensors[] */ enum SensorOffset_t { NearIRDistOffset = 0, //!< in millimeters, ranges from 50 to 500 + IRDistOffset=NearIRDistOffset, //!< alias for ERS-2xx's solitary range finder FarIRDistOffset, //!< in millimeters, ranges from 200 to 1500 ChestIRDistOffset, //!< in millimeters, ranges from 100 to 900 BAccelOffset, //!< backward acceleration, in @f$m/s^2@f$, negative if sitting on butt (positive for faceplant) @@ -302,20 +326,18 @@ //@} - //! The length of the strings used for each of the outputs in outputNames (doesn't include null term) - const unsigned outputNameLen = 9; - //! A name of uniform length for referring to joints - handy for posture files, etc. + //! Names for each of the outputs const char* const outputNames[NumOutputs] = { - "LFr:rotor","LFr:elvtr","LFr:knee~", - "RFr:rotor","RFr:elvtr","RFr:knee~", - "LBk:rotor","LBk:elvtr","LBk:knee~", - "RBk:rotor","RBk:elvtr","RBk:knee~", + "LFr:rotor","LFr:elvtr","LFr:knee", + "RFr:rotor","RFr:elvtr","RFr:knee", + "LBk:rotor","LBk:elvtr","LBk:knee", + "RBk:rotor","RBk:elvtr","RBk:knee", - "NECK:tilt","NECK:pan~","NECK:nod~", + "NECK:tilt","NECK:pan","NECK:nod", - "TAIL:tilt", "TAIL:pan~", + "TAIL:tilt", "TAIL:pan", - "MOUTH~~~~", + "MOUTH", "LED:headC","LED:headW", "LED:modeR","LED:modeG", @@ -327,10 +349,44 @@ "LED:bkRrC","LED:bkRrW", "LED:ABmod", - "EAR:left~","EAR:right" + "EAR:left","EAR:right" }; - + + //! provides polymorphic robot capability detection/mapping + class ERS7Capabilities : public Capabilities { + public: + //! constructor + ERS7Capabilities() + : Capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs) + { + // 2xx button aliases + buttonToIndex["HeadFrBut"]=HeadFrButOffset; // aliased to HeadButOffset + buttonToIndex["BackBut"]=BackButOffset; //aliased to MiddleBackButOffset + // 210 led aliases + outputToIndex["LED:botL"]=BotLLEDOffset; // aliased to face panel... + outputToIndex["LED:botR"]=BotRLEDOffset; + outputToIndex["LED:midL"]=MidLLEDOffset; + outputToIndex["LED:midR"]=MidRLEDOffset; + outputToIndex["LED:topL"]=TopLLEDOffset; + outputToIndex["LED:topR"]=TopRLEDOffset; + outputToIndex["LED:topBr"]=TopBrLEDOffset; + outputToIndex["LED:tlRed"]=TlRedLEDOffset; // aliased to the red back light + outputToIndex["LED:tlBlu"]=TlBluLEDOffset; // aliased to the blue back light + // 220 led aliases + outputToIndex["LED:bkL1"]=TlBluLEDOffset; // aliased to the blue back light + outputToIndex["LED:bkL2"]=TlRedLEDOffset; // aliased to the red back light + // 2xx sensor aliases + sensorToIndex["IRDist"]=IRDistOffset; // aliased to the near IR sensor + + // the AB switch is a meta-output, don't tell Aperios about it + fakeOutputs.insert(LEDABModeOffset); + } + }; + //! allocation declared in RobotInfo.cc + extern ERS7Capabilities capabilities; + + //! the joint identifier strings used to refer to specific joints in OPEN-R (but not needed for others) /*!@showinitializer * The offset consts defined in this file correspond to this table and will make life easier @@ -475,7 +531,7 @@ #define __RI_RAD_FLAG #endif - //! This table holds the software limits of each of the outputs, first index is the output offset, second index is #MinMaxRange_t (i.e. #MinRange or #MaxRange) + //! This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) const double outputRanges[NumOutputs][2] = { { RAD(-115),RAD(130) },{ RAD(-10),RAD(88) },{ RAD(-25),RAD(122) }, //left front REK @@ -497,8 +553,8 @@ {0,1},{0,1} //ears }; - //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is #MinMaxRange_t (i.e. #MinRange or #MaxRange) - /*! Same as #outputLimits, don't know actual values because they were never specified by Sony */ + //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + /*! Same as #outputRanges, don't know actual values because they were never specified by Sony */ const double mechanicalLimits[NumOutputs][2] = { { RAD(-115),RAD(130) },{ RAD(-10),RAD(88) },{ RAD(-25),RAD(122) }, //left front REK @@ -528,40 +584,40 @@ /*! @name CPC IDs * Values defined by OPEN-R, used to interface with lower level OPEN-R code to read sensors - values @e don't correspond to order of ERS7Info::PrimitiveName */ - static const int CPCJointMouth = 0; //!< Mouth - static const int CPCSwitchChin = 1; //!< Chin sensor - static const int CPCJointNeckNod = 2; //!< Neck tilt2 - static const int CPCSensorHead = 3; //!< Head sensor - static const int CPCSensorNearPSD = 4; //!< Head distance sensor(near) - static const int CPCSensorFarPSD = 5; //!< Head distance sensor(far) - static const int CPCJointNeckPan = 6; //!< Neck pan - static const int CPCJointNeckTilt = 7; //!< Neck tilt1 - static const int CPCSwitchLFPaw = 8; //!< Left fore leg paw sensor - static const int CPCJointLFKnee = 9; //!< Left fore legJ3 - static const int CPCJointLFElevator = 10; //!< Left fore legJ2 - static const int CPCJointLFRotator = 11; //!< Left fore legJ1 - static const int CPCSwitchLHPaw = 12; //!< Left hind leg paw sensor - static const int CPCJointLHKnee = 13; //!< Left hind legJ3 - static const int CPCJointLHElevator = 14; //!< Left hind legJ2 - static const int CPCJointLHRotator = 15; //!< Left hind legJ1 - static const int CPCSwitchRFPaw = 16; //!< Right fore leg paw sensor - static const int CPCJointRFKnee = 17; //!< Right fore legJ3 - static const int CPCJointRFElevator = 18; //!< Right fore legJ2 - static const int CPCJointRFRotator = 19; //!< Right fore legJ1 - static const int CPCSwitchRHPaw = 20; //!< Right hind leg paw sensor - static const int CPCJointRHKnee = 21; //!< Right hind legJ3 - static const int CPCJointRHElevator = 22; //!< Right hind legJ2 - static const int CPCJointRHRotator = 23; //!< Right hind legJ1 - static const int CPCJointTailTilt = 24; //!< Tail tilt - static const int CPCJointTailPan = 25; //!< Tail pan - static const int CPCSensorAccelFB = 26; //!< Acceleration sensor(front-back) - static const int CPCSensorAccelLR = 27; //!< Acceleration sensor(right-left) - static const int CPCSensorAccelUD = 28; //!< Acceleration sensor(up-down) - static const int CPCSensorChestPSD = 29; //!< Chest distance sensor - static const int CPCSwitchWireless = 30; //!< Wireless LAN switch - static const int CPCSensorBackRear = 31; //!< Back sensor(rear) - static const int CPCSensorBackMiddle= 32; //!< Back sensor(middle) - static const int CPCSensorBackFront = 33; //!< Back sensor(front) + const int CPCJointMouth = 0; //!< Mouth + const int CPCSwitchChin = 1; //!< Chin sensor + const int CPCJointNeckNod = 2; //!< Neck tilt2 + const int CPCSensorHead = 3; //!< Head sensor + const int CPCSensorNearPSD = 4; //!< Head distance sensor(near) + const int CPCSensorFarPSD = 5; //!< Head distance sensor(far) + const int CPCJointNeckPan = 6; //!< Neck pan + const int CPCJointNeckTilt = 7; //!< Neck tilt1 + const int CPCSwitchLFPaw = 8; //!< Left fore leg paw sensor + const int CPCJointLFKnee = 9; //!< Left fore legJ3 + const int CPCJointLFElevator = 10; //!< Left fore legJ2 + const int CPCJointLFRotator = 11; //!< Left fore legJ1 + const int CPCSwitchLHPaw = 12; //!< Left hind leg paw sensor + const int CPCJointLHKnee = 13; //!< Left hind legJ3 + const int CPCJointLHElevator = 14; //!< Left hind legJ2 + const int CPCJointLHRotator = 15; //!< Left hind legJ1 + const int CPCSwitchRFPaw = 16; //!< Right fore leg paw sensor + const int CPCJointRFKnee = 17; //!< Right fore legJ3 + const int CPCJointRFElevator = 18; //!< Right fore legJ2 + const int CPCJointRFRotator = 19; //!< Right fore legJ1 + const int CPCSwitchRHPaw = 20; //!< Right hind leg paw sensor + const int CPCJointRHKnee = 21; //!< Right hind legJ3 + const int CPCJointRHElevator = 22; //!< Right hind legJ2 + const int CPCJointRHRotator = 23; //!< Right hind legJ1 + const int CPCJointTailTilt = 24; //!< Tail tilt + const int CPCJointTailPan = 25; //!< Tail pan + const int CPCSensorAccelFB = 26; //!< Acceleration sensor(front-back) + const int CPCSensorAccelLR = 27; //!< Acceleration sensor(right-left) + const int CPCSensorAccelUD = 28; //!< Acceleration sensor(up-down) + const int CPCSensorChestPSD = 29; //!< Chest distance sensor + const int CPCSwitchWireless = 30; //!< Wireless LAN switch + const int CPCSensorBackRear = 31; //!< Back sensor(rear) + const int CPCSensorBackMiddle= 32; //!< Back sensor(middle) + const int CPCSensorBackFront = 33; //!< Back sensor(front) //@} } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Factories.h ./Shared/Factories.h --- ../Tekkotsu_3.0/Shared/Factories.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/Factories.h 2007-11-09 13:08:29.000000000 -0500 @@ -0,0 +1,173 @@ +//-*-c++-*- +#ifndef INCLUDED_Factories_h_ +#define INCLUDED_Factories_h_ + +//! A factory interface which doesn't actually allow anything to be produced (for completeness, like 'NULL') +template +struct FactoryInvalidT { + //! concrete class for not doing anything + template struct Factory : public FactoryInvalidT {}; +}; +//! specialization: all invalid factories are the same... +typedef FactoryInvalidT<> FactoryInvalid; + +// Alternate implementation of FactoryInvalid just for reference: +// (I prefer the one used above though, because it provides a (unused) template for the base class like the other factory types) +#if 0 +//! A factory interface which doesn't actually allow anything to be produced (for completeness, like 'NULL') +struct FactoryInvalid { + //! concrete class for not doing anything (prototype here, "implementation" follows) + template struct Factory; +}; +//! implementation of concrete class for not doing anything +template struct FactoryInvalid::Factory : public FactoryInvalid {}; +#endif + + + +//! Untyped base class for factories which don't require any arguments to construct their product, see Factories.h file notes (see Factory0Arg) +/*! Note that this does not mean the product has to be constructed without arguments... see Factory0Arg1Static for example. */ +struct Factory0ArgBase { + //! functor interface for constructing the product + virtual void* construct()=0; + //! explicit destructor to avoid warnings regarding virtual functions without virtual destructor + virtual ~Factory0ArgBase() {} +}; +//! Typed base class for factories which don't require any arguments to construct their product, see Factories.h file notes +/*! Note that this does not mean the product has to be constructed without arguments... see Factory0Arg1Static for example. */ +template +struct Factory0Arg : public Factory0ArgBase { + //! functor interface for constructing the product + virtual Base* operator()()=0; + virtual void* construct() { return operator()(); } + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory0Arg { + virtual Base* operator()() { return new T; } //!< functor for constructing the product + }; +}; +//! This class produces objects based on a constant specified as a template parameter +/*! You could also implement this by adding a member field to the factory and passing that to + * the target constuctor instead of the non-type template parameter (which has some restrictions). + * See Factory0Arg1Member */ +template +struct Factory0Arg1Static : public Factory0Arg { + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory0Arg1Static { + virtual Base* operator()() { return new T(s1); } //!< functor for constructing the product + }; +}; +//! This class produces objects based on a constant specified as a factory member +/*! You could also implement this by using a non-type template parameter argument, see Factory0Arg1Static. */ +template +struct Factory0Arg1Member : public Factory0Arg { + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory0Arg1Member { + Factory() : m1() {} //!< use default constructor for #m1 + explicit Factory(const M1& im1) : m1(im1) {} //!< use specified value to initalize #m1 + M1 m1; //!< storage for the product's constructor value + virtual Base* operator()() { return new T(m1); } //!< functor for constructing the product + }; +}; +//! This class produces objects based on constant values specified as a template parameters +/*! You could also implement this by adding member fields to the factory and passing that to + * the target constuctor instead of the non-type template parameter (which has some restrictions). + * See Factory0Arg1Member for an example how this is done. */ +template +struct Factory0Arg2Static : public Factory0Arg { + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory0Arg2Static { + virtual Base* operator()() { return new T(s1,s2); } //!< functor for constructing the product + }; +}; + + + +//! Untyped base class for factories which require a single argument to construct their product, which is passed to the concrete Factory's functor (see Factory1Arg) +/*! Note that this does not mean the product can only be constructed with only one argument... see Factory1Arg1Static for example. */ +template +struct Factory1ArgBase { + //! functor interface for constructing the product + virtual void* construct(const A1& a1)=0; + //! explicit destructor to avoid warnings regarding virtual functions without virtual destructor + virtual ~Factory1ArgBase() {} +}; +//! Typed base class for factories which require a single argument to construct their product, which is passed to the concrete Factory's functor +/*! Note that this does not mean the product can only be constructed with only one argument... see Factory1Arg1Static for example. */ +template +struct Factory1Arg : public Factory1ArgBase { + //! functor interface for constructing the product + virtual Base* operator()(const A1& a1)=0; + virtual void* construct(const A1& a1) { return operator()(a1); } + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory1Arg { + virtual Base* operator()(const A1& a1) { return new T(a1); } //!< functor for constructing the product + }; +}; +//! This class produces objects based on a functor argument and a constant specified as a template parameter +/*! You could also implement this by adding a member field to the factory and passing that to + * the target constuctor instead of the non-type template parameter (which has some restrictions). + * See Factory0Arg1Member for an example how this is done. */ +template +struct Factory1Arg1Static : public Factory1Arg { + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory1Arg1Static { + virtual Base* operator()(const A1& a1) { return new T(a1,s1); } //!< functor for constructing the product + }; +}; +//! This class produces objects based on a constant specified as a template parameter and a constructor argument +/*! You could also implement this by adding a member field to the factory and passing that to + * the target constuctor instead of the non-type template parameter (which has some restrictions). + * See Factory0Arg1Member for an example how this is done. */ +template +struct Factory1Static1Arg : public Factory1Arg { + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory1Static1Arg { + virtual Base* operator()(const A1& a1) { return new T(s1,a1); } //!< functor for constructing the product + }; +}; + + + +//! Base class for factories which can create products more than one way, in this case via default constructor (0 arguments) or 1-argument constructor +/*! We use multiple inheritance to combine the Factory0Arg and Factory1Arg base classes. Keep in mind however, + * that all product subtypes must support all constr*/ +template +struct Factory0_1Arg : public virtual Factory0Arg, public virtual Factory1Arg { + using Factory0Arg::operator(); + using Factory1Arg::operator(); + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory0_1Arg { + virtual Base* operator()() { return new T; } //!< 0 argument functor for constructing the product + virtual Base* operator()(const A1& a1) { return new T(a1); } //!< 1 argument functor for constructing the product + }; +}; +//! Variant of Factory0_1Arg, this uses a constant non-type template parameter to specify a default value to use when the 0-argument functor is called... +/*! Thus, we only ever call the product's 1 argument constructor, but provide more options in the factory interface... */ +template +struct Factory1Static_1Arg : public Factory0_1Arg { + //! concrete class for constructing products of a specified subtype of Base + template struct Factory : public Factory1Static_1Arg { + virtual Base* operator()() { return new T(s1); } //!< 0 argument functor for constructing the product using the static value + virtual Base* operator()(const A1& a1) { return new T(a1); } //!< 1 argument functor for constructing the product + }; +}; + +/*! @file + * @brief Defines a variety of factory templates which can be used with FamilyFactory. + * This is not (and couldn't be) an exhaustive list of Factory configurations. It provides some commonly used + * configurations, and should give you some examples and ideas how to create your own for more complex cases. + * + * Factory0Arg and Factory1Arg allow you to instantiate classes with 0 or 1 arguments respectively. Subclasses of + * these interfaces allow you to specify additional parameters to the product's constructor call. Factory0_1Arg + * shows how to combine Factory configurations so you can have multiple constructor options at runtime. + * + * @author ejt (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.2 $ + * $State: Exp $ + * $Date: 2007/11/09 18:08:29 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Factory.h ./Shared/Factory.h --- ../Tekkotsu_3.0/Shared/Factory.h 2005-07-25 23:11:20.000000000 -0400 +++ ./Shared/Factory.h 2007-05-21 13:02:37.000000000 -0400 @@ -1,5 +1,5 @@ //-*-c++-*- -#ifndef INCLUDED_Factory_h_ +#if 0 #define INCLUDED_Factory_h_ //! Base class for Factory templated subclasses diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/FamilyFactory.h ./Shared/FamilyFactory.h --- ../Tekkotsu_3.0/Shared/FamilyFactory.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/FamilyFactory.h 2007-11-10 17:58:09.000000000 -0500 @@ -0,0 +1,128 @@ +//-*-c++-*- +#ifndef INCLUDED_FamilyFactory_h_ +#define INCLUDED_FamilyFactory_h_ + +#include "Factories.h" +#include +#include +#include +#include + +//! A class which can track a set of subclass types (with shared base class FamilyT), generating new instances on demand based on some form of identifier (the NameT template parameter) +/*! Register your class via registerType() or registerFactory(), and then instantiate it later + * with a call to create(). Note that you have a variety of options to control how the product + * is constructed via your choice of the FactoryBaseT and FactoryT template parameters. + * + * The FactoryBaseT defines the interface, exposing available factory functor calls which return + * the shared base class. The FactoryT is a template template parameter which indicates + * the factory to be created for each call to registerType(). This should take the type to be + * produced as its template parameter, and implement the interface expected by FactoryBaseT. + * + * By default, FamilyFactory looks for a type named 'Factory' within the FactoryBaseT namespace. + * This parameter would be ignored if you only ever call registerFactory, and pass your own factory + * instances. + * + * A cute way to automatically trigger type registration is to define a static member of your class, + * and then call registerType() or registerFactory() for its initialization. + * + * See Factories.h for some basic factory types. */ +template, template class FactoryT=FactoryBaseT::template Factory> +class FamilyFactory { +public: + //! allows indirect access to the product family type + typedef FamilyT FamilyType; + //! allows indirect access to the product class name type + typedef NameT NameType; + //! allows indirect access to the factory base class + typedef FactoryBaseT FactoryBaseType; + //! allows indirect access to create factory classes + template struct FactoryType : FactoryT {}; + + //! default constructor + FamilyFactory() : factories() {} + + //! destructor + virtual ~FamilyFactory() { + for(typename factories_t::iterator it=factories.begin(); it!=factories.end(); ++it) + delete it->second; + factories.clear(); + } + + //! clears @a types and fills in the currently registered type identifiers + void getTypeNames(std::set& types) const; + + //! returns the number of currently registered type identifiers + unsigned int getNumTypes() const { return factories.size(); } + + //! creates a factory for the specified type from FactoryT and registers it as @a type + template const NameT& registerType(const NameT& type) { return registerFactory(type,new FactoryT); } + + //! registers the specified factory for producing objects known by @a type; FamilyFactory assumes responsibilty for deallocation of @a f + const NameT& registerFactory(const NameT& type, FactoryBaseT* f); + + //! requests a new instance of the specified @a type be created, without passing any arguments to the factory + /*! Note that the factory interface chosen by FactoryBaseT may not actually provide such a call! */ + FamilyT* create(const NameT& type) const { FactoryBaseT * f=lookupFactory(type); return f ? (*f)() : NULL; } + + //! requests a new instance of the specified @a type be created, passing a single argument to the factory + /*! Note that the factory interface chosen by FactoryBaseT may not actually provide such a call! */ + template + FamilyT* create(const NameT& type, const A1& a1) const { FactoryBaseT * f=lookupFactory(type); return f ? (*f)(a1) : NULL; } + + //! requests a new instance of the specified @a type be created, passing two arguments to the factory + /*! Note that the factory interface chosen by FactoryBaseT may not actually provide such a call! */ + template + FamilyT* create(const NameT& type, const A1& a1, const A2& a2) const { FactoryBaseT * f=lookupFactory(type); return f ? (*f)(a1,a2) : NULL; } + + //! requests a new instance of the specified @a type be created, passing three arguments to the factory + /*! Note that the factory interface chosen by FactoryBaseT may not actually provide such a call! */ + template + FamilyT* create(const NameT& type, const A1& a1, const A2& a2, const A3& a3) const { FactoryBaseT * f=lookupFactory(type); return f ? (*f)(a1,a2,a3) : NULL; } + +protected: + //! utility function to see if @a type has been registered and return it, or NULL if not found + FactoryBaseT* lookupFactory(const NameT& type) const; + + //! type of #factories + typedef std::map factories_t; + factories_t factories; //!< storage for type identifier to factory mapping +}; + +template class FactoryT> +void FamilyFactory::getTypeNames(std::set& types) const { + types.clear(); + for(typename factories_t::const_iterator it=factories.begin(); it!=factories.end(); ++it) + types.insert(it->first); +} + +template class FactoryT> +const NameT& FamilyFactory::registerFactory(const NameT& type, FactoryBaseT* f) { + typename factories_t::const_iterator it=factories.find(type); + if(it!=factories.end()) { + std::cerr << "WARNING: Type " << type << " was already registered! Overwriting previous..." << std::endl; + delete it->second; + } + factories[type]=f; + return type; +} + +template class FactoryT> +FactoryBaseT* FamilyFactory::lookupFactory(const NameT& type) const { + typename factories_t::const_iterator it=factories.find(type); + if(it==factories.end()) + return NULL; + return it->second; +} + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.3 $ + * $State: Exp $ + * $Date: 2007/11/10 22:58:09 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ImageUtil.cc ./Shared/ImageUtil.cc --- ../Tekkotsu_3.0/Shared/ImageUtil.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/ImageUtil.cc 2007-11-13 21:29:03.000000000 -0500 @@ -0,0 +1,665 @@ +#include "ImageUtil.h" + +#include +#include +#include +#include +#include "Shared/jpeg-6b/jpeg_mem_dest.h" +#include "Shared/jpeg-6b/jpeg_mem_src.h" +#include "Shared/jpeg-6b/jpeg_istream_src.h" +#include "Shared/Config.h" +#ifndef LOADFILE_NO_MMAP +# include +# include +# include +# include +# include +#endif + +#include +extern "C" { +#include +} +using namespace std; + +namespace image_util { + + bool loadFile(const std::string& file, char*& buf, size_t& size) { + struct stat statbuf; + if(stat(file.c_str(),&statbuf)!=0) { + perror("image_util::loadFile"); + return false; + } +#ifdef LOADFILE_NO_MMAP + FILE * infile= fopen(file.c_str(), "rb"); + if (infile==NULL) { + int err=errno; + cerr << "image_util::loadFile(): Could not open '" << file << "' (fopen:" << strerror(err) << ")" << endl; + return false; + } + char* inbuf=new char[statbuf.st_size]; + if(!fread(inbuf,statbuf.st_size,1,infile)) { + int err=errno; + cerr << "image_util::loadFile(): Could not load '" << file << "' (fread:" << strerror(err) << ")" << endl; + if(fclose(infile)) + perror("Warning: image_util::loadFile(), on fclose"); + delete [] inbuf; + return false; + } + if(fclose(infile)) + perror("Warning: image_util::loadFile(), on fclose"); +#else /*use mmap to load file into memory*/ + int infd=open(file.c_str(),O_RDONLY,0666); + if(infd<0) { + int err=errno; + cerr << "image_util::loadFile(): Could not open '" << file << "' (open:" << strerror(err) << ")" << endl; + return false; + } + void* inbuf=mmap(NULL,statbuf.st_size,PROT_READ,MAP_FILE|MAP_PRIVATE,infd,0); + if (inbuf == MAP_FAILED) { /* MAP_FAILED generally defined as ((void*)-1) */ + int err=errno; + cerr << "image_util::loadFile(): Could not load '" << file << "' (mmap:" << strerror(err) << ")" << endl; + if(close(infd)<0) + perror("Warning: image_util::loadFile(), on closing temporary file descriptor from open"); + return false; + } + if(close(infd)<0) + perror("Warning: image_util::loadFile(), on closing temporary file descriptor from open"); +#endif + buf=static_cast(inbuf); + size=statbuf.st_size; + return true; + } + +#ifdef LOADFILE_NO_MMAP + void releaseFile(char* buf, size_t /*size*/) { + delete [] buf; + } +#else + void releaseFile(char* buf, size_t size) { + if(munmap(buf,size)) + perror("Warning: image_util::releaseFile(), on munmap"); + } +#endif + + /// @cond INTERNAL + + //! provides error handling in the case of a jpeg error, inspired by libpng's handling + struct my_error_mgr { + //! fields used for jpeg error handling (this MUST BE FIRST MEMBER so libjpeg can treat my_error_mgr as a jpeg_error_mgr struct — C-style "inheritance") + struct jpeg_error_mgr pub; + char buffer[JMSG_LENGTH_MAX]; //!< message indicating reason for error + jmp_buf setjmp_buffer; //!< a jump buffer to trigger on error, similar to exception except not as safe (use a C library, this is what you get...) + }; + //! called on error from libjpeg, @a cinfo should be an instance of my_error_mgr + static void my_error_exit (j_common_ptr cinfo) + { + /* cinfo->err really points to a my_error_mgr struct, so coerce pointer */ + my_error_mgr * myerr = (my_error_mgr *) cinfo->err; + (*cinfo->err->format_message) (cinfo, myerr->buffer); + /* Return control to the setjmp point */ + longjmp(myerr->setjmp_buffer, 1); + } + + //! common implementation for variants of decodeJPEG() to call after they've set up the decompression structure + bool decodeJPEG(jpeg_decompress_struct& cinfo, my_error_mgr& jerr, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize, const std::string& filename) { + jpeg_read_header(&cinfo, true); + cinfo.out_color_space=JCS_YCbCr; + jpeg_calc_output_dimensions(&cinfo); + width=cinfo.output_width; + height=cinfo.output_height; + channels=cinfo.output_components; + if(cinfo.output_width==0 || cinfo.output_height==0 || cinfo.output_components==0) { + jpeg_destroy_decompress(&cinfo); + return true; + } + if(outbuf==NULL) { + outbufSize=width*height*channels; + outbuf=new char[outbufSize]; + } else if(width*height*channels>outbufSize) { + // not enough output space + jpeg_destroy_decompress(&cinfo); + return false; + } + + // setup image destination + unsigned int remain=cinfo.output_height; + unsigned int row_stride = cinfo.output_width * cinfo.output_components; + JSAMPROW rows[remain]; + rows[0]=(JSAMPLE*)outbuf; + if(rows[0]==NULL) { + jpeg_destroy_decompress(&cinfo); + return false; + } + for(unsigned int i=1; ialloc_sarray)((j_common_ptr) &cinfo, JPOOL_IMAGE, row_stride, 1); + + // read image + jpeg_start_decompress(&cinfo); + while (remain>0) { + unsigned int used=jpeg_read_scanlines(&cinfo, curpos, remain); + curpos+=used; + remain-=used; + } + jpeg_finish_decompress(&cinfo); + if(jerr.pub.num_warnings>0) { + if(filename.size()>0) + cerr << "Warning: image_util JPEG decompression of '" << filename << "' had warnings" << endl; + else + cerr << "Warning: image_util JPEG decompression had warnings" << endl; + jerr.pub.num_warnings=0; + } + + // teardown + jpeg_destroy_decompress(&cinfo); + return true; + } + + /// @endcond + + bool decodeJPEG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels) { + jpeg_decompress_struct cinfo; //!< used to interface with libjpeg - holds compression parameters and state + my_error_mgr jerr; //!< used to interface with libjpeg - gives us access to error information + cinfo.err = jpeg_std_error(&jerr.pub); + jerr.pub.error_exit = my_error_exit; + /* Establish the setjmp return context for my_error_exit to use. */ + if (setjmp(jerr.setjmp_buffer)) { + /* If we get here, the JPEG code has signaled an error. + * We need to clean up the JPEG object, close the input file, and return. + */ + jpeg_destroy_decompress(&cinfo); + cerr << "JPEG header check failed: " << jerr.buffer << endl; + return false; + } + + jpeg_create_decompress(&cinfo); + + // get image header info + jpeg_mem_src(&cinfo, (JOCTET*)inbuf, inbufSize); + jpeg_read_header(&cinfo, true); + cinfo.out_color_space=JCS_YCbCr; + jpeg_calc_output_dimensions(&cinfo); + width=cinfo.output_width; + height=cinfo.output_height; + channels=cinfo.output_components; + jpeg_destroy_decompress(&cinfo); + return true; + } + + bool decodeJPEG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize, const std::string& filename/*=""*/) { + jpeg_decompress_struct cinfo; //!< used to interface with libjpeg - holds compression parameters and state + my_error_mgr jerr; //!< used to interface with libjpeg - gives us access to error information + cinfo.err = jpeg_std_error(&jerr.pub); + jerr.pub.error_exit = my_error_exit; + /* Establish the setjmp return context for my_error_exit to use. */ + if (setjmp(jerr.setjmp_buffer)) { + /* If we get here, the JPEG code has signaled an error. + * We need to clean up the JPEG object, close the input file, and return. + */ + jpeg_destroy_decompress(&cinfo); + cerr << "JPEG decompression failed: " << jerr.buffer << endl; + return false; + } + + jpeg_create_decompress(&cinfo); + + // get image header info + jpeg_mem_src(&cinfo, (JOCTET*)inbuf, inbufSize); + return decodeJPEG(cinfo,jerr,width,height,channels,outbuf,outbufSize,filename); + } + + bool decodeJPEG(std::istream& inStream, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize, const std::string& filename) { + jpeg_decompress_struct cinfo; //!< used to interface with libjpeg - holds compression parameters and state + my_error_mgr jerr; //!< used to interface with libjpeg - gives us access to error information + cinfo.err = jpeg_std_error(&jerr.pub); + jerr.pub.error_exit = my_error_exit; + /* Establish the setjmp return context for my_error_exit to use. */ + if (setjmp(jerr.setjmp_buffer)) { + /* If we get here, the JPEG code has signaled an error. + * We need to clean up the JPEG object, close the input file, and return. + */ + jpeg_destroy_decompress(&cinfo); + cerr << "JPEG stream decompression failed: " << jerr.buffer << endl; + return false; + } + + jpeg_create_decompress(&cinfo); + + // get image header info + jpeg_istream_src(&cinfo, inStream); + return decodeJPEG(cinfo,jerr,width,height,channels,outbuf,outbufSize,filename); + } + + + /// @cond INTERNAL + + //! stores progress of user_read_png_data() between calls + struct png_read_mem_status { + png_bytep buf; //!< pointer to the beginning of the read buffer, the current position within the buffer is indicated by #offset + size_t bufsize; //!< size of the read buffer pointed to by #buf + size_t offset; //!< current read position within #buf + }; + //! user callback function for reading a png from user parameters stored in @a png_ptr into @a data + static void user_read_png_data(png_structp png_ptr, png_bytep data, png_size_t length) { + png_read_mem_status* status=(png_read_mem_status*)(png_get_io_ptr(png_ptr)); + size_t endoff=status->offset+length; + if(endoff<=status->bufsize) { + memcpy(data,status->buf+status->offset,length); + status->offset=endoff; + } else { + png_error(png_ptr, "Read Error - ran out of file"); + } + } + + //! user callback function for reading a png from user parameters stored in @a png_ptr into @a data + static void user_read_png_istream(png_structp png_ptr, png_bytep data, png_size_t length) { + std::istream* inStream=(std::istream*)(png_get_io_ptr(png_ptr)); + if(!inStream->read((char*)data,length)) + png_error(png_ptr, "Read Error - stream closed early"); + } + + //! stores progress of user_write_png_data() between calls + struct png_write_mem_status { + png_bytep buf; //!< beginning of buffer being writen into (doesn't move with progress) + size_t bufsize; //!< total size of buffer + size_t offset; //!< position within buffer, i.e. amount of buffer written so far + }; + //! user callback function for writing a png at @a data into user parameters stored in @a png_ptr + void user_write_png_data(png_structp png_ptr, png_bytep data, png_size_t length) { + png_write_mem_status* status=(png_write_mem_status*)(png_get_io_ptr(png_ptr)); + size_t endoff=status->offset+length; + if(endoff<=status->bufsize) { + memcpy(status->buf+status->offset,data,length); + status->offset=endoff; + } else { + png_error(png_ptr, "Write Error - ran out of file"); + } + } + //! user callback function for flushing results of user_write_png_data() (this is a no-op) + void user_flush_png_data(png_structp /*png_ptr*/) {} + + //! Common implementation for decodePNG() implementations + bool decodePNG(png_structp png_ptr, png_infop info_ptr, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + // get image header info + png_read_info(png_ptr, info_ptr); + width=png_get_image_width(png_ptr, info_ptr); + height=png_get_image_height(png_ptr, info_ptr); + channels=3; + if(width==0 || height==0) + return true; + if(outbuf==NULL) { + outbufSize=width*height*channels; + outbuf=new char[outbufSize]; + } else if(width*height*channels>outbufSize) { + png_destroy_read_struct(&png_ptr, &info_ptr,(png_infopp)NULL); + return false; + } + + // setup image destination + size_t bit_depth=png_get_bit_depth(png_ptr, info_ptr); + if(bit_depth == 16) + png_set_strip_16(png_ptr); + if (bit_depth < 8) + png_set_packing(png_ptr); + + size_t color_type=png_get_color_type(png_ptr, info_ptr); + if (color_type & PNG_COLOR_MASK_ALPHA) + png_set_strip_alpha(png_ptr); + if (color_type == PNG_COLOR_TYPE_GRAY || color_type == PNG_COLOR_TYPE_GRAY_ALPHA) + png_set_gray_to_rgb(png_ptr); + + png_color_16 my_background; + my_background.index=0; + my_background.red=1<<15; + my_background.green=1<<15; + my_background.blue=1<<15; + my_background.gray=1<<15; + png_color_16p image_background=NULL; + if (png_get_bKGD(png_ptr, info_ptr, &image_background)) + png_set_background(png_ptr, image_background, PNG_BACKGROUND_GAMMA_FILE, 1, 1.0); + else + png_set_background(png_ptr, &my_background, PNG_BACKGROUND_GAMMA_SCREEN, 0, 1.0); + png_read_update_info(png_ptr, info_ptr); + + // read image + size_t rowbytes=png_get_rowbytes(png_ptr, info_ptr); + /*png_bytep row_pointers[height]; + row_pointers[0]=reinterpret_cast(data->Base()+FULL_HEADER_SIZE); + for(unsigned int h=1; h(outbuf); + for(unsigned int h=0; hreinterpret_cast(outbuf+outbufSize)) { + cerr << "image_util::decodePNG ran out of PNG buffer space" << endl; + break; + } + png_read_row(png_ptr, row, NULL); + row+=rowbytes; + } + png_read_end(png_ptr, NULL); + + // teardown + png_destroy_read_struct(&png_ptr, &info_ptr,(png_infopp)NULL); + return true; + } + + /// @endcond + + bool decodePNG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels) { + png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, (png_voidp)NULL, NULL, NULL); + if (!png_ptr) + return false; + png_infop info_ptr = png_create_info_struct(png_ptr); + if (!info_ptr) { + png_destroy_read_struct(&png_ptr, (png_infopp)NULL, (png_infopp)NULL); + return false; + } + if (setjmp(png_jmpbuf(png_ptr))) { + png_destroy_read_struct(&png_ptr, &info_ptr, (png_infopp)NULL); + return false; + } + + png_read_mem_status read_status; + read_status.buf=(png_bytep)inbuf; + read_status.bufsize=inbufSize; + read_status.offset=0; + png_set_read_fn(png_ptr, &read_status, user_read_png_data); + + // get image header info + png_read_info(png_ptr, info_ptr); + width=png_get_image_width(png_ptr, info_ptr); + height=png_get_image_height(png_ptr, info_ptr); + channels=3; + png_destroy_read_struct(&png_ptr, &info_ptr,(png_infopp)NULL); + return true; + } + + bool decodePNG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, (png_voidp)NULL, NULL, NULL); + if (!png_ptr) + return false; + png_infop info_ptr = png_create_info_struct(png_ptr); + if (!info_ptr) { + png_destroy_read_struct(&png_ptr, (png_infopp)NULL, (png_infopp)NULL); + return false; + } + if (setjmp(png_jmpbuf(png_ptr))) { + png_destroy_read_struct(&png_ptr, &info_ptr, (png_infopp)NULL); + return false; + } + + png_read_mem_status read_status; + read_status.buf=(png_bytep)inbuf; + read_status.bufsize=inbufSize; + read_status.offset=0; + png_set_read_fn(png_ptr, &read_status, user_read_png_data); + return decodePNG(png_ptr, info_ptr, width, height, channels, outbuf, outbufSize); + } + + bool decodePNG(std::istream& inStream, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, (png_voidp)NULL, NULL, NULL); + if (!png_ptr) + return false; + png_infop info_ptr = png_create_info_struct(png_ptr); + if (!info_ptr) { + png_destroy_read_struct(&png_ptr, (png_infopp)NULL, (png_infopp)NULL); + return false; + } + if (setjmp(png_jmpbuf(png_ptr))) { + png_destroy_read_struct(&png_ptr, &info_ptr, (png_infopp)NULL); + return false; + } + + png_set_read_fn(png_ptr, &inStream, user_read_png_istream); + return decodePNG(png_ptr, info_ptr, width, height, channels, outbuf, outbufSize); + } + + + + bool decodeImage(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels) { + if(!png_sig_cmp((png_byte*)inbuf, 0, 8)) { + return decodePNG(inbuf,inbufSize,width,height,channels); + } else { + return decodeJPEG(inbuf,inbufSize,width,height,channels); + } + } + bool decodeImage(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + if(!png_sig_cmp((png_byte*)inbuf, 0, 8)) { + return decodePNG(inbuf,inbufSize,width,height,channels,outbuf,outbufSize); + } else { + return decodeJPEG(inbuf,inbufSize,width,height,channels,outbuf,outbufSize); + } + } + + + + bool loadJPEG(const std::string& file, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + char* inbuf; + size_t inbufSize; + if(!loadFile(file, inbuf, inbufSize)) + return false; + bool res=decodeJPEG(inbuf,inbufSize,width,height,channels,outbuf,outbufSize); + releaseFile(inbuf,inbufSize); + return res; + } + bool loadPNG(const std::string& file, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + char* inbuf; + size_t inbufSize; + if(!loadFile(file, inbuf, inbufSize)) + return false; + bool res=decodePNG(inbuf,inbufSize,width,height,channels,outbuf,outbufSize); + releaseFile(inbuf,inbufSize); + return res; + } + bool loadImage(const std::string& file, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize) { + char* inbuf; + size_t inbufSize; + if(!loadFile(file, inbuf, inbufSize)) + return false; + bool res=decodeImage(inbuf,inbufSize,width,height,channels,outbuf,outbufSize); + releaseFile(inbuf,inbufSize); + return res; + } + + + + size_t encodeJPEG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels, int quality) { + jpeg_compress_struct cinfo; + jpeg_error_mgr jerr; + // We set the err object before we create the compress... the idea + // is if the creation fails, we can still get the error as to why it failed. + cinfo.err = jpeg_std_error(&jerr); + jpeg_create_compress(&cinfo); + size_t ans=encodeJPEG(inbuf,inbufSize,width,height,inbufChannels,outbuf,outbufSize,outbufChannels,quality,cinfo); + jpeg_destroy_compress(&cinfo); + return ans; + } + size_t encodeJPEG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels, int quality, jpeg_compress_struct& cinfo) { + return encodeJPEG(inbuf,inbufSize,width,height,inbufChannels,outbuf,outbufSize,outbufChannels,quality,1,1,cinfo); + } + size_t encodeJPEG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels, int quality, unsigned int yskip, unsigned int uvskip, jpeg_compress_struct& cinfo) { + try { + if(quality>100) + quality=100; + if(quality<0) + quality=0; + // check destination buffer + if(outbuf==NULL) { + outbufSize=width*height*outbufChannels*(quality+50)/200; + outbuf=new char[outbufSize]; + } + + //pass the destination buffer and buffer size here + jpeg_mem_dest(&cinfo, reinterpret_cast(outbuf), outbufSize); + + // mode setup + cinfo.image_width = width; + cinfo.image_height = height; + cinfo.input_components = outbufChannels; + if(outbufChannels==1) { + cinfo.in_color_space = JCS_GRAYSCALE; + } else if(outbufChannels==3) { + cinfo.in_color_space = JCS_YCbCr; + } else { + cerr << "image_util JPEG compression failed - don't know how to compress into " << outbufChannels << " channels" << endl; + return 0; + } + + // parameter setup + jpeg_set_defaults(&cinfo); + jpeg_set_quality(&cinfo, quality, false); /* limit to baseline-JPEG values */ + cinfo.dct_method=config->vision.jpeg_dct_method; + if(cinfo.in_color_space==JCS_GRAYSCALE && inbufChannels!=1) { + //special case, need to remove interleaved channels as we compress (single channel, grayscale) + jpeg_start_compress(&cinfo, true); + unsigned int row_stride = width*inbufChannels; /* JSAMPLEs per row in image_buffer */ + JSAMPROW row_pointer[1] = { new JSAMPLE[width] }; + while (cinfo.next_scanline < cinfo.image_height) { + if(inbufSizeuvskip) { + uvsamp=yskip-uvskip+1; + if(uvsamp>maxsamp) + uvsamp=maxsamp; + } else { + ysamp=uvskip-yskip+1; + if(ysamp>maxsamp) + ysamp=maxsamp; + } + cinfo.comp_info[0].h_samp_factor=ysamp; + cinfo.comp_info[0].v_samp_factor=ysamp; + cinfo.comp_info[1].h_samp_factor=uvsamp; + cinfo.comp_info[1].v_samp_factor=uvsamp; + cinfo.comp_info[2].h_samp_factor=uvsamp; + cinfo.comp_info[2].v_samp_factor=uvsamp; + } + + // compression + jpeg_start_compress(&cinfo, true); + unsigned int row_stride = width*inbufChannels; /* JSAMPLEs per row in image_buffer */ + JSAMPROW row_pointer[1] = { const_cast(reinterpret_cast(inbuf)) }; + while (cinfo.next_scanline < cinfo.image_height) { + if(inbufSize(outbuf); + write_status.bufsize=outbufSize; + write_status.offset=0; + png_set_write_fn(png_ptr, &write_status, user_write_png_data, user_flush_png_data); + + if(setjmp(png_jmpbuf(png_ptr))) { + cerr << "An error occurred during PNG compression" << endl; + png_destroy_write_struct(&png_ptr, &info_ptr); + return 0; + } + + // configure compression + int bit_depth=8; + int color_type; + if(outbufChannels==3) + color_type=PNG_COLOR_TYPE_RGB; + else if(outbufChannels==1) + color_type=PNG_COLOR_TYPE_GRAY; + else { + cerr << "image_util PNG compression failed - don't know how to compress into " << outbufChannels << " channels" << endl; + return 0; + } + png_set_IHDR(png_ptr, info_ptr, width, height, bit_depth, color_type, PNG_INTERLACE_NONE, PNG_COMPRESSION_TYPE_DEFAULT, PNG_FILTER_TYPE_DEFAULT); + png_write_info(png_ptr, info_ptr); + png_bytep row=reinterpret_cast(inbuf); + const unsigned int inc=inbufChannels; +#ifdef DEBUG + if(color_type==PNG_COLOR_TYPE_RGB && inc!=3 || color_type==PNG_COLOR_TYPE_GRAY && inc!=1) { + cerr << "image_util::encodePNG() only supports color mode from sources with interleaving of 3 samples (increment==3), or grayscale from \"pure\" sources (increment==1)" << endl; + png_write_end(png_ptr, NULL); + return 0; + } +#endif + + // do compression + unsigned int row_stride = width*inc; + png_bytep endp=reinterpret_cast(row+inbufSize); + for(unsigned int h=0; hendp) { + cerr << "image_util ran out of src image -- bad height?" << endl; + break; + } + png_write_row(png_ptr, row); + row+=row_stride; + } + png_write_end(png_ptr, NULL); + png_destroy_write_struct(&png_ptr, &info_ptr); + + // return results + return write_status.offset; + } + +} // image_util namespace + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.14 $ + * $State: Exp $ + * $Date: 2007/11/14 02:29:03 $ + */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ImageUtil.h ./Shared/ImageUtil.h --- ../Tekkotsu_3.0/Shared/ImageUtil.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/ImageUtil.h 2007-11-13 18:32:29.000000000 -0500 @@ -0,0 +1,269 @@ +//-*-c++-*- +#ifndef INCLUDED_image_util_h_ +#define INCLUDED_image_util_h_ + +#include + +struct jpeg_compress_struct; + +//! Provides a variety of straightforward calls to compress or decompress images in JPEG or PNG formats +namespace image_util { + + //! @name Generic File Utilities + + //! loads a file into memory, returns true if successful, storing resulting buffer information in @a buf and @a size + /*! uses mmap unless LOADFILE_NO_MMAP is defined, in which case it uses 'new' and fread() */ + bool loadFile(const std::string& file, char*& buf, size_t& size); + //! releases memory from a previous call to loadFile, triggering munmap() or 'delete' as appropriate + void releaseFile(char* buf, size_t size); + + //@} + + + + //! @name Decode Header Information (from memory buffer) + + //! decodes an image header already in memory -- if it looks like a PNG decodePNG() will be called, otherwise decodeJPEG(); returns true if successful + /*! @param inbuf input memory buffer containing compressed image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param channels the number of color channels*/ + bool decodeImage(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels); + + //! decodes a JPEG header already in memory, returns true if successful + /*! @param inbuf input memory buffer containing compressed image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param channels the number of color channels */ + bool decodeJPEG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels); + + //! decodes a PNG header already in memory, returns true if successful + /*! @param inbuf input memory buffer containing compressed image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param channels the number of color channels */ + bool decodePNG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels); + + //@} + + + + //! @name Decompress From Memory Buffer + + //! decodes an image already in memory -- if it looks like a PNG decodePNG() will be called, otherwise decodeJPEG(); returns true if successful + /*! @param inbuf input memory buffer containing compressed image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * (This is a handy way to read the image header only -- pass ((char*)NULL)-1 as @a outbuf and 0 for @a outbufSize, + * the function will return false after reading the header and filling in width, height, and channels) + * The image will be written in row order, with channels interleaved. */ + bool decodeImage(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize); + + //! decodes a JPEG image already in memory, returns true if successful + /*! @param inbuf input memory buffer containing compressed image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * @param filename optional parameter, used if warnings are raised + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool decodeJPEG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize, const std::string& filename=""); + + //! decodes a PNG image already in memory, returns true if successful + /*! @param inbuf input memory buffer containing compressed image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool decodePNG(char* inbuf, size_t inbufSize, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize); + + //@} + + + + //! @name Decompress From Input Stream + + //! decodes a JPEG image from a standard library input stream, returns true if successful + /*! @param inStream input stream providing image + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * @param filename optional parameter, used if warnings are raised + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool decodeJPEG(std::istream& inStream, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize, const std::string& filename=""); + + //! decodes a PNG image from a standard library input stream, returns true if successful + /*! @param inStream input stream from which to read images + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool decodePNG(std::istream& inStream, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize); + + //@} + + + + //! @name Decompress from File + + //! decodes an image from file on disk -- if it looks like a PNG decodePNG() will be called, otherwise decodeJPEG(); returns true if successful + /*! @param file path to file to load + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool loadImage(const std::string& file, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize); + + //! decodes a JPEG from disk, returns true if successful + /*! @param file path to file to load + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool loadJPEG(const std::string& file, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize); + + //! decodes a PNG from disk, returns true if successful + /*! @param file path to file to load + * @param width the image width + * @param height the image height + * @param channels the number of color channels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * + * If @a outbuf is pre-allocated and outbufSize is less than width*height*channels, the function will return false. + * The image will be written in row order, with channels interleaved. */ + bool loadPNG(const std::string& file, size_t& width, size_t& height, size_t& channels, char*& outbuf, size_t& outbufSize); + + //@} + + + + //! @name Compression (In-Memory only) + + //! encodes a JPEG from a pixel buffer into another memory buffer, returns number of bytes used, 0 if error + /*! @param inbuf input memory buffer containing the image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param inbufChannels the number of color channels in the source image; either 1 (grayscale), or 3 (color) + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * @param outbufChannels the number of color channels desired in the destination image (only downsample from color to grayscale) + * @param quality how well to reproduce the image, 0-100 + * + * If @a outbuf is NULL, one of size @f$ width \cdot height \cdot outbufChannels \cdot (quality/2+25)/100+500 @f$ will be allocated for you. + * (just a heuristic size... note that this won't all be used, and can't entirely guarantee it'll be enough!) + * + * If @a inbufChannels is 3, @a outbufChannels can be either 3 or 1. If 1, the first channel of + * @a inbuf is used. (pre-increment @a inbuf to use a different channel...) If @a inbufChannels + * is 1, outbufChannels must also be 1. */ + size_t encodeJPEG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels, int quality); + + //! encodes a JPEG from a pixel buffer into another memory buffer, returns number of bytes used, 0 if error + /*! @param inbuf input memory buffer containing the image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param inbufChannels the number of color channels in the source image; either 1 (grayscale), or 3 (color) + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * @param outbufChannels the number of color channels desired in the destination image (only downsample from color to grayscale) + * @param quality how well to reproduce the image, 0-100 + * @param cinfo allows you to use a pre-allocated jpeg structure instead of having the function recreate it each time + * + * If @a outbuf is NULL, one of size @f$ width \cdot height \cdot outbufChannels \cdot (quality/2+25)/100+500 @f$ will be allocated for you. + * (just a heuristic size... note that this won't all be used, and can't entirely guarantee it'll be enough!) + * + * If @a inbufChannels is 3, @a outbufChannels can be either 3 or 1. If 1, the first channel of + * @a inbuf is used. (pre-increment @a inbuf to use a different channel...) If @a inbufChannels + * is 1, outbufChannels must also be 1. */ + size_t encodeJPEG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels, int quality, jpeg_compress_struct& cinfo); + + //! encodes a JPEG from a pixel buffer into another memory buffer, returns number of bytes used, 0 if error + /*! @param inbuf input memory buffer containing the image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param inbufChannels the number of color channels in the source image; either 1 (grayscale), or 3 (color) + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * @param outbufChannels the number of color channels desired in the destination image (only downsample from color to grayscale) + * @param quality how well to reproduce the image, 0-100 + * @param yskip increment for the y channel + * @param uvskip increment for the u and v channels + * @param cinfo allows you to use a pre-allocated jpeg structure instead of having the function recreate it each time + * + * If @a outbuf is NULL, one of size @f$ width \cdot height \cdot outbufChannels \cdot (quality/2+25)/100+500 @f$ will be allocated for you. + * (just a heuristic size... note that this won't all be used, and can't entirely guarantee it'll be enough!) + * + * If @a inbufChannels is 3, @a outbufChannels can be either 3 or 1. If 1, the first channel of + * @a inbuf is used. (pre-increment @a inbuf to use a different channel...) If @a inbufChannels + * is 1, outbufChannels must also be 1. */ + size_t encodeJPEG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels, int quality, unsigned int yskip, unsigned int uvskip, jpeg_compress_struct& cinfo); + + //! encodes a JPEG from a pixel buffer into another memory buffer, returns number of bytes used, 0 if error + /*! @param inbuf input memory buffer containing the image + * @param inbufSize the size of @a inbuf allocation + * @param width the image width + * @param height the image height + * @param inbufChannels the number of color channels in the source image; either 1 (grayscale), or 3 (color); must match @a outbufChannels + * @param outbuf on input, a buffer to use for decompression; if NULL, a new buffer will be allocated and assigned + * @param outbufSize if @a outbuf is non-NULL, this should indicate the size of @a outbuf + * @param outbufChannels the number of color channels desired in the destination image; must match @a inbufChannels + * + * If @a outbuf is NULL, one of size @f$ width \cdot height \cdot outbufChannels + 500 @f$ will be allocated for you. + * (just a heuristic size... note that this won't all be used, and can't entirely guarantee it'll be enough!) + * + * Currently doesn't support changes in channels, so @a inbufChannels must match @a outbufChannels */ + size_t encodePNG(char* inbuf, size_t inbufSize, size_t width, size_t height, size_t inbufChannels, char*& outbuf, size_t& outbufSize, size_t outbufChannels); + + //@} + +}; + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.9 $ + * $State: Exp $ + * $Date: 2007/11/13 23:32:29 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/InstanceTracker.h ./Shared/InstanceTracker.h --- ../Tekkotsu_3.0/Shared/InstanceTracker.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/InstanceTracker.h 2007-11-14 21:44:06.000000000 -0500 @@ -0,0 +1,223 @@ +//-*-c++-*- +#ifndef INCLUDED_InstanceTracker_h_ +#define INCLUDED_InstanceTracker_h_ + +#include "plistCollections.h" +#include "FamilyFactory.h" +#include + +//! Attempts to provide references to all currently instantiated objects of a class (and its subclasses) +/*! The classes being tracked need to register themselves via registerInstance() -- this isn't magic. + * The easiest way to do this is simply to have the base FamilyT's constructor do the registration, + * and then all of the subclasses will get it automatically. This only works however, on the assumption + * that nothing is going to try to immediately access the newly registered entry while subclass + * construction is still in progress. */ +template, template class FactoryT=FactoryBaseT::template Factory> +class InstanceTracker : public plist::Dictionary, protected FamilyFactory { +public: + //! shorthand for iterators to be returned + typedef plist::Dictionary::iterator iterator; + //! shorthand for iterators to be returned + typedef plist::Dictionary::const_iterator const_iterator; + + //! allows indirect access to the product family type + typedef FamilyT FamilyType; + //! allows indirect access to the product class name type + typedef ClassNameT ClassNameType; + //! allows indirect access to the factory base class + typedef FactoryBaseT FactoryBaseType; + //! allows indirect access to create factory classes + template struct FactoryType : FactoryT {}; + + //! constructor + InstanceTracker() : plist::Dictionary(), FamilyFactory() {} + + using FamilyFactory::getTypeNames; + using FamilyFactory::getNumTypes; + using FamilyFactory::registerType; + using FamilyFactory::registerFactory; + + //! Register an existing instance via reference, does @em not assume responsibility for memory deallocation, returns false if @a name is already in use. + template bool registerInstance(const std::string& name, T& inst); + //! Register an existing instance via pointer, @em does assume responsibility for memory deallocation, returns false if @a name is already in use. + template bool registerInstance(const std::string& name, T* inst); + //! Register an existing instance via reference, does @em not assume responsibility for memory deallocation, returns false if @a name is already in use. + /*! If @a type is not an empty string, and @a inst is a plist::Dictionary, a '.type' entry will be added to store + * the type. This allows polymorphic loading. Non-dictionaries will be wrapped in a new plist::Dictionary with a '.type'. */ + template bool registerInstance(const ClassNameT& type, const std::string& name, T& inst); + //! Register an existing instance via pointer, @em does assume responsibility for memory deallocation, returns false if @a name is already in use. + /*! If @a type is not an empty string, and @a inst is a plist::Dictionary, a '.type' entry will be added to store + * the type. This allows polymorphic loading. Non-dictionaries will be wrapped in a new plist::Dictionary with a '.type'. */ + template bool registerInstance(const ClassNameT& type, const std::string& name, T* inst); + + //! create and register an instance in one call + FamilyT* create(const ClassNameType& type, const std::string& name); + //! looks up a previously registered instance, returning NULL if not found + FamilyT* getInstance(const std::string& name ); + //! Removes an instance from the tracker. + /*! If the tracker was managing the memory allocation (via create() or the registerInstance() functions + * which take a pointer instead of a reference), then this will cause the instance to be deallocated. */ + bool destroy(const std::string& name); + + void loadXML(xmlNode* node); + +protected: + //! Provides a wrapper for non-plist::Dictionary entries. + /*! This allows InstanceTracker to use plist::Dictionary as a superclass to manage the tracked instances, + * as well as polymorphically load and save the entire set of instances. Which is why we use a dictionary + * here instead of a simple plist::ObjectBase so we can handle a '.type' entry to store the instance's class type. */ + class InstanceEntry : public plist::Dictionary { + public: + //! constructor, assigns @a inst to both #instance and #alloc (thus marking the instance for deallocation on InstanceEntry destruction) + explicit InstanceEntry(FamilyT* inst) : plist::Dictionary(), alloc(inst), instance(*inst) {} + //! constructor, assigns @a inst to #instance only, leaving #alloc NULL (thus leaving deallocation of instance to the caller) + explicit InstanceEntry(FamilyT& inst) : plist::Dictionary(), alloc(NULL), instance(inst) {} + //! destructor, deallocates #alloc (which might be NULL, and thus a no-op) + ~InstanceEntry() { delete alloc; } + + FamilyT* const alloc; //!< if the original instance was passed as a pointer, we will store that here for easy deallocation on destruction + FamilyT& instance; //!< reference to the actual instance + + private: + InstanceEntry(const InstanceEntry&); //!< copy constructor, don't call + InstanceEntry& operator=(const InstanceEntry&); //!< assignment, don't call + }; + +private: + InstanceTracker(const InstanceTracker&); //!< copy constructor, don't call + InstanceTracker& operator=(const InstanceTracker&); //!< assignment, don't call +}; + +template class FactoryT> +template +bool InstanceTracker::registerInstance(const std::string& name, T& inst) { + if(findEntry(name)!=end()) + return false; // already have instance by that name + plist::Dictionary* dinst=dynamic_cast(&inst); + if(dinst!=NULL) { + addEntry(name,*dinst); // note adding as reference so we don't try to delete the reference we were given + } else { + dinst=new InstanceEntry(inst); // create a wrapper for the non-Dictionary type + addEntry(name,dinst); // adding as pointer since we want to delete our wrapper + } + return true; +} +template class FactoryT> +template +bool InstanceTracker::registerInstance(const std::string& name, T* inst) { + if(findEntry(name)!=end()) + return false; // already have instance by that name + plist::Dictionary* dinst=dynamic_cast(inst); + if(dinst==NULL) + dinst=new InstanceEntry(inst); // create a wrapper for the non-Dictionary type + addEntry(name,dinst); + return true; +} +template class FactoryT> +template +bool InstanceTracker::registerInstance(const ClassNameT& type, const std::string& name, T& inst) { + if(findEntry(name)!=end()) + return false; // already have instance by that name + plist::Dictionary* dinst=dynamic_cast(&inst); + if(dinst!=NULL) { + if(type.size()>0) + dinst->addEntry(".type",new plist::Primitive(type),"Stores the typename of the class so it can be re-instantiated on load.\n** Do not edit ** "); + addEntry(name,*dinst); // note adding as reference so we don't try to delete the reference we were given + } else { + dinst=new InstanceEntry(inst); // create a wrapper for the non-Dictionary type + if(type.size()>0) + dinst->addEntry(".type",new plist::Primitive(type),"Stores the typename of the class so it can be re-instantiated on load.\n** Do not edit ** "); + addEntry(name,dinst); // adding as pointer since we want to delete our wrapper + } + return true; +} +template class FactoryT> +template +bool InstanceTracker::registerInstance(const ClassNameT& type, const std::string& name, T* inst) { + if(findEntry(name)!=end()) + return false; // already have instance by that name + plist::Dictionary* dinst=dynamic_cast(inst); + if(dinst==NULL) + dinst=new InstanceEntry(inst); // create a wrapper for the non-Dictionary type + if(type.size()>0) + dinst->addEntry(".type",new plist::Primitive(type),"Stores the typename of the class so it can be re-instantiated on load.\n** Do not edit ** "); + addEntry(name,dinst); + return true; +} + +template class FactoryT> +FamilyT* InstanceTracker::create(const ClassNameT& type, const std::string& name) { + if(findEntry(name)!=end()) + return NULL; // already have instance by that name + FamilyT* inst=FamilyFactory::create(type,name); + if(inst==NULL) + return NULL; // apparently type isn't valid + registerInstance(type,name,inst); // if it fails, means instance registered itself from constructor, that's fine + return inst; +} + +template class FactoryT> +FamilyT* InstanceTracker::getInstance(const std::string& name) { + const_iterator it=findEntry(name); + if(it==end()) + return NULL; // doesn't exit + if(InstanceEntry* inst=dynamic_cast(it->second)) + return &inst->instance; // was a wrapper because FamilyT isn't a Dictionary, extract actual instance + return dynamic_cast(it->second); // otherwise this is our instance right here +} + +template class FactoryT> +bool InstanceTracker::destroy(const std::string& name) { + const_iterator it=findEntry(name); + if(it==end()) + return false; + removeEntry(name); + return true; +} + +template class FactoryT> +void InstanceTracker::loadXML(xmlNode* node) { + // first load the dictionary as a set of generic sub-dictionaries so we can pull out the type fields + plist::Dictionary d; + d.loadXML(node); + for(plist::Dictionary::const_iterator it=d.begin(); it!=d.end(); ++it) { + if(plist::Dictionary* dd = dynamic_cast(it->second)) { + plist::Dictionary::const_iterator obit = dd->findEntry(".type"); + if(obit==dd->end()) { + std::cerr << "ERROR: could not instantiate driver named '" << it->first << "'; no '.type' field found!" << std::endl; + } else { + std::string typestr = obit->second->toString(); + plist::Dictionary::const_iterator drobit = findEntry(it->first); + plist::ObjectBase * drob = (drobit==end()) ? NULL : drobit->second; + if(plist::Dictionary* dr = dynamic_cast(drob)) { + plist::Dictionary::const_iterator tyobit = dr->findEntry(".type"); + if(tyobit==dr->end()) + std::cerr << "WARNING: Driver dictionary lacking .type field for '" << it->first << "'" << std::endl; + else if(tyobit->second->toString()==typestr) + continue; // name and type already match, don't need to recreate + destroy(it->first); // otherwise clear the old instance and fall through to allocate a new instance + dr=NULL; + } + if(create(typestr,it->first)==NULL) + std::cerr << "ERROR: failed to instantiate driver named '" << it->first << "' with type '" << typestr << "'" << std::endl; + } + } else { + std::cerr << "ERROR: could not instantiate driver named '" << it->first << "'; not a dictionary!" << std::endl; + } + } + // now that we've created basic instances, do the "real" loading to give them settings + plist::Dictionary::loadXML(node); +} + +/*! @file + * @brief + * @author Ethan Tira-Thompson (ejt) (Creator) + * + * $Author: ejt $ + * $Name: tekkotsu-4_0 $ + * $Revision: 1.6 $ + * $State: Exp $ + * $Date: 2007/11/15 02:44:06 $ + */ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/LoadSave.h ./Shared/LoadSave.h --- ../Tekkotsu_3.0/Shared/LoadSave.h 2006-10-03 17:11:51.000000000 -0400 +++ ./Shared/LoadSave.h 2007-11-12 23:16:03.000000000 -0500 @@ -6,13 +6,18 @@ #include #include #include -#include "Shared/attributes.h" +#include "attributes.h" #ifdef PLATFORM_APERIOS //! prototype declared only on PLATFORM_APERIOS; system provides an implementation, but apparently no API declaration int vasprintf(char** ret, const char* format, va_list al); #endif +/*! @def LOADSAVE_SWAPBYTES + * @brief Set to 0 on platforms which don't actually need to swap bytes, 1 otherwise. If not set externally, will attempt to auto-detect. + * Swapping is performed to standardize on little-endian byte order. Mainly because this is what we used on the Aibo, which + * was the most processor-starved platform. If running embedded on other platforms, you may want to reverse the logic + * for determining whether byte swapping will be performed! */ #ifndef LOADSAVE_SWAPBYTES #ifdef BYTE_ORDER @@ -458,9 +463,9 @@ //inline static unsigned int encode(const void* x, char buf[], unsigned int cap) throw() { return encode(static_cast(x),buf,cap); } //inline static unsigned int decode(void*& x, const char buf[], unsigned int cap) throw() { unsigned long long tmp; unsigned int used=decode(tmp,buf,cap); if(used==0) return 0; x=reinterpret_cast(tmp); return used; } - inline static unsigned int encode(const std::string& x, char buf[], unsigned int cap) throw() { if(cap(x.size()),buf,cap),x.c_str(),x.size()+1); return x.size()+stringpad; } inline static unsigned int decode(std::string& x, const char buf[], unsigned int cap) throw() { if(cap(x.size()),f); return sizeof(unsigned int)+fwrite(x.c_str(),1,sizeof(x)+1,f); } inline static unsigned int decode(std::string& x, FILE* f) throw() { unsigned int sz=0; decode(sz,f); char *tmp=new char[sz+1]; if(fread(tmp,1,sz+1,f)!=sz+1) { delete [] tmp; return 0; } x.assign(tmp,sz); delete [] tmp; return sz+stringpad; } inline static unsigned int encode(const char* x, char buf[], unsigned int cap) throw() { unsigned int sz=strlen(x); if(cap +#include + +template class LocalizationParticleDistributionPolicy; + +//! Each Particle represents a hypothesis about the match of the local map to the world map. +class LocalizationParticle : public ParticleBase { +public: + float x; //!< X position of particle in world + float y; //!< Y position of particle in world + AngTwoPi theta; //!< Orientation of particle in world + + //! defines a default DistributionPolicy for the particle type + typedef LocalizationParticleDistributionPolicy DistributionPolicy; + + //! constructor + LocalizationParticle() : ParticleBase(), x(0), y(0), theta(0) {} + + //! constructor, allows you to define the particle's position + LocalizationParticle(float xp, float yp, AngTwoPi tp) : ParticleBase(), x(xp), y(yp), theta(tp) {} + + //! returns a straightforward sum squared error of each of the fields + template float sumSqErr(const ParticleT& lp) const { + //const LocalizationParticle& lp = static_cast(p); + float dx=x-lp.x; + float dy=y-lp.y; + float dt=theta-lp.theta; + return dx*dx+dy*dy+dt*dt; + } +}; + +//! Provides parameters and methods for randomizing and tweaking LocalizationParticles +template +class LocalizationParticleDistributionPolicy : public ParticleFilter::DistributionPolicy { +public: + typedef ParticleT particle_type; //!< just for convenience + typedef typename ParticleFilter::index_t index_t; //!< just for convenience + + float mapMinX; //!< specifies the low end of x coordinates during randomize() + float mapWidth; //!< along with #mapMinX, specifies the range of x coordinates to be used during randomize() + float mapMinY; //!< specifies the low end of y coordinates during randomize() + float mapHeight; //!< along with #mapMinY, specifies the range of y coordinates to be used during randomize() + float positionVariance; //!< controls how much the x and y parameters will be modified during jiggle() + float orientationVariance; //!< controls how much the orientation (theta) parameter will be modified during jiggle() + + //! constructor -- by default, coordinates will range from -1000 to 1000 for x and y, with variance of 50 and 0.18 for position and orientation + LocalizationParticleDistributionPolicy() + : mapMinX(-1000), mapWidth(2000), mapMinY(-1000), mapHeight(2000), + positionVariance(50), orientationVariance(0.18f) + {} + + virtual void randomize(particle_type* begin, index_t num) { + particle_type* end=&begin[num]; + while(begin!=end) { + begin->x = float(rand())/RAND_MAX * mapWidth + mapMinX; + begin->y = float(rand())/RAND_MAX * mapHeight + mapMinY; + begin->theta = float(rand())/RAND_MAX * 2 * M_PI; + //(begin++)->randomize(); + ++begin; + } + } + virtual void jiggle(float var, particle_type* begin, index_t num) { + if(var==0) + return; + particle_type* end=&begin[num]; + while(begin!=end) { + begin->x+=DRanNormalZig32()*positionVariance*var; + begin->y+=DRanNormalZig32()*positionVariance*var; + begin->theta+=DRanNormalZig32()*orientationVariance*var; + //(begin++)->jiggle(var); + ++begin; + } + } +}; + +//! dump a particle's state +inline std::ostream& operator << (std::ostream& os, const LocalizationParticle &p) { + os << "Particle(p=" << p.weight + << ", dx=" << p.x + << ", dy=" << p.y + << ", th=" << p.theta + << ")"; + return os; +} + + + +/*! @file +* @brief +* @author ejt (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.5 $ +* $State: Exp $ +* $Date: 2007/03/02 23:59:20 $ +*/ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/LynxArm6Info.h ./Shared/LynxArm6Info.h --- ../Tekkotsu_3.0/Shared/LynxArm6Info.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/LynxArm6Info.h 2007-11-18 01:47:04.000000000 -0500 @@ -0,0 +1,176 @@ +//-*-c++-*- +#ifndef INCLUDED_LynxArm6Info_h +#define INCLUDED_LynxArm6Info_h + +#include +#include +#include "CommonInfo.h" +using namespace RobotInfo; + +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_LYNXARM6) +# define TGT_HAS_ARMS 1 +#endif + +namespace LynxArm6Info { + + // ******************************* + // ROBOT CONFIGURATION + // ******************************* + + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs + + const unsigned int FrameTime=32; //!< time between frames in the motion system (milliseconds) + const unsigned int NumFrames=1; //!< the number of frames per buffer (don't forget also double buffered) + const unsigned int SoundBufferTime=32; //!< the number of milliseconds per sound buffer... I'm not sure if this can be changed + + //!@name Output Types Information + const unsigned NumWheels = 0; //!< no wheels, just legs + + const unsigned JointsPerArm = 6; + const unsigned NumArms = 1; + const unsigned NumArmJoints = JointsPerArm*NumArms; + + const unsigned JointsPerLeg = 0; //!< The number of joints per leg + const unsigned NumLegs = 0; //!< The number of legs + const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs + const unsigned NumHeadJoints = 0; //!< The number of joints in the neck + const unsigned NumTailJoints = 0; //!< The number of joints assigned to the tail + const unsigned NumMouthJoints = 0; //!< the number of joints that control the mouth + const unsigned NumEarJoints = 0; //!< The number of joints which control the ears (NOT per ear, is total) + const unsigned NumButtons = 0; //!< the number of buttons that are available, 2 head, 4 paws, 3 back, 1 underbelly see ERS7Info::ButtonOffset_t + const unsigned NumSensors = 4; //!< the four input pins + const unsigned NumLEDs = 0; //!< The number of LEDs which can be controlled + const unsigned NumFacePanelLEDs = 0; //!< The number of face panel LEDs + + const unsigned NumPIDJoints = NumArmJoints + NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints; //!< The number of joints which use PID motion - everything except ears + const unsigned NumOutputs = NumPIDJoints + NumLEDs; //!< the total number of outputs + const unsigned NumReferenceFrames = NumOutputs + 1 + NumArms + 1; //!< for the base, gripper (* NumArms), and camera reference frames + + // webcam ? + const float CameraHorizFOV=56.9/180*M_PI; //!< horizontal field of view (radians) + const float CameraVertFOV=45.2/180*M_PI; //!< vertical field of view (radians) + const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV + const unsigned int CameraResolutionX=320; //!< the number of pixels available in the 'full' layer + const unsigned int CameraResolutionY=240; //!< the number of pixels available in the 'full' layer + //@} + + + // ******************************* + // OUTPUT OFFSETS + // ******************************* + + //!Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file + //!@name Output Offsets + + const unsigned PIDJointOffset = 0; //!< The beginning of the PID Joints + const unsigned ArmOffset = PIDJointOffset; + + const unsigned BaseFrameOffset = NumOutputs; //!< Use with kinematics to refer to base reference frame + const unsigned GripperFrameOffset = BaseFrameOffset+1; //!< Use with kinematics to refer to paw reference frames + + //! The offsets of the individual LEDs on the head and tail. Note that left/right are robot's point of view. See also LEDBitMask_t + /*! @hideinitializer */ + enum LEDOffset_t { }; + + typedef unsigned int LEDBitMask_t; //!< So you can be clear when you're refering to a LED bitmask + //! LEDs for the face panel (all FaceLEDPanelMask<<(0:NumFacePanelLEDs-1) entries) + const LEDBitMask_t FaceLEDMask = 0; + //! selects all of the leds + const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; + //@} + + + // ******************************* + // INPUT OFFSETS + // ******************************* + + + //! The order in which inputs should be stored + //!@name Input Offsets + + //! holds offsets to different buttons in WorldState::buttons[] + /*! Should be a straight mapping to the ButtonSourceIDs + * + * Note that the chest (power) button is not a normal button. It kills + * power to the motors at a hardware level, and isn't sensed in the + * normal way. If you want to know when it is pressed (and you are + * about to shut down) see PowerSrcID::PauseSID. + * + * @see WorldState::buttons @see ButtonSourceID_t + * @hideinitializer */ + enum ButtonOffset_t { }; + + //! Provides a string name for each button + const char* const buttonNames[NumButtons+1] = { NULL }; // plus one and NULL entry to workaround gcc 3.4.2 internal error + + //! holds offset to different sensor values in WorldState::sensors[] + /*! @see WorldState::sensors[] */ + enum SensorOffset_t { SensorAOffset, SensorBOffset, SensorCOffset, SensorDOffset }; + + //! Provides a string name for each sensor + const char* const sensorNames[NumSensors] = { "SensorA", "SensorB", "SensorC", "SensorD" }; + + //@} + + + //! Names for each of the outputs + const char* const outputNames[NumOutputs] = { + "Shldr:rot","Shldr:elv","Elbow", + "Wrist:rot","Wrist:elv","Gripper" + }; + + //! allocation declared in RobotInfo.cc + extern Capabilities capabilities; + + //! This table holds the default PID values for each joint. see PIDMC + const float DefaultPIDs[NumPIDJoints][3] = { + {1,0,0}, {1,0,0}, {1,0,0}, + {1,0,0}, {1,0,0}, {1,0,0}, + }; + + //!These values are Sony's recommended maximum joint velocities, in rad/ms + /*! a value <= 0 means infinite speed (e.g. LEDs) + * + * These limits are not enforced by the framework. They are simply available for you to use as you see fit. + * HeadPointerMC and PostureMC are primary examples of included classes which do respect these values (although they can be overridden) + * + * These values were obtained from the administrators of the Sony OPEN-R BBS */ + const float MaxOutputSpeed[NumOutputs] = { + 4.86510529e-3, //Legs LR,FB,REK + 5.27962099e-3, + 5.27962099e-3, + 4.86510529e-3, + 5.27962099e-3, + 5.27962099e-3 + }; + + #ifndef RAD + //!Just a little macro for converting degrees to radians + #define RAD(deg) (((deg) * M_PI ) / 180.0) + //!a flag so we undef these after we're done - do you have a cleaner solution? + #define __RI_RAD_FLAG + #endif + + //! This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + const double outputRanges[NumOutputs][2] = + { + { RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) }, + { RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) }, + }; + + //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + /*! Same as #outputRanges */ + const double mechanicalLimits[NumOutputs][2] = + { + { RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) }, + { RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) }, + }; + +#ifdef __RI_RAD_FLAG +#undef RAD +#undef __RI_RAD_FLAG +#endif +} + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Measures.cc ./Shared/Measures.cc --- ../Tekkotsu_3.0/Shared/Measures.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/Measures.cc 2007-01-25 14:07:27.000000000 -0500 @@ -0,0 +1,68 @@ +#include "Shared/Measures.h" + +void AngPi::normalize() { + // Do cheap tests first; use fmod only if necessary. + if ( value < 0 ) + value += Pi; + else if ( value >= Pi) + value -= Pi; + else return; + // If we're still out of range, give up and call fmod. + if ( value < 0 || value >= Pi) { + value = fmod(value,Pi); + if ( value < 0 ) + value += Pi; + }; +} + + +AngPi angdist(AngPi const &arg1, AngPi const &arg2) { + AngPi diff = arg1.value - arg2.value; + if ( diff > Pi/2 ) + diff = Pi - diff; + return diff; +} + +void AngTwoPi::normalize() { + // Do cheap tests first; use fmod only if necessary. + if ( value < 0 ) + value += TwoPi; + else if ( value >= TwoPi) + value -= TwoPi; + else return; + // If we're still out of range, give up and call fmod. + if ( value < 0 || value >= TwoPi) { + value = fmod(value,TwoPi); + if ( value < 0 ) + value += TwoPi; + }; +} + +AngPi angdist(AngTwoPi const &arg1, AngTwoPi const &arg2) { + AngTwoPi diff = arg1.value - arg2.value; + if ( diff > Pi ) + diff = TwoPi - diff; + return AngPi(diff); +} + +void AngSignPi::normalize() { + // Do cheap tests first; use fmod only if necessary. + if ( value < -Pi ) + value += TwoPi; + else if ( value > Pi) + value -= TwoPi; + else return; + // If we're still out of range, give up and call fmod. + if ( value < -Pi || value > Pi) { + value = fmod(value,TwoPi); + if (value < -Pi) + value += TwoPi; + }; +} + +AngPi angdist(AngSignPi const &arg1, AngSignPi const &arg2) { + AngSignPi diff = arg1.value - arg2.value; + if ( diff > Pi ) + diff = TwoPi - diff; + return AngPi(diff); +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Measures.h ./Shared/Measures.h --- ../Tekkotsu_3.0/Shared/Measures.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/Measures.h 2007-01-25 14:07:27.000000000 -0500 @@ -0,0 +1,103 @@ +#ifndef INCLUDED_Measures_h_ +#define INCLUDED_Measures_h_ + +#include + +typedef float coordinate_t; //!< type used for positional coordinates +typedef float orientation_t; //!< type used for orientation values (0 to Pi) +typedef float direction_t; //!< type used for direction values (0 to 2*Pi) + +const direction_t Pi=M_PI; //!< shorthand for ::M_PI from math.h +const direction_t TwoPi=2*M_PI; //!< shorthand for 2*M_PI + +typedef coordinate_t Slope; //!< type used for ratio of coordinate offsets +const Slope BIG_SLOPE=5000.0; //!< slopes larger than this are considered vertical, or in other words, infinite slopes are rounded to this + +//! Circular arithmetic on angles between 0 and pi (180 degrees) +class AngPi { + friend AngPi angdist(AngPi const &arg1, AngPi const &arg2); +public: + AngPi(void) : value(0) {}; //!< constructor, #value defaults to 0 + AngPi(orientation_t const &v) : value(v) { normalize(); } //!< conversion operator allows implicit construction from primitive + + AngPi operator+(AngPi const &arg) const { return AngPi(value+arg.value); }; + AngPi operator-(AngPi const &arg) const { return AngPi(value-arg.value); }; + AngPi operator*(orientation_t const &arg) const { return AngPi(value*arg); }; + AngPi operator/(orientation_t const &arg) const { return AngPi(value/arg); }; + + AngPi& operator=(AngPi const &arg) { value = arg.value; return(*this); }; + AngPi& operator=(orientation_t const &arg) { value = arg; normalize(); return(*this); }; + AngPi& operator+=(orientation_t const &arg) { value += arg; normalize(); return(*this); }; + AngPi& operator-=(orientation_t const &arg) { value -= arg; normalize(); return(*this); }; + AngPi& operator*=(orientation_t const &arg) { value *= arg; normalize(); return(*this); }; + AngPi& operator/=(orientation_t const &arg) { value /= arg; normalize(); return(*this); }; + + operator orientation_t() const { return value; }; //!< conversion operator for going back to the primitive type + +protected: + void normalize(); //!< modifies #value to put it back in range + orientation_t value; //!< holds the angle, should be kept normalized at all times +}; + +//! Angular distance: value is between 0 and pi/2 +AngPi angdist(AngPi const &arg1, AngPi const &arg2); + +//! Circular arithmetic on angles between 0 and two pi (360 degrees) +class AngTwoPi { + friend AngPi angdist(AngTwoPi const &arg1, AngTwoPi const &arg2); +public: + AngTwoPi(void) : value(0) {}; //!< constructor, #value defaults to 0 + AngTwoPi(direction_t const &v) : value(v) { normalize(); } //!< conversion operator allows implicit construction from primitive + + AngTwoPi operator+(AngTwoPi const &arg) const { return AngTwoPi(value+arg.value); }; + AngTwoPi operator-(AngTwoPi const &arg) const { return AngTwoPi(value-arg.value); }; + AngTwoPi operator*(direction_t const &arg) const { return AngTwoPi(value*arg); }; + AngTwoPi operator/(direction_t const &arg) const { return AngTwoPi(value/arg); }; + + AngTwoPi& operator=(AngTwoPi const &arg) { value = arg.value; return(*this); }; + AngTwoPi& operator=(direction_t const &arg) { value = arg; normalize(); return(*this); }; + AngTwoPi& operator+=(direction_t const &arg) { value += arg; normalize(); return(*this); }; + AngTwoPi& operator-=(direction_t const &arg) { value -= arg; normalize(); return(*this); }; + AngTwoPi& operator*=(direction_t const &arg) { value *= arg; normalize(); return(*this); }; + AngTwoPi& operator/=(direction_t const &arg) { value /= arg; normalize(); return(*this); }; + + operator direction_t() const { return value; }; //!< conversion operator for going back to the primitive type + +protected: + void normalize(); //!< modifies #value to put it back in range + direction_t value; //!< holds the angle, should be kept normalized at all times +}; + +//! Angular distance: value is between 0 and pi +AngPi angdist(AngTwoPi const &arg1, AngTwoPi const &arg2); + +//! Circular arithmetic on angles between -pi and pi (360 degrees) +class AngSignPi { + friend AngPi angdist(AngSignPi const &arg1, AngSignPi const &arg2); +public: + AngSignPi(void) : value(0) {}; //!< constructor, #value defaults to 0 + AngSignPi(direction_t const &v) : value(v) { normalize(); } //!< conversion operator allows implicit construction from primitive + + AngSignPi operator+(AngSignPi const &arg) const { return AngSignPi(value+arg.value); }; + AngSignPi operator-(AngSignPi const &arg) const { return AngSignPi(value-arg.value); }; + AngSignPi operator*(direction_t const &arg) const { return AngSignPi(value*arg); }; + AngSignPi operator/(direction_t const &arg) const { return AngSignPi(value/arg); }; + + AngSignPi& operator=(AngSignPi const &arg) { value = arg.value; return(*this); }; + AngSignPi& operator=(direction_t const &arg) { value = arg; normalize(); return(*this); }; + AngSignPi& operator+=(direction_t const &arg) { value += arg; normalize(); return(*this); }; + AngSignPi& operator-=(direction_t const &arg) { value -= arg; normalize(); return(*this); }; + AngSignPi& operator*=(direction_t const &arg) { value *= arg; normalize(); return(*this); }; + AngSignPi& operator/=(direction_t const &arg) { value /= arg; normalize(); return(*this); }; + + operator direction_t() const { return value; }; //!< conversion operator for going back to the primitive type + +protected: + void normalize(); //!< modifies #value to put it back in range + direction_t value; //!< holds the angle, should be kept normalized at all times +}; + +//! Angular distance: value is between 0 and pi +AngPi angdist(AngSignPi const &arg1, AngSignPi const &arg2); + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ODataFormats.h ./Shared/ODataFormats.h --- ../Tekkotsu_3.0/Shared/ODataFormats.h 2005-02-02 13:22:29.000000000 -0500 +++ ./Shared/ODataFormats.h 2007-11-12 23:16:03.000000000 -0500 @@ -14,7 +14,7 @@ typedef unsigned char byte; typedef unsigned short word; -typedef unsigned long longword; +typedef unsigned int longword; typedef word OSoundFormat; const OSoundFormat osoundformatUNDEF = 0; const OSoundFormat osoundformatPCM = 1; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ParticleFilter.h ./Shared/ParticleFilter.h --- ../Tekkotsu_3.0/Shared/ParticleFilter.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/ParticleFilter.h 2007-11-10 17:58:10.000000000 -0500 @@ -0,0 +1,625 @@ +#ifndef INCLUDED_ParticleFilter_h +#define INCLUDED_ParticleFilter_h + +#include +#include +#include +#include +#include + +//! Provides a common base class for particles used by the ParticleFilter +/*! Each particle represents a hypothesis regarding a position in state space. + * The state space being modeled is defined by the fields tracked by + * the particles, a sensor model which evaluates the 'health' of each particle + * based on incoming information from the world, and a motion model + * which updates particles based on the robot's own changes to the world. + * + * For a common example, see the LocalizationParticle for + * tracking a robot's position and orientation in a 2D world. + * + * The default LowVarianceResamplingPolicy has two requirements for + * particles. One requirement is that all particle implementations must + * define a 'DistributionPolicy' (usually via typedef within your class) so + * that the resampler can create randomly generated particles and + * modify existing ones. (see ParticleFilter::DistributionPolicy) + * + * The second requirement is that all particles provide a public 'weight' + * field so that particles can be compared. The recommended way to do + * this is to inherit from this ParticleBase base class. However, since + * templates are used to specify the particle type to the particle filter, + * you can use an unaffiliated class as long as it provides a weight member. + * (However, inheritance is still recommended so you'll automatically pick up + * any changes or new requirements made to this base class.) + * + * The final requirement of the ParticleFilter itself is to provide a + * sumSqErr() function so that a confidence interval can be computed. + * However, the meaning of the value returned by this function is entirely + * up to you. The base class provides a prototype for the function, but + * its implementation is abstract.*/ +class ParticleBase { +public: + //! constructor + ParticleBase() : weight(0) {} + //! destructor + virtual ~ParticleBase() {}; + + //! returns the sum squared error between this particle and @a p + /*! This is only used to compute the confidence of the particle filter, + * you may want to weight some dimensions differently if they tend + * to have smaller values or are more important. How you interpret + * ParticleFilter::confidence() depends on how this function is implemented. + * + * A template is used so you can assume the argument type is that + * of your own particle type. (it doesn't really make sense to compare + * the distance between particles of different types.) */ + template float sumSqErr(const ParticleT& p) const=0; + + //! indicates the 'health' of the particle -- the bigger the value, the better this particle + /*! Generally weights are indicative of probability, but are often unnormalized + * since the normalization factor is constant across particles and thus doesn't + * affect matters of relative comparison. + * + * Further, weights tend to be very small as the accumulation of a number of + * sensor values tend to be each somewhat unlikely, and taken together + * the particle's weight shrinks exponentially. Thus it useful to work in + * log space to avoid numeric underflow on the range of a floating point value. + * This also has the advantage of transforming multiplication operations to + * slightly quicker addition operations. The default LowVarianceResamplingPolicy + * has a logWeights member so you can indicate whether weight values + * should be interpreted logarithmically (i.e. negative values) + * or linearly (e.g. positive (and generally very small) values). (default is logarithmic) */ + float weight; +}; + +//! Implements a particle filter with support for a variety of applications through the usage of arbitrary combination of a variety of models and policies +/*! The particle type is passed as a template parameter, which provides the implementation + * advantage of being able to directly store arrays of particles as contiguous blocks in memory. This allows + * better cache coherency and enables platform-specific acceleration tricks, such as SIMD calls. + * + * There are a number of embedded classes which together form the implementation of the + * particle filter. The advantage of this architecture is that you can mix and match any + * combination of modules to get the features needed for your application. + * - SensorModel: pass one of these to updateSensors in order to evaluate the particles + * as new information is discovered. You may have several different sensors at the same + * time, simply create a model for each type of sensor, and pass it to the filter when updated. + * - MotionModel: modifies particle states based on the expected outcome of + * any controls you might have over the system. See DeadReckoningBehavior for an example. + * Generally, you will install one motion model, and this model will be given a opportunity + * to update expected particle state before each sensor update. (unless you pass 'false' + * to updateSensors()). MotionModel can be NULL if you have no control over the system. + * - DistributionPolicy: defines how to generate random particles and "jiggle" existing ones. + * The default DistributionPolicy is usually specified via a typedef in the particle itself, and + * is stored as a property of the ResamplingPolicy (next item) since that is what will use it. + * - ResamplingPolicy: Following a sensor update, you may wish to re-evaluate the particles + * in use, making copies of the "good" particles, and dropping those which are not matching + * sensor values. If you receive a group of different sensor readings, you may want to + * hold off on resampling until they have all been applied for better evaluation of the particles + * before selecting which to replicate. Similarly, if your sensors are noisy, you may want to + * take several readings before allowing resampling so you don't kill off all the "good" particles + * based on a bad reading. Pass 'false' to updateSensors() or use the delayCount parameter of + * LowVarianceResamplingPolicy. The resampling policy can be 'NULL' if you never want to + * resample, but it defaults to an instance of LowVarianceResamlingPolicy. + * + * Generally, preparing to use a particle filter requires these prerequisites: + * - write your particle class and its associated distribution policy + * (see LocalizationParticle and LocalizationParticleDistributionPolicy) + * - write a sensor model to evaluate particles using sensors you'll have available + * (see DualCoding::ShapeSensorModel) + * - write a motion model if you have any knowledge of modifications to the state + * (see HolonomicMotionModel and DeadReckoningBehavior) + * + * Once these are available, usage goes something like this: + * -# create particle filter, optionally passing motion model and/or resampling policy + * -# customize parameters for resampling and distribution policies + * -# while active (note these are all "as needed", in no particular order): + * - update motion model whenever there's a change in controls (e.g. call setVelocity() on + * a HolonomicMotionModel) + * - create/pass SensorModel(s) for any measurements obtained (e.g. call updateSensors() + * on the particle filter) + * - query getBestParticle() on the particle filter to obtain current state estimate + * + * Remember that the particle filter takes responsibility for deallocating all policies and the + * motion model when they are removed. Do not attempt to reuse them between particle + * filters. SensorModels are the only exception -- they are @e not retained between calls + * to updateSensors, so you can reuse them. + */ +template +class ParticleFilter { +public: + typedef ParticleT particle_type; //!< redefinition here allows reference to the particle type even if the template parameter may be abstracted away due to a typedef + typedef typename std::vector particle_collection; //!< the collection type we'll be using to store the particles + typedef typename particle_collection::size_type index_t; //!< index type for refering to particles within the collection + + //! A sensor model is used to update particle weights to account based on each particle's ability to explain observations taken from the system + class SensorModel { + public: + typedef ParticleT particle_type; //!< redefinition here allows reference to the particle type even if the template parameter may be abstracted away due to a typedef + typedef typename std::vector particle_collection; //!< the collection type we'll be using to store the particles + typedef typename particle_collection::size_type index_t; //!< index type for refering to particles within the collection + virtual ~SensorModel() {} //!< destructor (no-op for base class) + + //! once passed to the particle filter's updateSensors(), this will be called to allow the sensor model to update the 'weight' member of each particle + /*! @param particles the current set of particles to be evaluated + * @param[in] bestIndex on input, this will hold the index within @a particles of the particle with the highest weight. + * @param[out] bestIndex on return, your function should update the parameter so it still indicates the best particle + * + * Remember to @e update each particle's weight, don't overwrite it. In other words, + * you want to combine (e.g. add or multiply) the weight from the current sensor evaluation + * with the weight currently stored in each particle, don't just replace it. This is because + * there may be several sensor updates between resamplings so that particles can be + * more accurately evaluated. */ + virtual void evaluate(particle_collection& particles, index_t& bestIndex)=0; + }; + + //! A motion model is retained by the particle filter to query before evaluating sensor measurements so all known influences are accounted for before testing the particles + /*! It's a good idea to apply noise to the motion model depending on the precision of the model. + * This allows the particle cluster to spread over time until new information is obtained to + * to evaluate how accurate the motion really was, at which point resampling will collapse + * the cluster back down again. */ + class MotionModel { + public: + typedef ParticleT particle_type; //!< redefinition here allows reference to the particle type even if the template parameter may be abstracted away due to a typedef + typedef typename std::vector particle_collection; //!< the collection type we'll be using to store the particles + typedef typename particle_collection::size_type index_t; //!< index type for refering to particles within the collection + virtual ~MotionModel() {} //!< destructor + + //! The particle filter will call these when it wants to update particle state values to account for known influences + /*! See the class notes regarding the usefulness of adding noise to the control parameters (or their effects) */ + virtual void updateMotion(particle_collection& particles)=0; + }; + + //! A distribution policy provides the ability to randomize ("redistribute") or tweak the values of a group of particles + /*! Unlike the other particle filter helper classes, the functions for the distribution policy + * operate on a subset of the particles at a time. + * You may wonder why the randomize() and jiggle() functions aren't simply made methods + * of the ParticleBase class. The main reason is that these functions may need additional + * parameters, such as specification of how large an area to distribute over, and these + * parameters are static across particles. However, if they were actually static members + * of the particle class, then the values would be shared by all particle filters. By making + * a separate class to hold the parameters and apply the one-to-many relationship, you + * can have multiple particle filters with the same type of particle, and each filter can have + * different parameter values controlling distribution of its particles. + * + * Note that the DistributionPolicy is actually a property of the resampling policy, not + * directly of the particle filter itself. */ + class DistributionPolicy { + public: + typedef ParticleT particle_type; //!< redefinition here allows reference to the particle type even if the template parameter may be abstracted away due to a typedef + typedef typename std::vector particle_collection; //!< the collection type we'll be using to store the particles + typedef typename particle_collection::size_type index_t; //!< index type for refering to particles within the collection + virtual ~DistributionPolicy() {} //!< destructor + + //! This should redistribute the particles over a large area, independently of the particle's current value + /*! Randomization occurs whenever the particle filter doesn't have any usable particles for + * replication, either because the particle filter has just been created and doesn't have any + * information yet, or because new sensor readings have invalidated all of the current particles. */ + virtual void randomize(particle_type* begin, index_t num)=0;// { particle_type* end=begin+num; while(begin!=end) (begin++)->randomize(); } + + //! This should slightly modify the particles' state values + /*! @param var indicates the scale of the variance desired -- multiply whatever variance you use for modifying each state parameter by this value + * @param begin the first particle in the array + * @param num the number of particles to apply the operation to + * + * This function is called on particles which have been replicated from an existing + * particle to explore the space around that particle. The more accurate your + * sensors and particle evaluation, the smaller the jiggle variance can be. */ + virtual void jiggle(float var, particle_type* begin, index_t num)=0;// { particle_type* end=begin+num; while(begin!=end) (begin++)->jiggle(var); } + }; + + //! The resampling policy focuses the particle filter on those particles which are performing well, and dropping those which are poorly rated + /*! Resampling should replicate particles proportionally to how well their weights compare + * to other particles in the filter. The process is similar to a genetic algorithm. + * This process typically does not vary between applications, + * so you will probably want to use the supplied LowVarianceResamplingPolicy, and + * simply tweak parameters as needed. + * + * The ResamplingPolicy interface includes a DistributionPolicy so particles can be + * randomly generated or modified in an abstract manner. */ + class ResamplingPolicy { + public: + typedef ParticleT particle_type; //!< redefinition here allows reference to the particle type even if the template parameter may be abstracted away due to a typedef + typedef typename std::vector particle_collection; //!< the collection type we'll be using to store the particles + typedef typename particle_collection::size_type index_t; //!< index type for refering to particles within the collection + + //! constructor, creates a DistributionPolicy based on the particle_type's own DistributionPolicy typedef + ResamplingPolicy() : dist(new typename particle_type::DistributionPolicy) {} + //! constructor, pass your own custom distribution policy (responsibility for deallocation is assumed by the ResamplingPolicy) + explicit ResamplingPolicy(DistributionPolicy * distPolicy) : dist(distPolicy) {} + //! destructor + virtual ~ResamplingPolicy() { delete dist; }; + //! the particle filter will call resample() when the particles have been evaluated and are ready to be selected + virtual void resample(particle_collection& particles, index_t& bestIndex)=0; + //! replaces #dist with a new distribution policy. If you pass NULL, #dist will be reset to the particle_type's default distribution policy, as specified by a 'DistributionPolicy' typedef within the particle class + virtual void setDistributionPolicy(DistributionPolicy * distPolicy) { + delete dist; + dist = (distPolicy!=NULL) ? distPolicy : new typename particle_type::DistributionPolicy; + } + //! returns the currently active distribution policy (#dist) + virtual DistributionPolicy& getDistributionPolicy() const { return *dist; } + protected: + //! a pointer to the current distribution policy, which cannot be NULL + DistributionPolicy * dist; + private: + ResamplingPolicy(const ResamplingPolicy& rp); //!< copy unsupported + ResamplingPolicy& operator=(const ResamplingPolicy& rp); //!< assignment unsupported + }; + + //! This class provides a generic, default ResamplingPolicy. It is based on the low variance resampling policy algorithm found in "Probabilistic Robotics" by Sebastian Thrun, Wolfram Burgard, Dieter Fox + /*! This class is called "low variance" because it will maintain particle modalities in the face of + * uniform weighting. This means that if resamples are triggered when no new information + * is available, every particle is resampled for the next generation. This prevents the eventual + * convergence of particle clusters over time. + * + * However, this implementation provides a #varianceScale parameter for adding variance + * to the particle's state on each generation, which can be useful for more rapidly exploring + * the state space around a "winning" particle. Ideally, it is better to use a very low resampling + * variance, and rely on noise in the motion model and a broad probability distribution in + * the sensor model to allow particles to spread. #varianceScale is really a crutch to manage + * an overconfident sensor model (one which weights "correct" particles with sharply higher values). + * + * The #varianceScale parameter defaults to a negative value, which indicates the + * resampling variance will be scaled with particle weight to provide broader sampling when + * particle weights are poor, and tighten sampling when particles are tracking accurately. This + * requires setting a value for #minAcceptableWeight, described next. + * + * The other trick this implementation provides is specification of a minimum acceptable + * particle weight (#minAcceptableWeight). If the best particle's weight is below this value, + * new, randomly generated particles will be created, up to #maxRedistribute percent of + * the particles on a round of resampling. This handles situations where the actual state + * has somehow jumped out of the region being sampled by the particles, and the filter is "lost". + * Without some further information (i.e. fixing the MotionModel to predict the "kidnapping"), + * this can provide automatic re-acquisition of the position in state space. (at the cost of + * spawning new modalities) + * + * Finally, #resampleDelay is provided to limit actual resampling to one in every #resampleDelay + * attempts. This allows you to only resample at a lower frequency than the sensor model, + * without having to manually track the number of sensor samples and pass a parameter to + * the ParticleFilter::updateSensors() to limit resampling yourself. The reason you would + * want to limit the resampling frequency is to better evaluate the particles before selecting + * them for replication or pruning -- if your sensors are noisy and you resample too often, + * bad values will kill off good particles on a regular basis, causing the filter to continually be "lost". + * + * This policy can interpret weights in either "log space" or "linear space". It defaults to "log space", + * but if your sensor model is providing linear weights, set #logWeights to false. + */ + class LowVarianceResamplingPolicy : public ResamplingPolicy { + public: + //! constructor + LowVarianceResamplingPolicy() + : varianceScale(-2), maxRedistribute(1/2.f), minAcceptableWeight(-FLT_MAX), + logWeights(true), resampleDelay(0), newParticles(), resampleCount(0) + {} + virtual void resample(particle_collection& particles, index_t& bestIndex); + + //! returns true if the next call to resample will trigger a "real" resampling (is #resampleCount greater than #resampleDelay?) + bool nextResampleIsFull() { return resampleCount>=resampleDelay; } + + //! If non-negative, passed to the DistributionPolicy's jiggle() for replicated particles; otherwise an "automatic" value is used which inversely scales with the best particle weight + /*! A negative value is still used to control the maximum magnitude of the resampling variance. + * It's better to keep this small (or zero) and rely on the sensor and motion model's noise parameters */ + float varianceScale; + //! A percentage (0-1) of the particles which can be randomly re-distributed on a single resampling if the best particle's weight is below #minAcceptableWeight + float maxRedistribute; + //! The lowest weight per resample attempt to consider "acceptable" + /*! This is scaled by resampleDelay when being compared to particle weights, so that + * you don't have to adjust this parameter when you increase resampleDelay. + * As the best particle weight drops below this value, more particles will be randomly + * redistributed, up to #maxRedistribute. */ + float minAcceptableWeight; + //! This controls the interpretation of particle weights. If true, they are interpreted as "log space", otherwise "linear space" + bool logWeights; + //! This indicates how many resampling attempts should be skipped before actually doing it. See class notes for rationale. + unsigned int resampleDelay; + protected: + particle_collection newParticles; //!< temporary scratch space as particles are created, and then the collections are swapped + unsigned int resampleCount; //!< the number of resampling attempts which have occurred. + }; + + + //! Constructor for the particle filter, specify number of particles and optionally pass a motion model and resampling policy + /*! The particle filter assumes responsibility for eventual deallocation of the motion model and resampling policy */ + explicit ParticleFilter(unsigned int numParticles, MotionModel* mm=NULL, ResamplingPolicy* rs=new LowVarianceResamplingPolicy) + : particles(numParticles), bestIndex(0), motion(mm), resampler(rs), hasEvaluation(false) + { + if(numParticles>0) + resetFilter(particles.front().weight); + } + + //! Destructor + virtual ~ParticleFilter() { delete motion; delete resampler; } + + //! Returns the current motion model (#motion) + virtual MotionModel * getMotionModel() const { return motion; } + //! Reassigns the motion model, deleting the old one; motion model can be NULL + virtual void installMotionModel(MotionModel* mm) { delete motion; motion=mm; } + + //! Returns the current resampling policy (#resampler) + virtual ResamplingPolicy * getResamplingPolicy() const { return resampler; } + //! Reassigns the resampling policy, deleting the old one; resampling policy can be NULL (although not recommended...) + virtual void installResamplingPolicy(ResamplingPolicy* rs) { delete resampler; resampler=rs; } + + //! Sets the resampling policy's resampleDelay, which controls how many sensor updates to process before resampling the particles; policy must be a LowVarianceResamplingPolicy + virtual void setResampleDelay(unsigned int d) { + LowVarianceResamplingPolicy* p = dynamic_cast(getResamplingPolicy()); + if ( p ) + p->resampleDelay = d; + else + std::cout << "Warning: setResampleDelay found getResamplingPolicy() returns wrong type policy; resampleDelay not set." << std::endl; + } + + //! Sets the resampling policy's minimum acceptable weight for a particle; policy must be a LowVarianceResamplingPolicy + virtual void setMinAcceptableWeight(float w) { + LowVarianceResamplingPolicy* p = dynamic_cast(getResamplingPolicy()); + if ( p ) + p->minAcceptableWeight = w; + else + std::cout << "Warning: setMinAcceptableWeight found getResamplingPolicy() returns wrong type policy; minAcceptableWeight not set." << std::endl; + } + + //! If getResamplingPolicy() returns a LowVarianceResamplingPolicy instance, this will set LowVarianceResamplingPolicy::maxRedistribute; otherwise will display a warning + virtual void setMaxRedistribute(float r) { + LowVarianceResamplingPolicy* p = dynamic_cast(getResamplingPolicy()); + if ( p ) + p->maxRedistribute = r; + else + std::cout << "Warning: setMaxRedistribute found getResamplingPolicy() returns wrong type policy; maxRedistribute not set." << std::endl; + } + + //! If getResamplingPolicy() returns a LowVarianceResamplingPolicy instance, this will set LowVarianceResamplingPolicy::varianceScale; otherwise will display a warning + virtual void setVarianceScale(float s) { + LowVarianceResamplingPolicy* p = dynamic_cast(getResamplingPolicy()); + if ( p ) + p->varianceScale = s; + else + std::cout << "Warning: setVarianceScale found getResamplingPolicy() returns wrong type policy; varianceScale not set." << std::endl; + } + + + //! Allows you to manually request a position update -- you might want to call this before using getBestParticle's state information + virtual void updateMotion() { + if(motion!=NULL) + motion->updateMotion(particles); + } + + //! Applies the sensor model's evaluation to the particles, optionally updating the motion model and resampling first + /*! If you are applying a group of sensor readings, you probably only want to update motion for the first one + * (since no motion is occuring between the readings if they were taken at the same time), and may + * want to hold off on resampling until the end (so the particles are better evaluated). + * If using the default LowVarianceResamplingPolicy, see also LowVarianceResamplingPolicy::resampleDelay. */ + virtual void updateSensors(SensorModel& sm, bool updateMot=true, bool doResample=true) { + if(updateMot) + updateMotion(); + if(doResample && hasEvaluation) + resample(); + sm.evaluate(particles, bestIndex); + hasEvaluation=true; + } + + //! A manual call to trigger resampling + virtual void resample() { + if(resampler!=NULL) + resampler->resample(particles,bestIndex); + hasEvaluation=false; + } + + //! Assigns the specified weight value to all of the particles + virtual void resetWeights(float w) { + for(typename particle_collection::iterator it=particles.begin(); it!=particles.end(); ++it) + it->weight=w; + hasEvaluation=false; + } + //! Requests that the resampler's distribution policy randomly distribute all of the particles, and reset weights to @a w. + /*! You might want to do this if you believe you have been "kidnapped" by some unmodeled motion + * to a new area of state space, and need to restart the filter to determine the new location. */ + virtual void resetFilter(float w) { + if(resampler!=NULL) + resampler->getDistributionPolicy().randomize(&particles[0],particles.size()); + resetWeights(w); + } + + virtual index_t getBestIndex() const { return bestIndex; } //!< Returns the index of the best particle in #particles + virtual const particle_type& getBestParticle() const { return particles[bestIndex]; } //!< Returns a reference to the best particle in #particles + virtual particle_collection& getParticles() { return particles; } //!< Returns a reference to #particles itself (if you want to modify the particles, generally better to formulate it in terms of a sensor model or motion model for consistency) + virtual const particle_collection& getParticles() const { return particles; } //!< Returns a reference to #particles itself (if you want to modify the particles, generally better to formulate it in terms of a sensor model or motion model for consistency) + + //! if you know the position in state space, pass it here, along with a positive varianceScale if you want some jiggle from the distribution policy + virtual void setPosition(const particle_type& pos, float variance=0) { + particles.assign(particles.size(),pos); + if(variance>0) + resampler->getDistributionPolicy().jiggle(variance,&particles.front(),particles.size()); + } + + //! Returns a confidence interval based on the particle_type's sumSqErr implementation (see ParticleBase::sumSqErr()) + virtual float getConfidenceInterval() const { + float d=0; + const particle_type& p=particles[bestIndex]; + for(typename particle_collection::const_iterator it=particles.begin(); it!=particles.end(); ++it) + d += it->sumSqErr(p); + return std::sqrt(d/(particles.size()-1)); + } + //! Adjusts the size of the particle collection -- more particles gives better coverage, but more computation + /*! You may wish to shrink the number of particles when the confidence interval is small or + * particle weights are high, and increase particles when the filter is getting "lost". */ + virtual void resizeParticles(unsigned int numParticles) { + std::cerr << "Resizing particles from " << particles.size() << " to " << numParticles << std::endl; + if(numParticles > particles.size()) { + index_t oldsize=particles.size(); + particles.resize(numParticles); + if(resampler!=NULL) + resampler->getDistributionPolicy().randomize(&particles[oldsize],numParticles-oldsize); + + } else if(numParticles < particles.size()) { + std::vector sorted(particles.size()); + for(unsigned int i=0; iweight < b->weight; } + + particle_collection particles; //!< storage of the particles (no particular order) + index_t bestIndex; //!< index of the currently highest-rated particle + MotionModel * motion; //!< motion model, can be NULL if you have no control or knowledge of changes in the system + ResamplingPolicy * resampler; //!< resampling policy refocuses filter on "good" particles, can be NULL but filter won't work well without a resampler + bool hasEvaluation; //!< set to true following each call to updateSensors, and false following resample() or resetWeights(); avoids repeated resamplings + +private: + ParticleFilter(const ParticleFilter&); //!< don't call (copy constructor) + ParticleFilter& operator=(const ParticleFilter&); //!< don't call (assignment operator) +}; + +template +void ParticleFilter::LowVarianceResamplingPolicy::resample(particle_collection& particles, index_t& bestIndex) { + if(resampleCount++particles.size()*2) + newParticles.resize(particles.size()); + if(particles.size()==0) + return; + + // This part figures out how many particles we're going to globally redistribute, + // leaving the rest for resampling + float bestWeight = particles[bestIndex].weight; + float redistributeRatio = 0; + if(logWeights) { + if(bestWeight<=-FLT_MAX) + redistributeRatio=1; + else { + float min=minAcceptableWeight*(resampleDelay+1); + if(bestWeight1) + redistributeRatio=1; + } + } + } else { + if(bestWeight<=0) + redistributeRatio=1; + else { + float min=std::pow(minAcceptableWeight,(float)(resampleDelay+1)); + if(bestWeight0) { + // add up the cumulative weights for each particle... + std::vector weights(particles.size()); + if(logWeights) { + weights[0]=std::exp(particles.front().weight-bestWeight); + for (unsigned int i=1; i < particles.size(); i++) + weights[i] = weights[i-1] + std::exp(particles[i].weight-bestWeight); + } else { + weights[0]=particles.front().weight/bestWeight; + for (unsigned int i=1; i < particles.size(); i++) + weights[i] = weights[i-1] + particles[i].weight/bestWeight; + } + if(weights.back()<=0) { + std::cerr << "Warning particle filter attempted resampling with weight total " << weights.back() << std::endl; + return; + } + + float r = weights.back() / numResample; // last element of weights/number of particles + float offset = r*float(rand())/RAND_MAX; + unsigned int pos = 0; + + //unsigned int lpos=0, fi=0; + for (unsigned int i=0; i < numResample; i++){ + float target = offset+r*i; // multiply instead of repeatedly adding to avoid rounding issues + while (target >= weights[pos]) { + pos++; +/*#ifdef DEBUG + if(pos>=particles.size()) { + std::cerr << std::endl << std::endl << " WTF: ParticleFilter pos past end of particles " << std::endl << std::endl << std::endl; + pos=particles.size()-1; + break; + } +#endif*/ + } + // debugging output (display which particles got sampled) + /*if(lpos!=pos) { + if(fi!=i) + std::cerr << "selected " << lpos << " x" << i-fi << " @ " << particles[lpos].weight << std::endl; + fi=i; lpos=pos; + }*/ + //std::cerr << "copying particle " << pos << " of " << particles.size() << " to position " << i << " of " << newParticles.size() << std::endl; + + // copy over particle (we'll "jiggle" it later if desired) + newParticles[i]=particles[pos]; + // keep track of index of best particle in the new list + if(newParticles[i].weight>newParticles[bestIndex].weight) + bestIndex=i; + } + // debugging output (display which particles got sampled) + //std::cerr << "selected " << lpos << " x" << numResample-fi << " @ " << particles[lpos].weight << std::endl; + + // now jiggle all of the particles we've resampled + if(varianceScale!=0) { + float vs; + if(varianceScale>=0) + vs=varianceScale; // use the user's setting + // otherwise varianceScale is negative, we'll try to pick a variance scale based on how well we're doing + else if(redistributeRatio>0) + vs=1+redistributeRatio*(-varianceScale-1); + else { + if(logWeights) { + float min=minAcceptableWeight*(resampleDelay+1); + vs=bestWeight/min; + } else { + float min=std::pow(minAcceptableWeight,(float)(resampleDelay+1)); + vs=(1-bestWeight)/(1-min); + } + //vs=std::pow(vs,4.f); + } + //std::cerr << "variance scale is " << vs << std::endl; + ResamplingPolicy::dist->jiggle(vs,&newParticles[0],numResample); + } + } + + // finished resampling, redistribute the remaining particles (if needed due to falling below minAcceptableWeight) + ResamplingPolicy::dist->randomize(&newParticles[numResample],numRedistribute); + + // reset weights + if(logWeights) { + for(typename particle_collection::iterator it=newParticles.begin(); it!=newParticles.end(); ++it) + it->weight=0; + } else { + for(typename particle_collection::iterator it=newParticles.begin(); it!=newParticles.end(); ++it) + it->weight=1; + } + + particles.swap(newParticles); // all done! swap the particle lists +} + +/*! @file +* @brief +* @author ejt (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.14 $ +* $State: Exp $ +* $Date: 2007/11/10 22:58:10 $ +*/ + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ProjectInterface.cc ./Shared/ProjectInterface.cc --- ../Tekkotsu_3.0/Shared/ProjectInterface.cc 2006-09-25 19:31:06.000000000 -0400 +++ ./Shared/ProjectInterface.cc 2007-11-11 01:18:35.000000000 -0500 @@ -6,6 +6,12 @@ namespace ProjectInterface { + //! default implementation used for #sendCommand (just displays a warning and ignores the call) + void noSendCommandErr(const std::string& cmd) { + serr->printf("command '%s' ignored because no ProjectInterface::sendCommand() is installed\n",cmd.c_str()); + } + void (*sendCommand)(const std::string& cmd)=noSendCommandErr; + bool displayException(const char * file, int line, const char * message, const std::exception* ex) { if(file!=NULL) { serr->printf("Exception caught at %s:%d => ",debuget::extractFilename(file),line); @@ -30,29 +36,37 @@ bool (*uncaughtException)(const char * file, int line, const char * message, const std::exception* ex)=&displayException; //! default implementation assigned to lookupColorIndexByName(); checks that #defSegmentedColorGenerator is non-NULL and returns getColorIndex on it - unsigned int defLookupColorIndexByName(const std::string& name) { - if(defSegmentedColorGenerator==NULL) - return -1U; - return defSegmentedColorGenerator->getColorIndex(name); + color_index defLookupColorIndexByName(const std::string& name) { + if(defSegmentedColorGenerator==NULL) + return -1U; + return defSegmentedColorGenerator->getColorIndex(name); } - unsigned int (*lookupColorIndexByName)(const std::string& name)=&defLookupColorIndexByName; + color_index (*lookupColorIndexByName)(const std::string& name)=&defLookupColorIndexByName; //! default value initially assigned to lookupColorIndexByRgb(); checks that #defSegmentedColorGenerator is non-NULL and returns getColorIndex on it - unsigned int defLookupColorIndexByRgb(const rgb rgbval) { + color_index defLookupColorIndexByRgb(const rgb rgbval) { if(defSegmentedColorGenerator==NULL) return -1U; return defSegmentedColorGenerator->getColorIndex(rgbval); } //! returns color index for color with specified "representitive" RGB color - unsigned int (*lookupColorIndexByRgb)(const rgb rgbval)=&defLookupColorIndexByRgb; + color_index (*lookupColorIndexByRgb)(const rgb rgbval)=&defLookupColorIndexByRgb; //! default implementation assigned to lookupColorRGB(); checks that #defSegmentedColorGenerator is non-NULL and returns getColorRGB on it - rgb defLookupColorRGB(unsigned int index) { + rgb defLookupColorRGB(color_index cindex) { if(defSegmentedColorGenerator==NULL) return rgb(); - return defSegmentedColorGenerator->getColorRGB(index); + return defSegmentedColorGenerator->getColorRGB(cindex); } - rgb (*lookupColorRGB)(unsigned int index)=&defLookupColorRGB; + rgb (*lookupColorRGB)(color_index cindex)=&defLookupColorRGB; + + //! default implementation assigned to lookupColorName(); checks that #defSegmentedColorGenerator is non-NULL and returns getColorName on it + const char* defLookupColorName(color_index cindex) { + if(defSegmentedColorGenerator==NULL) + return NULL; + return defSegmentedColorGenerator->getColorName(cindex); + } + const char* (*lookupColorName)(color_index cindex)=&defLookupColorName; //! default value initially assigned to lookupNumColors(); checks that #defSegmentedColorGenerator is non-NULL and returns getNumColors on it unsigned int defLookupNumColors() { @@ -63,27 +77,8 @@ //! returns the number of indexed colors which are currently defined unsigned int (*lookupNumColors)() = &defLookupNumColors; - //! displays an rgb value in the form '[r,g,b]' - std::ostream& operator<<(std::ostream &os, const rgb &rgbval) { - os << "[" << (unsigned int)rgbval.red - << "," << (unsigned int)rgbval.green - << "," << (unsigned int)rgbval.blue - << "]"; - return os; - } - - //! returns @a rgbval in the form 'r g b' - std::string toString(const rgb &rgbval) { - char buff[15]; - snprintf(buff,15,"%d %d %d",rgbval.red,rgbval.green,rgbval.blue); - return buff; - } - - - //! A collection of the various stages of vision processing. None of these are absolutely required, but are needed to run included demo behaviors and TekkotsuMon modules - /*! @name Vision Setup */ - //! pointer to generator + /*** Vision Setup ***/ FilterBankGenerator * defRawCameraGenerator=NULL; FilterBankGenerator * defInterleavedYUVGenerator=NULL; JPEGGenerator * defColorJPEGGenerator=NULL; @@ -93,11 +88,9 @@ SegmentedColorGenerator * defSegmentedColorGenerator=NULL; RLEGenerator * defRLEGenerator=NULL; RegionGenerator * defRegionGenerator=NULL; - //@} - - //! Default source IDs for the various generators; These are given default values, but you can reassign them if you like. - /*! @name Vision SIDs */ - //! source id for event + + + /*** Vision SIDs ***/ unsigned int visRawCameraSID=0; unsigned int visInterleaveSID=0; @@ -118,18 +111,17 @@ unsigned int visBlueBallSID=1; unsigned int visGreenBallSID=2; unsigned int visYellowBallSID=3; - unsigned int visHandSID=4; - //@} - - //! Allows you to request a particular layer abstractly - this isn't used by the framework, just a suggestion for clarity - /*! @name Layer Resolutions */ + unsigned int visOrangeSID=4; + unsigned int visHandSID=visOrangeSID; + + + /*** Layer Resolutions ***/ unsigned int doubleLayer=5; unsigned int fullLayer=4; unsigned int halfLayer=3; unsigned int quarterLayer=2; unsigned int eighthLayer=1; unsigned int sixteenthLayer=0; - //@} } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ProjectInterface.h ./Shared/ProjectInterface.h --- ../Tekkotsu_3.0/Shared/ProjectInterface.h 2006-07-14 02:48:55.000000000 -0400 +++ ./Shared/ProjectInterface.h 2007-06-13 14:14:14.000000000 -0400 @@ -17,7 +17,7 @@ } //! A collection of the global variables which should be set by a project to use the Tekkotsu framework -/*! This namespace a few variables needed for initialization of the +/*! This namespace hold a few variables needed for initialization of the * framework, but mainly declares variables which are used by demo * behaviors. Although the variables are declared here, and * some default values provided, it is up to your project to define @@ -52,7 +52,12 @@ * most sense to implement as a static local variable of the function. * (Each call should return the same behavior) */ BehaviorBase& startupBehavior(); - + + //! sends a command to the project, allows GUI elements of the framework to send commands to the hardware abstraction layer + /*! Generally commands are assumed to be for the Tekkostu HAL command line, + * and otherwise this will be left NULL. */ + extern void (*sendCommand)(const std::string& cmd); + //! The exception handler for exceptions which have fallen through to base Tekkotsu functions /*! You can override this to install your own handler by assigning a * new function. This defaults to displayException(), which @@ -76,32 +81,35 @@ //! allows you to override how colors are defined -- by default, this will be set to a function which passes the call to defSegmentedColorGenerator /*! As per SegmentedColorGenerator::getColorIndex(), if @a name is not valid, return -1U */ - extern unsigned int (*lookupColorIndexByName)(const std::string& name); + extern color_index (*lookupColorIndexByName)(const std::string& name); //! allows you to override how colors are defined -- by default, this will be set to a function which passes the call to defSegmentedColorGenerator - extern unsigned int (*lookupColorIndexByRgb)(const rgb rgbval); + extern color_index (*lookupColorIndexByRgb)(const rgb rgbval); //! allows you to override how colors are defined -- by default, this will be set to a function which passes the call to defSegmentedColorGenerator /*! As per SegmentedColorGenerator::getColorRGB(), if @a index is not valid, return black (rgb()) */ - extern rgb (*lookupColorRGB)(unsigned int index); + extern rgb (*lookupColorRGB)(color_index cindex); + //! allows you to override how colors are defined -- by default, this will be set to a function which passes the call to defSegmentedColorGenerator + /*! As per SegmentedColorGenerator::getColorRGB(), if @a index is not valid, return black (rgb()) */ + extern const char* (*lookupColorName)(color_index cindex); //! Returns the index corresponding to a color of specified name by calling lookupColorIndexByName() /*! As per SegmentedColorGenerator::getColorIndex(), if @a name is not valid, return -1U */ - inline unsigned int getColorIndex(const std::string& name) { if(lookupColorIndexByName==NULL) return -1U; return (*lookupColorIndexByName)(name); } + inline color_index getColorIndex(const std::string& name) { if(lookupColorIndexByName==NULL) return -1U; return (*lookupColorIndexByName)(name); } //! Returns the index corresponding to an rgb value by calling lookupColorIndexByRgb() - inline unsigned int getColorIndex(const rgb rgbval) { if(lookupColorIndexByRgb==NULL) return -1U; return (*lookupColorIndexByRgb)(rgbval); } + inline color_index getColorIndex(const rgb rgbval) { if(lookupColorIndexByRgb==NULL) return -1U; return (*lookupColorIndexByRgb)(rgbval); } //! Returns rgb value corresponding to a color of specified name by calling lookupColorRGB(lookupColorIndexByName()) /*! As per SegmentedColorGenerator::getColorRGB(), if @a name is not valid, return black (rgb()) */ inline rgb getColorRGB(const std::string& name) { if(lookupColorIndexByName==NULL || lookupColorRGB==NULL) return rgb(); return (*lookupColorRGB)((*lookupColorIndexByName)(name)); } //! Returns rgb value corresponding to a color of specified name by calling lookupColorRGB() /*! As per SegmentedColorGenerator::getColorRGB(), if @a index is not valid, return black (rgb()) */ - inline rgb getColorRGB(unsigned int index) { if(lookupColorRGB==NULL) return rgb(); return (*lookupColorRGB)(index); } - - extern unsigned int (*lookupNumColors)(); - //! Returns the number of colors, obtained from defSegmentedColorGenerator - inline unsigned int getNumColors() { if (lookupNumColors == NULL) return -1U; return (*lookupNumColors)(); } - - std::ostream& operator<<(std::ostream &os, const rgb &rgbval); - std::string toString(const rgb &rgbval); + inline rgb getColorRGB(color_index cindex) { if(lookupColorRGB==NULL) return rgb(); return (*lookupColorRGB)(cindex); } + //! Returns color name corresponding to specified color index by calling lookupColorName() + /*! As per SegmentedColorGenerator::getColorName(), if @a index is not valid, return NULL */ + inline const char* getColorName(color_index cindex) { if(lookupColorName==NULL) return NULL; return (*lookupColorName)(cindex); } + + extern unsigned int (*lookupNumColors)(); + //! Returns the number of colors, obtained from defSegmentedColorGenerator + inline unsigned int getNumColors() { if (lookupNumColors == NULL) return -1U; return (*lookupNumColors)(); } //! A collection of the various stages of vision processing. None of these are absolutely required, but are needed to run included demo behaviors and TekkotsuMon modules /*! @name Vision Setup */ @@ -119,7 +127,7 @@ //! Default source IDs for the various generators; These are given default values, but you can reassign them if you like. /*! @name Vision SIDs */ - //! source id for event + //! source id for vision events from the corresponding pipeline stage or object detector extern unsigned int visRawCameraSID; extern unsigned int visInterleaveSID; extern unsigned int visColorJPEGSID; @@ -133,7 +141,8 @@ extern unsigned int visBlueBallSID; extern unsigned int visGreenBallSID; extern unsigned int visYellowBallSID; - extern unsigned int visHandSID; + extern unsigned int visOrangeSID; + extern unsigned int visHandSID; //!< synonym for #visOrangeSID //@} //! Allows you to request a particular layer abstractly - this isn't used by the framework, just a suggestion for clarity diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/QBotPlusInfo.h ./Shared/QBotPlusInfo.h --- ../Tekkotsu_3.0/Shared/QBotPlusInfo.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/QBotPlusInfo.h 2007-11-18 01:47:04.000000000 -0500 @@ -0,0 +1,246 @@ +//-*-c++-*- +#ifndef INCLUDED_QBotPlusInfo_h +#define INCLUDED_QBotPlusInfo_h + +#include +#include +#include "CommonInfo.h" +using namespace RobotInfo; + +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_QBOTPLUS) +# define TGT_IS_QWERK +# define TGT_HAS_WHEELS 2 +# define TGT_HAS_LEDS 10 +# define TGT_HAS_CAMERA 1 +# define TGT_HAS_HEAD 1 +#endif + +namespace QBotPlusInfo { + + // ******************************* + // ROBOT CONFIGURATION + // ******************************* + + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs + + const unsigned int FrameTime=15; //!< time between frames in the motion system (milliseconds) + const unsigned int NumFrames=1; //!< the number of frames per buffer (don't forget also double buffered) + const unsigned int SoundBufferTime=32; //!< the number of milliseconds per sound buffer... I'm not sure if this can be changed + + //!@name Output Types Information + const unsigned NumWheels = 2; + + const unsigned JointsPerArm = 0; + const unsigned NumArms = 0; + const unsigned NumArmJoints = JointsPerArm*NumArms; + + const unsigned JointsPerLeg = 0; //!< The number of joints per leg + const unsigned NumLegs = 0; //!< The number of legs + const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs + const unsigned NumHeadJoints = 2; //!< The number of joints in the neck + const unsigned NumTailJoints = 0; //!< The number of joints assigned to the tail + const unsigned NumMouthJoints = 0; //!< the number of joints that control the mouth + const unsigned NumEarJoints = 0; //!< The number of joints which control the ears (NOT per ear, is total) + const unsigned NumButtons = 0; //!< the number of buttons that are available, 2 head, 4 paws, 3 back, 1 underbelly see ERS7Info::ButtonOffset_t + const unsigned NumSensors = 5; //!< the number of sensors available + const unsigned NumLEDs = 10; //!< The number of LEDs which can be controlled + const unsigned NumFacePanelLEDs = 0; //!< The number of face panel LEDs + + const unsigned NumPIDJoints = NumWheels + NumArmJoints + NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints; //!< The number of joints which use PID motion - everything except ears + const unsigned NumOutputs = NumPIDJoints + NumLEDs; //!< the total number of outputs + const unsigned NumReferenceFrames = NumOutputs + 1 + NumArms + 1; //!< for the base, gripper (* NumArms), and camera reference frames + + // webcam ? + const float CameraHorizFOV=56.9/180*M_PI; //!< horizontal field of view (radians) + const float CameraVertFOV=45.2/180*M_PI; //!< vertical field of view (radians) + const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV + const unsigned int CameraResolutionX=320; //!< the number of pixels available in the 'full' layer + const unsigned int CameraResolutionY=240; //!< the number of pixels available in the 'full' layer + //@} + + + // ******************************* + // OUTPUT OFFSETS + // ******************************* + + //!Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file + //!@name Output Offsets + + + const unsigned PIDJointOffset = 0; //!< The beginning of the PID Joints + const unsigned WheelOffset = PIDJointOffset; + const unsigned HeadOffset = WheelOffset+NumWheels; //!< the offset of the beginning of the head joints, add TPROffset_t to get specific joint + + const unsigned LEDOffset = PIDJointOffset + NumPIDJoints; //!< the offset of LEDs in WorldState::outputs and MotionCommand functions, see LedOffset_t for specific offsets + + const unsigned BaseFrameOffset = NumOutputs; //!< Use with kinematics to refer to base reference frame + const unsigned CameraFrameOffset = BaseFrameOffset + 1; //!< Use with kinematics to refer to camera reference frame + + //! The offsets of appendages with pan (heading), tilt (elevation), note that this should be added to HeadOffset, otherwise use HeadOffset_t (#HeadPanOffset and #HeadTiltOffset) + enum TPROffset_t { + PanOffset = 0, //!< pan/heading (horizontal) + TiltOffset, //!< tilt/elevation (vertical) + NodOffset = TiltOffset //!< replicated tilt (could be left undefined instead...) + }; + + //! These are 'absolute' offsets for the neck joints, don't need to add to HeadOffset like TPROffset_t values do + enum HeadOffset_t { + HeadPanOffset = HeadOffset, //!< pan/heading (horizontal) + HeadTiltOffset, //!< tilt/elevation (vertical) + }; + + //! 'Absolute' offsets for each of the wheels + enum WheelOffset_t { + LWheelOffset=WheelOffset, + RWheelOffset + }; + + //! The offsets of the individual LEDs -- except the qwerk board doesn't have any particularly symbolic LEDs, just use numeric values... + /*! @hideinitializer */ + enum LEDOffset_t { }; + + typedef unsigned int LEDBitMask_t; //!< So you can be clear when you're refering to a LED bitmask + //! LEDs for the face panel (all FaceLEDPanelMask<<(0:NumFacePanelLEDs-1) entries) + const LEDBitMask_t FaceLEDMask = 0; + //! selects all of the leds + const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; + //@} + + + // ******************************* + // INPUT OFFSETS + // ******************************* + + + //! The order in which inputs should be stored + //!@name Input Offsets + + //! holds offsets to different buttons in WorldState::buttons[] + /*! Should be a straight mapping to the ButtonSourceIDs + * + * Note that the chest (power) button is not a normal button. It kills + * power to the motors at a hardware level, and isn't sensed in the + * normal way. If you want to know when it is pressed (and you are + * about to shut down) see PowerSrcID::PauseSID. + * + * @see WorldState::buttons @see ButtonSourceID_t + * @hideinitializer */ + enum ButtonOffset_t { }; + + //! Provides a string name for each button + const char* const buttonNames[NumButtons+1] = { NULL }; // non-empty array to avoid gcc 3.4.2 internal error + + //! holds offset to different sensor values in WorldState::sensors[] + /*! @see WorldState::sensors[] */ + enum SensorOffset_t { BatteryVoltage }; + + //! Provides a string name for each sensor + const char* const sensorNames[NumSensors] = { + "BatteryVoltage", + "analogInValues0", + "analogInValues1", + "analogInValues2", + "analogInValues3" + }; + + //@} + + + //! Names for each of the outputs + const char* const outputNames[NumOutputs] = { + "WHEEL:L", + "WHEEL:R", + "NECK:pan", + "NECK:nod", + "LED:00000", + "LED:00001", + "LED:00002", + "LED:00003", + "LED:00004", + "LED:00005", + "LED:00006", + "LED:00007", + "LED:00008", + "LED:00009" + }; + + //! provides polymorphic robot capability detection/mapping + class QBotPlusCapabilities : public Capabilities { + public: + //! constructor + QBotPlusCapabilities() + : Capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs) + { + // alias neck tilt to "nod" + outputToIndex["NECK:tilt"]=HeadTiltOffset; + } + }; + //! allocation declared in RobotInfo.cc + extern QBotPlusCapabilities capabilities; + + //! This table holds the default PID values for each joint. see PIDMC + const float DefaultPIDs[NumPIDJoints][3] = { + {1,0,0}, + {1,0,0}, + {1,0,0}, + {1,0,0} + }; + + //!These values are our recommended maximum joint velocities, in rad/ms + /*! a value <= 0 means infinite speed (e.g. LEDs) + * + * These limits are not enforced by the framework. They are simply available for you to use as you see fit. + * HeadPointerMC and PostureMC are primary examples of included classes which do respect these values (although they can be overridden) + * + * These values were obtained from the administrators of the Sony OPEN-R BBS */ + const float MaxOutputSpeed[NumOutputs] = { + 1e-3, //Wheels: left, right + 1e-3, + 3.14e-3, // Neck: tilt, pan + 6.28e-3, + + 0,0,0,0,0,0,0,0,0,0 // LED + }; + + #ifndef RAD + //!Just a little macro for converting degrees to radians + #define RAD(deg) (((deg) * M_PI ) / 180.0) + //!a flag so we undef these after we're done - do you have a cleaner solution? + #define __RI_RAD_FLAG + #endif + + //! This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + const double outputRanges[NumOutputs][2] = + { + { -1 , 1 }, + { -1 , 1 }, + { RAD(-90) , RAD(90) }, + { RAD(-90) , RAD(90) }, + + // LED + {0,1}, {0,1}, {0,1}, {0,1}, {0,1}, + {0,1}, {0,1}, {0,1}, {0,1}, {0,1} + }; + + //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + /*! Same as #outputRanges, don't know actual values because they were never specified by Sony */ + const double mechanicalLimits[NumOutputs][2] = + { + { -1 , 1 }, + { -1 , 1 }, + { RAD(-90) , RAD(90) }, + { RAD(-90) , RAD(90) }, + + // LED + {0,1}, {0,1}, {0,1}, {0,1}, {0,1}, + {0,1}, {0,1}, {0,1}, {0,1}, {0,1} + }; + +#ifdef __RI_RAD_FLAG +#undef RAD +#undef __RI_RAD_FLAG +#endif +} + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/QwerkInfo.h ./Shared/QwerkInfo.h --- ../Tekkotsu_3.0/Shared/QwerkInfo.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/QwerkInfo.h 2007-11-18 01:47:05.000000000 -0500 @@ -0,0 +1,232 @@ +//-*-c++-*- +#ifndef INCLUDED_QwerkInfo_h +#define INCLUDED_QwerkInfo_h + +#include +#include +#include "CommonInfo.h" +using namespace RobotInfo; + +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_QWERK) +# define TGT_IS_QWERK +# define TGT_HAS_WHEELS 4 +# define TGT_HAS_LEDS 10 +#endif + +namespace QwerkInfo { + + // ******************************* + // ROBOT CONFIGURATION + // ******************************* + + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs + + const unsigned int FrameTime=15; //!< time between frames in the motion system (milliseconds) + const unsigned int NumFrames=1; //!< the number of frames per buffer (don't forget also double buffered) + const unsigned int SoundBufferTime=32; //!< the number of milliseconds per sound buffer... I'm not sure if this can be changed + + //!@name Output Types Information + const unsigned NumWheels = 4; + + const unsigned JointsPerArm = 0; + const unsigned NumArms = 0; + const unsigned NumArmJoints = JointsPerArm*NumArms; + + const unsigned JointsPerLeg = 0; //!< The number of joints per leg + const unsigned NumLegs = 0; //!< The number of legs + const unsigned NumLegJoints = JointsPerLeg*NumLegs; //!< the TOTAL number of joints on ALL legs + const unsigned NumHeadJoints = 0; //!< The number of joints in the pantilt + const unsigned NumTailJoints = 0; //!< The number of joints assigned to the tail + const unsigned NumMouthJoints = 0; //!< the number of joints that control the mouth + const unsigned NumEarJoints = 0; //!< The number of joints which control the ears (NOT per ear, is total) + const unsigned NumButtons = 0; //!< the number of buttons that are available + const unsigned NumSensors = 9; //!< the number of sensors available + const unsigned NumLEDs = 10; //!< The number of LEDs which can be controlled + const unsigned NumFacePanelLEDs = 0; //!< The number of face panel LEDs + + const unsigned NumPIDJoints = NumWheels + NumArmJoints + NumLegJoints+NumHeadJoints+NumTailJoints+NumMouthJoints;; //!< servo pins + const unsigned NumOutputs = NumWheels + 16 + NumLEDs; //!< the total number of outputs + const unsigned NumReferenceFrames = NumOutputs + 1 + NumArms + 1; //!< for the base, gripper (* NumArms), and camera reference frames + + // webcam ? + const float CameraHorizFOV=56.9/180*M_PI; //!< horizontal field of view (radians) + const float CameraVertFOV=45.2/180*M_PI; //!< vertical field of view (radians) + const float CameraFOV=CameraHorizFOV; //!< should be set to maximum of #CameraHorizFOV or #CameraVertFOV + const unsigned int CameraResolutionX=320; //!< the number of pixels available in the 'full' layer + const unsigned int CameraResolutionY=240; //!< the number of pixels available in the 'full' layer + //@} + + + // ******************************* + // OUTPUT OFFSETS + // ******************************* + + //!Corresponds to entries in ERS7Info::PrimitiveName, defined at the end of this file + //!@name Output Offsets + + + const unsigned PIDJointOffset = 0; //!< The beginning of the PID Joints + const unsigned WheelOffset = PIDJointOffset; + + const unsigned LEDOffset = PIDJointOffset + NumPIDJoints; //!< the offset of LEDs in WorldState::outputs and MotionCommand functions, see LedOffset_t for specific offsets + + const unsigned BaseFrameOffset = NumOutputs; //!< Use with kinematics to refer to base reference frame + + enum WheelOffset_t { + LWheelOffset=WheelOffset, + RWheelOffset + }; + + //! The offsets of the individual LEDs -- except the qwerk board doesn't have any particularly symbolic LEDs, just use numeric values... + /*! @hideinitializer */ + enum LEDOffset_t { }; + + typedef unsigned int LEDBitMask_t; //!< So you can be clear when you're refering to a LED bitmask + //! LEDs for the face panel (all FaceLEDPanelMask<<(0:NumFacePanelLEDs-1) entries) + const LEDBitMask_t FaceLEDMask = 0; + //! selects all of the leds + const LEDBitMask_t AllLEDMask = (LEDBitMask_t)~0; + //@} + + + // ******************************* + // INPUT OFFSETS + // ******************************* + + + //! The order in which inputs should be stored + //!@name Input Offsets + + //! holds offsets to different buttons in WorldState::buttons[] + /*! Should be a straight mapping to the ButtonSourceIDs + * + * Note that the chest (power) button is not a normal button. It kills + * power to the motors at a hardware level, and isn't sensed in the + * normal way. If you want to know when it is pressed (and you are + * about to shut down) see PowerSrcID::PauseSID. + * + * @see WorldState::buttons @see ButtonSourceID_t + * @hideinitializer */ + enum ButtonOffset_t { }; + + //! Provides a string name for each button + const char* const buttonNames[NumButtons+1] = { NULL }; // non-empty array to avoid gcc 3.4.2 internal error + + //! holds offset to different sensor values in WorldState::sensors[] + /*! @see WorldState::sensors[] */ + enum SensorOffset_t { BatteryVoltage }; + + //! Provides a string name for each sensor + const char* const sensorNames[NumSensors] = { + "BatteryVoltage", + "AnalogIn0", + "AnalogIn1", + "AnalogIn2", + "AnalogIn3", + "AnalogIn4", + "AnalogIn5", + "AnalogIn6", + "AnalogIn7", + }; + + //@} + + + //! Names for each of the outputs + const char* const outputNames[NumOutputs] = { + "WHEEL:000", + "WHEEL:001", + "WHEEL:002", + "WHEEL:003", + "SERVO:000", + "SERVO:001", + "SERVO:002", + "SERVO:003", + "SERVO:004", + "SERVO:005", + "SERVO:006", + "SERVO:007", + "SERVO:008", + "SERVO:009", + "SERVO:010", + "SERVO:011", + "SERVO:012", + "SERVO:013", + "SERVO:014", + "SERVO:015", + "LED:00000", + "LED:00001", + "LED:00002", + "LED:00003", + "LED:00004", + "LED:00005", + "LED:00006", + "LED:00007", + "LED:00008", + "LED:00009" + }; + + //! allocation declared in RobotInfo.cc + extern Capabilities capabilities; + + //! This table holds the default PID values for each joint. see PIDMC + const float DefaultPIDs[NumPIDJoints+1][3] = { {0,0,0} }; + + //!These values are our recommended maximum joint velocities, in rad/ms + /*! a value <= 0 means infinite speed (e.g. LEDs) + * + * These limits are not enforced by the framework. They are simply available for you to use as you see fit. + * HeadPointerMC and PostureMC are primary examples of included classes which do respect these values (although they can be overridden) + * + * These values were obtained from the administrators of the Sony OPEN-R BBS */ + const float MaxOutputSpeed[NumOutputs] = { + 1e-3, //Wheels: left, right + 1e-3, + 3.14e-3, // Neck: tilt, pan + 6.28e-3, + + 0,0,0,0,0,0,0,0,0,0 // LED + }; + + #ifndef RAD + //!Just a little macro for converting degrees to radians + #define RAD(deg) (((deg) * M_PI ) / 180.0) + //!a flag so we undef these after we're done - do you have a cleaner solution? + #define __RI_RAD_FLAG + #endif + + //! This table holds the software limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + const double outputRanges[NumOutputs][2] = + { + { -1 , 1 }, + { -1 , 1 }, + { RAD(-90) , RAD(90) }, + { RAD(-90) , RAD(90) }, + + // LED + {0,1}, {0,1}, {0,1}, {0,1}, {0,1}, + {0,1}, {0,1}, {0,1}, {0,1}, {0,1} + }; + + //! This table holds the mechanical limits of each of the outputs, first index is the output offset, second index is MinMaxRange_t (i.e. MinRange or MaxRange) + /*! Same as #outputRanges, don't know actual values because they were never specified by Sony */ + const double mechanicalLimits[NumOutputs][2] = + { + { -1 , 1 }, + { -1 , 1 }, + { RAD(-90) , RAD(90) }, + { RAD(-90) , RAD(90) }, + + // LED + {0,1}, {0,1}, {0,1}, {0,1}, {0,1}, + {0,1}, {0,1}, {0,1}, {0,1}, {0,1} + }; + +#ifdef __RI_RAD_FLAG +#undef RAD +#undef __RI_RAD_FLAG +#endif +} + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/Regis1Info.h ./Shared/Regis1Info.h --- ../Tekkotsu_3.0/Shared/Regis1Info.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/Regis1Info.h 2007-11-22 00:10:09.000000000 -0500 @@ -0,0 +1,201 @@ +//-*-c++-*- +#ifndef INCLUDED_Regis1Info_h +#define INCLUDED_Regis1Info_h + +#include +#include +#include "CommonInfo.h" +using namespace RobotInfo; + +// see http://tekkotsu.org/porting.html#configuration for more information on TGT_HAS_* flags +#if defined(TGT_REGIS1) +# define TGT_HAS_WHEELS 2 +# define TGT_HAS_ARMS 1 +# define TGT_HAS_CAMERA 1 +# define TGT_HAS_HEAD 1 +#endif + +namespace Regis1Info { + + // ******************************* + // ROBOT CONFIGURATION + // ******************************* + + extern const char* const TargetName; //!< the name of the model, to be used for logging and remote GUIs + + const unsigned int FrameTime=15; //!< time between frames in the motion system (milliseconds) + const unsigned int NumFrames=1; //!< the number of frames per buffer (don't forget also double buffered) + const unsigned int SoundBufferTime=32; //!< the number of milliseconds per sound buffer... I'm not sure if this can be changed + + //!@name Output Types Information + const unsigned NumWheels = 2; //! event(this, EventBase::remoteStateEGID, + t, EventBase::statusETID); + + erouter->postEvent(event); +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/RemoteState.h ./Shared/RemoteState.h --- ../Tekkotsu_3.0/Shared/RemoteState.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/RemoteState.h 2007-10-16 13:37:21.000000000 -0400 @@ -0,0 +1,37 @@ +#ifndef REMOTESTATE_H_ +#define REMOTESTATE_H_ + +#include "Shared/RobotInfo.h" +#include + +class RemoteRouter; + +/*! This class represents remote state information recieved from a + * remote dog, and can be treated like a WorldState object */ +class RemoteState { + public: + RemoteState(const RemoteRouter *p); + virtual ~RemoteState(); + float outputs[NumOutputs]; + float buttons[NumButtons]; + float sensors[NumSensors]; + + void update(char *data); + + enum StateType { + OutputState, + ButtonState, + SensorState, + }; + + static const int sizes[]; + + private: + const RemoteRouter *parent; + + + RemoteState(RemoteState&); + RemoteState &operator=(const RemoteState&); +}; + +#endif /* REMOTESTATE_H_ */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/RobotInfo.cc ./Shared/RobotInfo.cc --- ../Tekkotsu_3.0/Shared/RobotInfo.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/RobotInfo.cc 2007-11-18 01:47:05.000000000 -0500 @@ -0,0 +1,131 @@ +#include "RobotInfo.h" +#include + +#if defined(TGT_ERS2xx) && defined(PLATFORM_APERIOS) +# include +#endif + +// collecting these static allocations here so we don't have to have a separate file for each one +// you can either make a .cc file dedicated to your Info.h, or just add an entry below... + +#include "ERS210Info.h" +namespace ERS210Info { + const char* const TargetName="ERS-210"; + ERS210Capabilities capabilities; +} + +#include "ERS220Info.h" +namespace ERS220Info { + const char* const TargetName="ERS-220"; + ERS220Capabilities capabilities; +} + +#include "ERS2xxInfo.h" +namespace ERS2xxInfo { + const char* const TargetName="ERS-2xx"; + ERS2xxCapabilities capabilities; +} + +#include "ERS7Info.h" +namespace ERS7Info { + const char* const TargetName="ERS-7"; + ERS7Capabilities capabilities; +} + +#include "LynxArm6Info.h" +namespace LynxArm6Info { + const char* const TargetName="LynxArm6"; + Capabilities capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,0,0); +} + +#include "Regis1Info.h" +namespace Regis1Info { + const char* const TargetName="Regis1"; + Regis1Capabilities capabilities; +} + +#include "QBotPlusInfo.h" +namespace QBotPlusInfo { + const char* const TargetName="QBotPlus"; + QBotPlusCapabilities capabilities; +} + +#include "QwerkInfo.h" +namespace QwerkInfo { + const char* const TargetName="Qwerk"; + Capabilities capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs); +} + +#include "CreateInfo.h" +namespace CreateInfo { + const char* const TargetName="Create"; + Capabilities capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs); +} + + +// and now for RobotInfo's own stuff: +namespace RobotInfo { + + const char* const detectModel() { +#ifdef TGT_ERS2xx +# ifdef PLATFORM_APERIOS + // might be running on either 210 or 220, check + char robotDesignStr[orobotdesignNAME_MAX + 1]; + memset(robotDesignStr, 0, sizeof(robotDesignStr)); + if (OPENR::GetRobotDesign(robotDesignStr) != oSUCCESS) { + std::cout << "OPENR::GetRobotDesign() failed." << std::endl; + return TargetName; + } else { + if(strcmp(robotDesignStr,"ERS-210")==0) + return ERS210Info::TargetName; + else if(strcmp(robotDesignStr,"ERS-220")==0) + return ERS220Info::TargetName; + else { + std::cerr << "ERROR: Unknown name '" << robotDesignStr << "' for target ERS2xx" << std::endl; + return TargetName; + } + } +# else +# warning TGT_ERS2xx assuming ERS-210 for simulation on local platform + return ERS210Info::TargetName; +# endif + +#else + // target is directly the robot, return the target name + return TargetName; +#endif + } + +#ifndef PLATFORM_APERIOS + const char* const RobotName = detectModel(); +#else // have to use a string because aperios is annoying like that + const std::string RobotName = detectModel(); +#endif + + + Capabilities::Capabilities(const char* robName, size_t numOut, const char * const outNames[], size_t numBut, const char * const butNames[], size_t numSen, const char * const senNames[], size_t pidOff, size_t numPID, size_t ledOff, size_t numLED) + : name(robName), numOutputs(numOut), numButtons(numBut), numSensors(numSen), + outputs(outNames), buttons(butNames), sensors(senNames), + outputToIndex(), buttonToIndex(), sensorToIndex(), + pidJointOffset(pidOff), numPIDJoints(numPID), ledOffset(ledOff), numLEDs(numLED), + fakeOutputs() + { + for(size_t i=0; i::const_iterator it=getCaps().find(robName); + if(it!=getCaps().end()) + std::cerr << "WARNING: RobotInfo '" << robName << "' capabilities has already been registered! Name conflict? Replacing previous..." << std::endl; + getCaps()[robName]=this; + } + + std::map& Capabilities::getCaps() { + static std::map caps; + return caps; + } + +} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/RobotInfo.h ./Shared/RobotInfo.h --- ../Tekkotsu_3.0/Shared/RobotInfo.h 2006-10-03 19:06:58.000000000 -0400 +++ ./Shared/RobotInfo.h 2007-11-18 01:47:05.000000000 -0500 @@ -2,39 +2,76 @@ #ifndef INCLUDED_RobotInfo_h #define INCLUDED_RobotInfo_h -#if TGT_ERS220 -# include "ERS220Info.h" -#elif TGT_ERS210 -# include "ERS210Info.h" +#include +#include + +// If creating a new robot configuration, add a new entry in the list below + +#if TGT_ERS210 +# include "Shared/ERS210Info.h" +namespace RobotInfo { using namespace ERS210Info; } + +#elif TGT_ERS220 +# include "Shared/ERS220Info.h" +namespace RobotInfo { using namespace ERS220Info; } + #elif TGT_ERS2xx -# include "ERS2xxInfo.h" +# include "Shared/ERS2xxInfo.h" +namespace RobotInfo { using namespace ERS2xxInfo; } + #elif TGT_ERS7 -# include "ERS7Info.h" +# include "Shared/ERS7Info.h" +namespace RobotInfo { using namespace ERS7Info; } + +#elif TGT_LYNXARM6 +# include "Shared/LynxArm6Info.h" +namespace RobotInfo { using namespace LynxArm6Info; } + +#elif TGT_REGIS1 +# include "Shared/Regis1Info.h" +namespace RobotInfo { using namespace Regis1Info; } + +#elif TGT_QBOTPLUS +# include "Shared/QBotPlusInfo.h" +namespace RobotInfo { using namespace QBotPlusInfo; } + +#elif TGT_QWERK +# include "Shared/QwerkInfo.h" +namespace RobotInfo { using namespace QwerkInfo; } + +#elif TGT_CREATE +# include "Shared/CreateInfo.h" +namespace RobotInfo { using namespace CreateInfo; } + #else //default case, currently ERS-7 -# warning "TGT_ undefined or unknown model set - defaulting to ERS7 (valid values are TGT_ERS210, TGT_ERS220, TGT_ERS2xx, or TGT_ERS7)" -# include "ERS7Info.h" +# warning "TGT_ undefined or unknown model set - defaulting to ERS7" +# include "Shared/ERS7Info.h" +namespace RobotInfo { using namespace ERS7Info; } #endif //model selection + //! Contains information about the robot, such as number of joints, PID defaults, timing information, etc. /*! This is just a wrapper for whichever namespace corresponds to the current - * robot target setting (one of TGT_ERS7, TGT_ERS210, TGT_ERS220, or the cross-booting TGT_ERS2xx) - * - * You probably should look at ERS7Info, ERS210Info, ERS220Info, or ERS2xxInfo for the actual - * constants used for each model, although some common information shared by all of these namespaces - * is defined in CommonInfo.h */ +* robot target setting (one of TGT_ERS7, TGT_ERS210, TGT_ERS220, or the cross-booting TGT_ERS2xx) +* +* You probably should look at ERS7Info, ERS210Info, ERS220Info, or ERS2xxInfo for the actual +* constants used for each model, although some common information shared by all of these namespaces +* is defined in CommonInfo.h */ namespace RobotInfo { - -#if TGT_ERS220 - using namespace ERS220Info; -#elif TGT_ERS210 - using namespace ERS210Info; -#elif TGT_ERS7 - using namespace ERS7Info; -#elif TGT_ERS2xx - using namespace ERS2xxInfo; -#else //default case, ERS7 - using namespace ERS7Info; -#endif //model selection + + //! Accessor for Capabilities::caps, returns the Capabilities instance for a specified robot model (or NULL if robot is unknown or didn't provide a Capabilities instance) + /*! Use this if you have a robot name in string form and want to check or map its capabilities. + * (For example, if you are communicating with another robot of a different type over the network.) + * If you know at compile time the type of the robot in question, you could just directly access + * its 'capabilities' instance via its RobotInfo namespace. (e.g. ERS210Info::capabilities) + * If you want the capabilities for the current robot, just use the global 'capabilities' instance + * as RobotInfo.h will automatically import the current robot's namespace into the global space. */ + inline Capabilities* getCapabilities(const std::string& robName) { + const std::map& caps = Capabilities::getCaps(); + std::map::const_iterator it = caps.find(robName); + return it==caps.end() ? NULL : it->second; + } + } using namespace RobotInfo; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/StackTrace.cc ./Shared/StackTrace.cc --- ../Tekkotsu_3.0/Shared/StackTrace.cc 2006-09-16 02:28:08.000000000 -0400 +++ ./Shared/StackTrace.cc 2007-11-12 23:16:03.000000000 -0500 @@ -96,7 +96,7 @@ void* nsp=NULL; machineInstruction * nra=NULL; -#ifdef __i386__ +#if defined(__i386__) || defined(__x86_64__) || defined(__amd64__) if(curFrame==NULL) return 0; curFrame->caller=NULL; @@ -223,9 +223,9 @@ if(ins>=INS_BASE) { if(nsp<=curFrame->sp) { #ifdef __pic__ - fprintf(stderr,"stacktrace::unrollStackFrame(sp=%p,ra=%p,gp=%p) directed to invalid next frame: (sp=%p,ra=%p,gp=%p)\n",curFrame->sp,curFrame->ra,curFrame->gp,nsp,nra,reinterpret_cast(nsp)[4]); + fprintf(stderr,"stacktrace::unrollStackFrame(sp=%p,ra=%p,gp=%p) directed to invalid next frame: (sp=%p,ra=%p,gp=%p)\n",curFrame->sp,(void*)curFrame->ra,(void*)curFrame->gp,nsp,nra,(void*)(reinterpret_cast(nsp)[4])); #else - fprintf(stderr,"stacktrace::unrollStackFrame(sp=%p,ra=%p) directed to invalid next frame: (sp=%p,ra=%p)\n",curFrame->sp,curFrame->ra,nsp,nra); + fprintf(stderr,"stacktrace::unrollStackFrame(sp=%p,ra=%p) directed to invalid next frame: (sp=%p,ra=%p)\n",curFrame->sp,(void*)curFrame->ra,nsp,nra); #endif return 0; } @@ -297,14 +297,14 @@ __asm __volatile__ ("jal readepc; nop; readepc: move %0,$ra" : "=r"(cra) ); // get the current return address #endif /* __MIPSEL__ */ -#ifdef __i386__ +#if defined(__i386__) || defined(__x86_64__) || defined(__amd64__) __asm __volatile__ ("movl %%ebp,%0" : "=m"(csp) ); // get the caller's stack pointer csp++; //go back one to really be a stack pointer //__asm __volatile__ ("movl (%%esp),%0" : "=r"(cra) ); // get the caller's address cra=*((machineInstruction**)csp); csp=((void***)csp)[-1]+1; #endif /* __i386__ */ - + frame->sp=csp; #ifdef __pic__ frame->ra=cgp-reinterpret_cast(cra); @@ -313,7 +313,7 @@ frame->ra=cra; #endif /* __pic__ */ -#ifndef __i386__ +#if !defined(__i386__) && !defined(__x86_64__) && !defined(__amd64__) //with ia-32 it was more convenient to directly provide caller, so don't need to unroll //otherwise we actually want to return *caller's* frame, so unroll once unrollStackFrame(frame,frame); @@ -626,7 +626,7 @@ #else void displayStackFrame(unsigned int ST_UNUSED(depth), const struct StackFrame* frame) { ST_BODY_UNUSED(depth); - fprintf(stderr," %p",frame->ra); + fprintf(stderr," %p",(void*)frame->ra); } #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/WorldState.cc ./Shared/WorldState.cc --- ../Tekkotsu_3.0/Shared/WorldState.cc 2006-09-29 12:56:09.000000000 -0400 +++ ./Shared/WorldState.cc 2007-11-15 16:33:04.000000000 -0500 @@ -5,7 +5,6 @@ #include "ERS220Info.h" #include "ERS7Info.h" #include "Shared/Config.h" -#include "IPC/ProcessID.h" #ifdef PLATFORM_APERIOS # include @@ -18,26 +17,29 @@ # include "Motion/PostureEngine.h" #endif +using namespace std; + #define GETD(cpc) (((float)sensor.GetData(cpc)->frame[lastFrame].value) / 1.0E6f) //!< returns value from OPEN-R, converted from micro in int to base in float #define GETB(cpc) ((bool)sensor.GetData(cpc)->frame[lastFrame].value) //!< returns value from OPEN-R, as bool #define GETSENSOR(cpc) ((float)sensor.GetData(cpc)->frame[lastFrame].value) //!< return value from OPEN-R, as int #define GETSIG(cpc) ((word)sensor.GetData(cpc)->frame[lastFrame].signal) //!< returns signal from OPEN-R as word -#define GETDUTY(cpc) ((float)((OJointValue*)&sensor.GetData(cpc)->frame[lastFrame])->pwmDuty/512.0f) //!< returns duty cycle from OPEN-R as float; -1 (full reverse) to 0 (idle) to 1 (full forward) +#define GETDUTY(cpc) (((OJointValue*)(void*)&sensor.GetData(cpc)->frame[lastFrame])->pwmDuty/512.0f) //!< returns duty cycle from OPEN-R as float; -1 (full reverse) to 0 (idle) to 1 (full forward) const double WorldState::g=9.80665; const double WorldState::IROORDist = 900.0; #ifdef PLATFORM_APERIOS WorldState ** WorldState::stateLookupMap=NULL; -#endif - WorldState * state=NULL; +#else +WorldStateLookup state; +#endif WorldState::WorldState() : alwaysGenerateStatus(false), vel_x(0), vel_y(0), vel_a(0), vel_time(0), robotStatus(0), batteryStatus(0), lastSensorUpdateTime(0), frameNumber(1), framesProcessed(0), - robotDesign(0), curtime(0) + curtime(0) { for(unsigned int i=0; i< NumOutputs; i++) outputs[i]=0; @@ -47,47 +49,11 @@ sensors[i]=0; for(unsigned int i=0; i< NumPIDJoints; i++) for(unsigned int j=0; j<3; j++) - pids[i][j]=0; + pids[i][j]=DefaultPIDs[i][j]; for(unsigned int i=0; i< NumPIDJoints; i++) pidduties[i]=0; - memset(powerFlags,0,sizeof(unsigned int)*PowerSourceID::NumPowerSIDs); + memset(powerFlags,0,sizeof(unsigned int)*PowerSrcID::NumPowerSIDs); memset(button_times,0,sizeof(unsigned int)*NumButtons); - -#ifdef PLATFORM_APERIOS - //Thanks Daishi: - char robotDesignStr[orobotdesignNAME_MAX + 1]; - memset(robotDesignStr, 0, sizeof(robotDesignStr)); - if (OPENR::GetRobotDesign(robotDesignStr) != oSUCCESS) { - cout << "OPENR::GetRobotDesign() failed." << endl; - } else { - if(strcmp(robotDesignStr,"ERS-210")==0) - robotDesign=ERS210Mask; - else if(strcmp(robotDesignStr,"ERS-220")==0) - robotDesign=ERS220Mask; - else if(strcmp(robotDesignStr,"ERS-7")==0) - robotDesign=ERS7Mask; - else { - cout << "ERROR: Unrecognized model: "< undefined - defaulting to TGT_ERS7" - robotDesign=ERS7Mask; -# endif //model selection -#endif } #ifdef PLATFORM_APERIOS @@ -109,7 +75,7 @@ //pid and velocity values will be copied at "completion" robotStatus=lastState->robotStatus; batteryStatus=lastState->batteryStatus; - for(unsigned int i=0; ipowerFlags[i]; //important part -- copy over button_times before calls to chkEvent @@ -117,7 +83,7 @@ button_times[i]=lastState->button_times[i]; } - if(robotDesign&ERS210Mask) { + if(RobotName == ERS210Info::TargetName) { outputs[LFrLegOffset + RotatorOffset ] = GETD(ERS210Info::CPCJointLFRotator); outputs[LFrLegOffset + ElevatorOffset ] = GETD(ERS210Info::CPCJointLFElevator); outputs[LFrLegOffset + KneeOffset ] = GETD(ERS210Info::CPCJointLFKnee); @@ -154,16 +120,27 @@ pidduties[HeadOffset+PanOffset ] = GETDUTY(ERS210Info::CPCJointNeckPan); pidduties[HeadOffset+RollOffset] = GETDUTY(ERS210Info::CPCJointNeckRoll); - outputs[ERS210Info::TailOffset+TiltOffset] = GETD(ERS210Info::CPCJointTailTilt); - outputs[ERS210Info::TailOffset+PanOffset] = GETD(ERS210Info::CPCJointTailPan); - pidduties[ERS210Info::TailOffset+TiltOffset] = GETDUTY(ERS210Info::CPCJointTailTilt); - pidduties[ERS210Info::TailOffset+PanOffset] = GETDUTY(ERS210Info::CPCJointTailPan); +#ifdef TGT_ERS210 + unsigned tail = ERS210Info::TailOffset; + unsigned mouth = ERS210Info::MouthOffset; +#elif defined(TGT_ERS2xx) + unsigned tail = ERS2xxInfo::TailOffset; + unsigned mouth = ERS2xxInfo::MouthOffset; +#else + unsigned tail = capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::TailOffset]); + unsigned mouth = capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::MouthOffset]); +#endif + outputs[tail+TiltOffset] = GETD(ERS210Info::CPCJointTailTilt); + outputs[tail+PanOffset] = GETD(ERS210Info::CPCJointTailPan); + pidduties[tail+TiltOffset] = GETDUTY(ERS210Info::CPCJointTailTilt); + pidduties[tail+PanOffset] = GETDUTY(ERS210Info::CPCJointTailPan); - outputs[ERS210Info::MouthOffset] = GETD(ERS210Info::CPCJointMouth); - pidduties[ERS210Info::MouthOffset] = GETDUTY(ERS210Info::CPCJointMouth); + outputs[mouth] = GETD(ERS210Info::CPCJointMouth); + pidduties[mouth] = GETDUTY(ERS210Info::CPCJointMouth); if(lastState!=NULL && lastState!=this) { // Copy over new buttons + // ERS2xx happens to match ERS210 offsets for buttons, so nothing special needed... buttons[ERS210Info::LFrPawOffset]=GETB(ERS210Info::CPCSensorLFPaw); buttons[ERS210Info::RFrPawOffset]=GETB(ERS210Info::CPCSensorRFPaw); buttons[ERS210Info::LBkPawOffset]=GETB(ERS210Info::CPCSensorLHPaw); @@ -202,7 +179,7 @@ } // (ERS-220 only) - if(robotDesign&ERS220Mask) { + if(RobotName == ERS220Info::TargetName) { outputs[LFrLegOffset + RotatorOffset ] = GETD(ERS220Info::CPCJointLFRotator); outputs[LFrLegOffset + ElevatorOffset ] = GETD(ERS220Info::CPCJointLFElevator); outputs[LFrLegOffset + KneeOffset ] = GETD(ERS220Info::CPCJointLFKnee); @@ -241,6 +218,7 @@ if(lastState!=NULL && lastState!=this) { // Copy over new buttons + // ERS2xx happens to match ERS220 offsets for buttons, so nothing special needed... buttons[ERS220Info::LFrPawOffset]=GETB(ERS220Info::CPCSensorLFPaw); buttons[ERS220Info::RFrPawOffset]=GETB(ERS220Info::CPCSensorRFPaw); buttons[ERS220Info::LBkPawOffset]=GETB(ERS220Info::CPCSensorLHPaw); @@ -285,7 +263,7 @@ } // (ERS-7 only) - if(robotDesign&ERS7Mask) { + if(RobotName == ERS7Info::TargetName) { outputs[LFrLegOffset + RotatorOffset ] = GETD(ERS7Info::CPCJointLFRotator); outputs[LFrLegOffset + ElevatorOffset ] = GETD(ERS7Info::CPCJointLFElevator); outputs[LFrLegOffset + KneeOffset ] = GETD(ERS7Info::CPCJointLFKnee); @@ -379,68 +357,71 @@ lastSensorUpdateTime=curtime; frameNumber=newFrameNumber; framesProcessed=(lastState!=NULL?lastState->framesProcessed:framesProcessed)+1; - for(unsigned int i=0; ipostEvent(evtBuf[i]); - //Apply sensor calibrations (currently only joint positions - perhaps IR as well?) + /* for(unsigned int i=0; imotion.calibration[i]; + */ + applyCalibration(); + + for(unsigned int i=0; ipostEvent(evtBuf[i]); //this version of read doesn't post the sensor update event -- the caller should do that //this event gets posted by MMCombo only if there's no back log on the interprocess event queue (don't want to stack these up for sensor frames missed by main) - //er->postEvent(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,dif,"SensorSouceID::UpdatedSID",1); + //er->postEvent(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,dif,"SensorSouceID::UpdatedSID",1); } /*! This will cause events to be posted */ void WorldState::read(const OPowerStatus& power, EventRouter* er) { - std::string actnames[PowerSourceID::NumPowerSIDs]; - std::string denames[PowerSourceID::NumPowerSIDs]; - unsigned int actmasks[PowerSourceID::NumPowerSIDs]; - memset(actmasks,0,sizeof(unsigned int)*PowerSourceID::NumPowerSIDs); + std::string actnames[PowerSrcID::NumPowerSIDs]; + std::string denames[PowerSrcID::NumPowerSIDs]; + unsigned int actmasks[PowerSrcID::NumPowerSIDs]; + memset(actmasks,0,sizeof(unsigned int)*PowerSrcID::NumPowerSIDs); //RobotStatus - chkPowerEvent(PowerSourceID::PauseSID, power.robotStatus,orsbPAUSE, "Pause",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::MotorPowerSID, power.robotStatus,orsbMOTOR_POWER, "MotorPower",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::VibrationSID, power.robotStatus,orsbVIBRATION_DETECT, "Vibration",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ExternalPortSID, power.robotStatus,orsbEX_PORT_CONNECTED, "ExternalPort",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::StationConnectSID, power.robotStatus,orsbSTATION_CONNECTED, "StationConnect",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ExternalPowerSID, power.robotStatus,orsbEX_POWER_CONNECTED, "ExternalPower",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::BatteryConnectSID, power.robotStatus,orsbBATTERY_CONNECTED, "BatteryConnect",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ChargingSID, power.robotStatus,orsbBATTERY_CHARGING, "BatteryCharging",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::BatteryFullSID, power.robotStatus,orsbBATTERY_CAPACITY_FULL, "BatteryFull",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::LowPowerWarnSID, power.robotStatus,orsbBATTERY_CAPACITY_LOW, "BatteryLow",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::OverChargedSID, power.robotStatus,orsbBATTERY_OVER_CURRENT, "BatteryOverCurrent",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::OverheatingSID, power.robotStatus,orsbBATTERY_OVER_TEMP_DISCHARGING,"BatteryOverTempDischarge",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::OverheatingSID, power.robotStatus,orsbBATTERY_OVER_TEMP_CHARGING, "BatteryOverTempCharge",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ErrorSID, power.robotStatus,orsbBATTERY_ERROR_OF_CHARGING, "BatteryChargeError",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ErrorSID, power.robotStatus,orsbERROR_OF_PLUNGER, "PlungerError",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::PowerGoodSID, power.robotStatus,orsbOPEN_R_POWER_GOOD, "PowerGood",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ErrorSID, power.robotStatus,orsbERROR_OF_FAN, "FanError",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::DataFromStationSID,power.robotStatus,orsbDATA_STREAM_FROM_STATION, "DataFromStation",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::RegisterUpdateSID, power.robotStatus,orsbREGISTER_UPDATED_BY_STATION, "RegisterUpdate",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ErrorSID, power.robotStatus,orsbRTC_ERROR, "RTCError",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::RTCSID, power.robotStatus,orsbRTC_OVERFLOW, "RTCOverflow",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::RTCSID, power.robotStatus,orsbRTC_RESET, "RTCReset",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::RTCSID, power.robotStatus,orsbRTC_SET, "RTCSet",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::SpecialModeSID, power.robotStatus,orsbSPECIAL_MODE, "SpecialMode",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::BMNDebugModeSID, power.robotStatus,orsbBMN_DEBUG_MODE, "BMNDebugMode",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::ChargerStatusSID, power.robotStatus,orsbCHARGER_STATUS, "ChargerStatus",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::PlungerSID, power.robotStatus,orsbPLUNGER, "Plunger",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::SuspendedSID, power.robotStatus,orsbSUSPENDED, "Suspended",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::PauseSID, power.robotStatus,orsbPAUSE, "Pause",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::MotorPowerSID, power.robotStatus,orsbMOTOR_POWER, "MotorPower",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::VibrationSID, power.robotStatus,orsbVIBRATION_DETECT, "Vibration",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ExternalPortSID, power.robotStatus,orsbEX_PORT_CONNECTED, "ExternalPort",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::StationConnectSID, power.robotStatus,orsbSTATION_CONNECTED, "StationConnect",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ExternalPowerSID, power.robotStatus,orsbEX_POWER_CONNECTED, "ExternalPower",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::BatteryConnectSID, power.robotStatus,orsbBATTERY_CONNECTED, "BatteryConnect",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ChargingSID, power.robotStatus,orsbBATTERY_CHARGING, "BatteryCharging",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::BatteryFullSID, power.robotStatus,orsbBATTERY_CAPACITY_FULL, "BatteryFull",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::LowPowerWarnSID, power.robotStatus,orsbBATTERY_CAPACITY_LOW, "BatteryLow",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::OverChargedSID, power.robotStatus,orsbBATTERY_OVER_CURRENT, "BatteryOverCurrent",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::OverheatingSID, power.robotStatus,orsbBATTERY_OVER_TEMP_DISCHARGING,"BatteryOverTempDischarge",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::OverheatingSID, power.robotStatus,orsbBATTERY_OVER_TEMP_CHARGING, "BatteryOverTempCharge",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ErrorSID, power.robotStatus,orsbBATTERY_ERROR_OF_CHARGING, "BatteryChargeError",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ErrorSID, power.robotStatus,orsbERROR_OF_PLUNGER, "PlungerError",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::PowerGoodSID, power.robotStatus,orsbOPEN_R_POWER_GOOD, "PowerGood",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ErrorSID, power.robotStatus,orsbERROR_OF_FAN, "FanError",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::DataFromStationSID,power.robotStatus,orsbDATA_STREAM_FROM_STATION, "DataFromStation",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::RegisterUpdateSID, power.robotStatus,orsbREGISTER_UPDATED_BY_STATION, "RegisterUpdate",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ErrorSID, power.robotStatus,orsbRTC_ERROR, "RTCError",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::RTCSID, power.robotStatus,orsbRTC_OVERFLOW, "RTCOverflow",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::RTCSID, power.robotStatus,orsbRTC_RESET, "RTCReset",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::RTCSID, power.robotStatus,orsbRTC_SET, "RTCSet",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::SpecialModeSID, power.robotStatus,orsbSPECIAL_MODE, "SpecialMode",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::BMNDebugModeSID, power.robotStatus,orsbBMN_DEBUG_MODE, "BMNDebugMode",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ChargerStatusSID, power.robotStatus,orsbCHARGER_STATUS, "ChargerStatus",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::PlungerSID, power.robotStatus,orsbPLUNGER, "Plunger",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::SuspendedSID, power.robotStatus,orsbSUSPENDED, "Suspended",actnames,denames,actmasks); //BatteryStatus - chkPowerEvent(PowerSourceID::ErrorSID, power.batteryStatus,obsbERROR_CODE_MASK, "BatteryError",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::BatteryEmptySID, power.batteryStatus,obsbFULLY_DISCHARGED, "FullyDischarged",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::BatteryFullSID, power.batteryStatus,obsbFULLY_CHARGED, "FullyCharged",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::DischargingSID, power.batteryStatus,obsbDISCHARGING, "Discharging",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::BatteryInitSID, power.batteryStatus,obsbINITIALIZED, "BatteryInit",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::LowPowerWarnSID, power.batteryStatus,obsbREMAINING_TIME_ALARM, "RemainingTimeAlarm",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::LowPowerWarnSID, power.batteryStatus,obsbREMAINING_CAPACITY_ALARM, "RemainingCapacityAlarm",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::TermDischargeSID,power.batteryStatus,obsbTERMINATED_DISCHARGING_ALARM,"TermDischargeAlarm",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::OverheatingSID, power.batteryStatus,obsbOVER_TEMP_ALARM, "OverTempAlarm",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::TermChargeSID, power.batteryStatus,obsbTERMINATED_CHARGING_ALARM, "TermChargeAlarm",actnames,denames,actmasks); - chkPowerEvent(PowerSourceID::OverChargedSID, power.batteryStatus,obsbOVER_CHARGED_ALARM, "OverChargeAlarm",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::ErrorSID, power.batteryStatus,obsbERROR_CODE_MASK, "BatteryError",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::BatteryEmptySID, power.batteryStatus,obsbFULLY_DISCHARGED, "FullyDischarged",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::BatteryFullSID, power.batteryStatus,obsbFULLY_CHARGED, "FullyCharged",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::DischargingSID, power.batteryStatus,obsbDISCHARGING, "Discharging",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::BatteryInitSID, power.batteryStatus,obsbINITIALIZED, "BatteryInit",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::LowPowerWarnSID, power.batteryStatus,obsbREMAINING_TIME_ALARM, "RemainingTimeAlarm",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::LowPowerWarnSID, power.batteryStatus,obsbREMAINING_CAPACITY_ALARM, "RemainingCapacityAlarm",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::TermDischargeSID,power.batteryStatus,obsbTERMINATED_DISCHARGING_ALARM,"TermDischargeAlarm",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::OverheatingSID, power.batteryStatus,obsbOVER_TEMP_ALARM, "OverTempAlarm",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::TermChargeSID, power.batteryStatus,obsbTERMINATED_CHARGING_ALARM, "TermChargeAlarm",actnames,denames,actmasks); + chkPowerEvent(PowerSrcID::OverChargedSID, power.batteryStatus,obsbOVER_CHARGED_ALARM, "OverChargeAlarm",actnames,denames,actmasks); sensors[PowerRemainOffset] = power.remainingCapacity/100.0; sensors[PowerThermoOffset] = power.temperature/100.0; @@ -449,7 +430,7 @@ sensors[PowerCurrentOffset] = power.current; //only generate status events when a change happens - for(unsigned int i=0; ipostEvent(EventBase::powerEGID,i,EventBase::activateETID,0,actnames[i],1); @@ -462,7 +443,7 @@ powerFlags[i]=actmasks[i]; } - er->postEvent(EventBase::powerEGID,PowerSourceID::UpdatedSID,EventBase::statusETID,0,"PowerSourceID::UpdatedSID",1); + er->postEvent(EventBase::powerEGID,PowerSrcID::UpdatedSID,EventBase::statusETID,0,"PowerSrcID::UpdatedSID",1); } #else //PLATFORM_LOCAL @@ -471,8 +452,8 @@ * (this variant is used by the simulator, different parts fill in different sections, the last one should trigger the event) * * This function assumes that the pose (and any associated sensor readings) - * are for the current model robot, and that any calibration has already - * been applied (so the values can be used unchanged) + * are for the current model robot, and that no calibration has already + * been applied (so the values must be calibrated) */ void WorldState::read(const PostureEngine& pose, WorldState* lastState, EventRouter* er) { curtime=get_time(); @@ -481,19 +462,42 @@ unsigned int newFrameNumber=(lastState!=NULL?lastState->frameNumber:frameNumber)+NumFrames; - for(unsigned int i=0; i0) - outputs[i]=pose(i).value; - - if(frameNumber>=newFrameNumber) + if(frameNumber>=newFrameNumber) { return; //sensors have already been filled in + } + + if(lastState!=NULL && lastState!=this) { + // copy over previous value if weight is 0 + //printf("this=%p, last=%p, ext=%p\n",this,lastState,ext); + for(unsigned int i=0; i0) { + if (i>=PIDJointOffset && imotion.calibration_scale[i-PIDJointOffset]) + - config->motion.calibration_offset[i-PIDJointOffset]; + } else { + outputs[i] = pose(i).value; + } + } else { + outputs[i] = lastState->outputs[i]; + } + } + } else { + // just ignore 0 weighted values + for(unsigned int i=0; i0) { + outputs[i]=pose(i).value; + } + } + applyCalibration(); + } + if(lastState!=NULL && lastState!=this) { alwaysGenerateStatus=lastState->alwaysGenerateStatus; //pid and velocity values will be copied at "completion" robotStatus=lastState->robotStatus; batteryStatus=lastState->batteryStatus; - for(unsigned int i=0; ipowerFlags[i]; //important part -- copy over button_times before calls to chkEvent @@ -533,12 +537,13 @@ if(newFrameNumber!=-1U) frameNumber=newFrameNumber; framesProcessed=(lastState!=NULL?lastState->framesProcessed:framesProcessed)+1; + for(unsigned int i=0; ipostEvent(evtBuf[i]); - + //this version of read doesn't post the sensor update event -- the caller should do that // (this variant is used by the simulator, different parts fill in different sections, the last one should trigger the event) - //er->postEvent(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,dif,"SensorSourceID::UpdatedSID",1); + //er->postEvent(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,dif,"SensorSrcID::UpdatedSID",1); } #endif //platform-specific sensor updating @@ -588,6 +593,12 @@ } } +void WorldState::applyCalibration() { + for (unsigned int i=PIDJointOffset; imotion.calibration_scale[i-PIDJointOffset]) ) - config->motion.calibration_offset[i-PIDJointOffset]; + } +} + /*! @file * @brief Implements WorldState, maintains information about the robot's environment, namely sensors and power status * @author ejt (Creator) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/WorldState.h ./Shared/WorldState.h --- ../Tekkotsu_3.0/Shared/WorldState.h 2006-10-03 18:00:08.000000000 -0400 +++ ./Shared/WorldState.h 2007-11-15 16:33:04.000000000 -0500 @@ -3,7 +3,6 @@ #define INCLUDED_WorldState_h #ifdef PLATFORM_APERIOS -#include "IPC/ProcessID.h" #include #include #include @@ -15,6 +14,7 @@ #include "Shared/RobotInfo.h" #include "Events/EventBase.h" +#include "IPC/ProcessID.h" #include #include @@ -24,7 +24,7 @@ //The following SourceIDs are for events created by WorldState's event generators //! holds source ID types for sensor events; see EventBase, see #SensorSourceID_t -namespace SensorSourceID { +namespace SensorSrcID { //! holds source ID types for sensor events /*! May want to add a proximity alarm for IR distance? Probably * should do it from a separate generator to avoid screwing up @@ -36,7 +36,7 @@ } //! holds source ID types for power events; see EventBase, see #PowerSourceID_t -namespace PowerSourceID { +namespace PowerSrcID { //! holds source ID types for power events /*! Also serve as offsets into WorldState::powerFlags[]. * @@ -97,8 +97,33 @@ } class WorldState; -extern WorldState * state; //!< the global state object, is a shared memory region, created by MainObject +#ifdef PLATFORM_APERIOS +extern WorldState * state; //!< the global state object, points into a shared memory region, created by MainObject +#else +//! This class masquerades as a simple WorldState pointer, but actually checks the process ID of the referencing thread to allow each thread group to have a separate WorldState* +/*! This is to support WorldStatePool functionality, so if a behavior in Main is blocking, it doesn't prevent Motion threads from getting updated sensors */ +class WorldStateLookup { +public: + WorldStateLookup() { for(unsigned int i=0; i() { return ws[ProcessID::getID()]; } //!< smart pointer to the underlying class + WorldState& operator*() { return *ws[ProcessID::getID()]; } //!< smart pointer to the underlying class + operator WorldState*&() { return ws[ProcessID::getID()]; } //!< pretend we're a simple pointer + WorldStateLookup& operator=(WorldState* p) { ws[ProcessID::getID()]=p; return *this; } //!< assign from a pointer as well +protected: + //! This holds a separate WorldState pointer for each process + /*! Note that under a multi-process model, each process is only ever going to reference one of these, + * (so we could get away with a single global pointer), but under a uni-process model, we wind up + * using the various entries to differentiate the thread groups */ + WorldState* ws[ProcessID::NumProcesses]; +private: + WorldStateLookup(const WorldStateLookup&); //!< don't call this + WorldStateLookup& operator=(const WorldStateLookup&); //!< don't call this +}; +//! the global state object, points into a shared memory region, created by MainObject +extern WorldStateLookup state; +#endif + //! The state of the robot and its environment /*! Contains sensor readings, current joint positions, etc. Notable members are: * - #outputs - joint positions and current LED values @@ -149,7 +174,7 @@ unsigned int robotStatus; //!< bitmask, see OPENR/OPower.h unsigned int batteryStatus; //!< bitmask, see OPENR/OPower.h - unsigned int powerFlags[PowerSourceID::NumPowerSIDs]; //!< bitmasks of similarly-grouped items from previous two masks, corresponds to the PowerSourceID::PowerSourceID_t's + unsigned int powerFlags[PowerSrcID::NumPowerSIDs]; //!< bitmasks of similarly-grouped items from previous two masks, corresponds to the PowerSrcID::PowerSourceID_t's unsigned int button_times[NumButtons]; //!< value is time of current press, 0 if not down @@ -183,22 +208,6 @@ static WorldState* getCurrent() { return ::state; } #endif - //! bitmask corresponding to OPENR::GetRobotDesign() - /*! This allows you to efficiently test different combinations, like - * any 2x0 model vs. any 7 model or any 3xx model (when/if the - * 3xx's are supported). - * - * Testing this will give more accurate feedback as to whether - * features exist than checking RobotInfo values - to achieve dual - * booting, RobotInfo may, for instance, tell you there are two - * ears, but if you're running on a 220 the value you set them to - * will be ignored */ - unsigned int robotDesign; - static const unsigned int ERS210Mask=1<<0; //!< use this to test for ERS-210 features - static const unsigned int ERS220Mask=1<<1; //!< use this to test for ERS-220 features - static const unsigned int ERS2xxMask = ERS210Mask | ERS220Mask; //!< use this to test for ERS-2xx features - static const unsigned int ERS7Mask=1<<2; //!< use this to test for ERS-7 features - protected: unsigned int curtime; //!< set by read(OSensorFrameVectorData& sensor, EventRouter* er) for chkEvent() so each call doesn't have to @@ -207,13 +216,16 @@ //! Tests to see if any button statuses have changed and post events as needed, bases comparison between already filled-in WorldStates void chkEvent(std::vector& evtBuf, WorldState* lastState); + //! Apply calibration to the sensors and joint positions (reversing motion calibration parameters) + void applyCalibration(); + //! sets the names of the flags that will be generating events /*! note that this function does not actually do the event posting, * unlike chkEvent() */ void chkPowerEvent(unsigned int sid, unsigned int cur, unsigned int mask, const char* name, - std::string actname[PowerSourceID::NumPowerSIDs], - std::string dename[PowerSourceID::NumPowerSIDs], - unsigned int summask[PowerSourceID::NumPowerSIDs]) { + std::string actname[PowerSrcID::NumPowerSIDs], + std::string dename[PowerSrcID::NumPowerSIDs], + unsigned int summask[PowerSrcID::NumPowerSIDs]) { if(cur&mask) { actname[sid]+=name; summask[sid]|=mask; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/WorldStatePool.cc ./Shared/WorldStatePool.cc --- ../Tekkotsu_3.0/Shared/WorldStatePool.cc 2006-09-28 16:42:51.000000000 -0400 +++ ./Shared/WorldStatePool.cc 2007-11-15 16:33:04.000000000 -0500 @@ -1,10 +1,11 @@ #include "WorldStatePool.h" #include "Shared/MarkScope.h" #include "Shared/debuget.h" +#include "Shared/Config.h" #include "IPC/RCRegion.h" #ifndef PLATFORM_APERIOS # include "Events/EventRouter.h" -# include "local/LoadFileThread.h" +# include "local/LoadDataThread.h" #endif //better to put this here instead of the header @@ -19,14 +20,14 @@ #ifdef PLATFORM_APERIOS stateLookupMap[i]=NULL; #else - complete[i]=MutexLockBase::getSemaphoreManager()->getSemaphore(); + complete[i]=MessageQueueBase::getSemaphoreManager()->getSemaphore(); #endif order.push_back(i); } #ifdef PLATFORM_APERIOS complete[order.size()-1].lock(ProcessID::getID()); #else - MutexLockBase::getSemaphoreManager()->setValue(complete[order.size()-1],1); + MessageQueueBase::getSemaphoreManager()->setValue(complete[order.size()-1],1); #endif } @@ -119,7 +120,7 @@ //cout << ProcessID::getIDStr() << " checking tgtFr=" << curFrameNumber << " lastFr=" << lastFrameNumber << " fdbkAv=" << haveFeedback << " ovrd="<=3 && info.payloadSize==0) + cout << ProcessID::getIDStr() << " received sensor heartbeat at " << get_time() << endl; + else if(info.verbose>=2 && info.payloadSize!=0) + cout << ProcessID::getIDStr() << " received sensor data \"" << info.filename << "\" at " << get_time() << endl; //cout << "Intending to use " << toUse << " holding frame " << frames[toUse] << " marked " << (isComplete(toUse)?"complete":"not complete") << " with status " << status[toUse] << " for frame " << info.frameNumber << endl; if(frames[toUse]==info.frameNumber && isComplete(toUse)) { - if(info.frameNumber-lastFrameNumber!=1 && info.verbose) + if(info.frameNumber-lastFrameNumber!=1 && info.verbose>=1) cout << ProcessID::getIDStr() << " dropped " << (info.frameNumber-lastFrameNumber-1) << " sensor frame(s)" << endl; lastFrameNumber=info.frameNumber; //cout << ProcessID::getIDStr() << " decided frame is complete or nothing to contribute" << endl; @@ -178,6 +177,10 @@ if(!isZeroPID(wsw.src,i)) state->outputs[i]=feedback->getOutputCmd(i).value; } + //Apply calibration to the joints (this reverses the calibration from MotionManager + for (uint i=0; ioutputs[i+PIDJointOffset] = state->outputs[i+PIDJointOffset] / config->motion.calibration_scale[i] + - config->motion.calibration_offset[i]; wsw.setStatus(wsw.getStatus() | FEEDBACK_APPLIED); } @@ -222,8 +225,11 @@ unsigned int stateFrame=state->frameNumber; //back up current frame number so we can restore it after the load // new sensor values are provided pose.setLoadedSensors(state); - //cout << "Parsing sensor data" << endl; - if(!pose.loadBuffer(info.payload,info.payloadSize)) { + //cout << "Parsing sensor data " << info.payloadSize << " bytes" << endl; + //cout << string(info.payload,info.payloadSize) << endl; + size_t x=pose.loadBuffer(info.payload,info.payloadSize); + //cout << "read " << x << endl; + if(!x) { cerr << "ERROR: Corrupted sensor readings received by Main" << endl; return false; } @@ -235,9 +241,9 @@ if(!feedbackGenerated) { // no feedback, so just use all of the values we just loaded - // weight should already be set to 1 from load (otherwise would need pose.setWeights(1) or assign wsw.src values) - for(unsigned int i=0; i0,"zero weight found after loading"); // one would expect the compiler to no-op this loop ifndef DEBUG + // weight may be 0 if sensor which sent update doesn't provide joint positions + //for(unsigned int i=0; i0,"zero weight found after loading"); // one would expect the compiler to no-op this loop ifndef DEBUG } else if(zeroPIDFeedback) { // feedback is applied, regardless of PID settings if(feedback!=NULL) { @@ -252,22 +258,22 @@ for(unsigned int i=0; igetOutputCmd(i).value; - else - ASSERT(pose(i+PIDJointOffset).weight!=0,"zero weight found after loading"); + /*else // this can happen validly if starting up with zero PID and unknown positions + ASSERT(pose(i+PIDJointOffset).weight!=0,"zero weight found after loading");*/ wsw.setStatus(wsw.getStatus() | FEEDBACK_APPLIED); } else { // this process doesn't have the feedback, only fill in the non-feedback for(unsigned int i=0; iread(pose,wsw.src,erouter); //ASSERT((state->frameNumber-5)/4==wsw.frame,"state frame number and message serial number are desynchronized " << state->frameNumber << " vs " << wsw.frame); - state->frameNumber=wsw.frame*4+5; //lets dropped messages be skipped + state->frameNumber=(wsw.frame+1)*NumFrames+1; //lets dropped messages be skipped wsw.setStatus(wsw.getStatus() | SENSORS_APPLIED); } wsw.setComplete(feedbackGenerated && wsw.getStatus()==(SENSORS_APPLIED|FEEDBACK_APPLIED) || !feedbackGenerated && (wsw.getStatus()&SENSORS_APPLIED)!=0); @@ -281,7 +287,7 @@ unsigned int WorldStatePool::getCurrentReadState(WorldState*& tgt, bool block) { unsigned int toUse=-1U; if(block) { - while(toUse!=order.end()) { + while(toUse!=order.back()) { { MarkScope l(lock); if(toUse!=-1U) { //newer frame added while we were waiting @@ -294,7 +300,7 @@ #ifdef PLATFORM_APERIOS MarkScope wl(complete[toUse]); //now block until writing lock is released #else - MutexLockBase::getSemaphoreManager()->testZero(complete[toUse],true); //block until complete semaphore is released (set to 0) + MessageQueueBase::getSemaphoreManager()->testZero(complete[toUse],true); //block until complete semaphore is released (set to 0) #endif } } else { @@ -307,12 +313,23 @@ } if(idx==order.end()) { std::cerr << "ERROR: WorldStatePool unable to read state because none available" << std::endl; - return -1U; + //return -1U; + std::cerr << " falling into most recent buffer" << std::endl; + toUse=order.prev(order.end()); } reading[toUse]++; } //std::cout << ProcessID::getID() << " reading " << toUse << endl; //ASSERTRETVAL(toUse!=-1U,"toUse was not chosen!",-1U); +#ifdef DEBUG + if(toUse==-1U) { + std::cerr << "ERROR: WorldStatePool: toUse was not chosen!" << std::endl; + //return -1U; + std::cerr << " falling into most recent buffer" << std::endl; + toUse=order.prev(order.end()); + reading[toUse]++; + } +#endif tgt=&states[toUse]; return toUse; } @@ -326,7 +343,7 @@ #ifdef PLATFORM_APERIOS return static_cast(complete[idx].owner())==MutexLockBase::NO_OWNER; #else - return MutexLockBase::getSemaphoreManager()->testZero(complete[idx],false); + return MessageQueueBase::getSemaphoreManager()->testZero(complete[idx],false); #endif } @@ -388,7 +405,7 @@ complete[toUse].releaseAll(); //make sure it wasn't an incomplete frame that's being recycled complete[toUse].lock(ProcessID::getID()); #else - MutexLockBase::getSemaphoreManager()->setValue(complete[toUse],1); + MessageQueueBase::getSemaphoreManager()->setValue(complete[toUse],1); #endif } } @@ -417,7 +434,7 @@ if(!isComplete(i)) complete[i].unlock(); #else - MutexLockBase::getSemaphoreManager()->setValue(complete[i],0); + MessageQueueBase::getSemaphoreManager()->setValue(complete[i],0); #endif } writeLocks[i].unlock(); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/WorldStatePool.h ./Shared/WorldStatePool.h --- ../Tekkotsu_3.0/Shared/WorldStatePool.h 2006-09-19 01:39:33.000000000 -0400 +++ ./Shared/WorldStatePool.h 2007-11-11 18:57:26.000000000 -0500 @@ -41,6 +41,7 @@ */ class WorldStatePool : public Resource { public: + //! common base class for ReadRequest or WriteRequest class Request : public Resource::Data { protected: //! constructor, sets the WorldState point to be assigned, whether to block, and whether is an instance of ReadRequest @@ -139,13 +140,14 @@ //! returned by isUnread containing information parsed from the incoming message class UpdateInfo { public: + //! constructor UpdateInfo() #ifdef DEBUG - : verbose(false), frameNumber(-1U), filename(), dataInQueue(false), payload(NULL), payloadSize(0), intendedBuf(-1U) {} + : verbose(0), frameNumber(-1U), filename(), dataInQueue(false), payload(NULL), payloadSize(0), intendedBuf(-1U) {} #else - : verbose(false), frameNumber(-1U), filename(), dataInQueue(false), payload(NULL), payloadSize(0) {} + : verbose(0), frameNumber(-1U), filename(), dataInQueue(false), payload(NULL), payloadSize(0) {} #endif - bool verbose; //!< status of processing the message should be displayed + unsigned int verbose; //!< status of processing the message should be displayed unsigned int frameNumber; //!< serial number of the message std::string filename; //!< source of the data in the message bool dataInQueue; //!< sender indicates data is in the queue (if this is heartbeat, treat it as data) @@ -207,7 +209,7 @@ order_t order; //! shorthand to test if all three P, I, and D values are 0 for the specified joint index (relative to 0, not PIDJointOffset) - static bool isZeroPID(WorldState* s, unsigned int i) { return s->pids[i][0]==0 && s->pids[i][1]==0 && s->pids[i][2]==0; } + static bool isZeroPID(WorldState* s, unsigned int i) { return i>=PIDJointOffset && ipids[i][0]==0 && s->pids[i][1]==0 && s->pids[i][2]==0; } //! called when access to an entry for reading is requested unsigned int getCurrentReadState(WorldState*& tgt, bool block); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/XMLLoadSave.cc ./Shared/XMLLoadSave.cc --- ../Tekkotsu_3.0/Shared/XMLLoadSave.cc 2006-09-09 00:33:02.000000000 -0400 +++ ./Shared/XMLLoadSave.cc 2007-11-01 16:25:26.000000000 -0400 @@ -280,7 +280,7 @@ xmlNodePtr cur = FindRootXMLElement(xmldocument); loadXML(cur); } catch(const bad_format& err) { - reportError("During readParseTree:",err); + reportError("During XMLLoadSave::readParseTree:",err); xmlFreeDoc(xmldocument); xmldocument=NULL; } @@ -334,7 +334,7 @@ while(cur!=NULL && cur->type!=XML_ELEMENT_NODE) { if(cur->type==XML_COMMENT_NODE) { xmlChar* cont=xmlNodeGetContent(cur); - comment+=(char*)cont; + comment=(char*)cont; //only take last comment in series xmlFree(cont); } cur=cur->next; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/XMLLoadSave.h ./Shared/XMLLoadSave.h --- ../Tekkotsu_3.0/Shared/XMLLoadSave.h 2006-09-09 00:33:02.000000000 -0400 +++ ./Shared/XMLLoadSave.h 2007-01-30 17:56:20.000000000 -0500 @@ -21,7 +21,7 @@ public: //! an exception to be thrown when a bad XML file is parsed, allows file position information to be passed to the user - class bad_format : std::exception { + class bad_format : public std::exception { public: //!constructor bad_format(xmlNode * node) throw() : std::exception(), node_(node), msg_("invalid format in plist") {} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/attributes.h ./Shared/attributes.h --- ../Tekkotsu_3.0/Shared/attributes.h 2006-09-16 02:01:41.000000000 -0400 +++ ./Shared/attributes.h 2007-02-06 14:40:51.000000000 -0500 @@ -86,6 +86,21 @@ #endif +#ifdef _MSC_VER +# ifdef BUILDING_DLL +# define EXPORT_SYMBOL __declspec(dllexport) +# else +# define EXPORT_SYMBOL __declspec(dllimport) +# endif +# define LOCAL_SYMBOL +#elif defined(__GNUC__) && __GNUC__ >= 4 +# define EXPORT_SYMBOL __attribute__ ((visibility("default"))) +# define LOCAL_SYMBOL __attribute__ ((visibility("hidden"))) +#else +# define EXPORT_SYMBOL +# define LOCAL_SYMBOL +#endif + /*! @file * @brief Defines variants of the __attribute__ macros to provide better portability * @author Robert Love (Creator), ejt (more version specificity) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/debuget.h ./Shared/debuget.h --- ../Tekkotsu_3.0/Shared/debuget.h 2006-09-27 17:12:31.000000000 -0400 +++ ./Shared/debuget.h 2007-11-01 14:51:37.000000000 -0400 @@ -27,13 +27,13 @@ #ifdef DEBUG //! if the bool b is false, std::cout the string - #define ASSERT(b,msgstream) {if(!(b)) { std::stringstream ss; ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,ss.str().c_str()); }} + #define ASSERT(b,msgstream) {if(!(b)) { std::stringstream DEBUGET_ss; DEBUGET_ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,DEBUGET_ss.str().c_str()); }} //! if the bool b is false, std::cout the string and return - #define ASSERTRET(b,msgstream) {if(!(b)) { std::stringstream ss; ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,ss.str().c_str()); return; }} + #define ASSERTRET(b,msgstream) {if(!(b)) { std::stringstream DEBUGET_ss; DEBUGET_ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,DEBUGET_ss.str().c_str()); return; }} //! if the bool b is false, std::cout the string and return the value - #define ASSERTRETVAL(b,msgstream,v) {if(!(b)) { std::stringstream ss; ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,ss.str().c_str()); return v; }} + #define ASSERTRETVAL(b,msgstream,v) {if(!(b)) { std::stringstream DEBUGET_ss; DEBUGET_ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,DEBUGET_ss.str().c_str()); return v; }} //! if the bool b is false, std::cout the string and exit(x) - #define ASSERTFATAL(b,msgstream,x) {if(!(b)) { std::stringstream ss; ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,ss.str().c_str()); exit(x); }} + #define ASSERTFATAL(b,msgstream,x) {if(!(b)) { std::stringstream DEBUGET_ss; DEBUGET_ss << msgstream; debuget::displayAssert(__FILE__,__LINE__,DEBUGET_ss.str().c_str()); exit(x); }} #else //! if the bool b is false, std::cout the string #define ASSERT(b,msgstream) {} diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/get_time.cc ./Shared/get_time.cc --- ../Tekkotsu_3.0/Shared/get_time.cc 2006-10-03 22:40:42.000000000 -0400 +++ ./Shared/get_time.cc 2007-11-09 14:01:14.000000000 -0500 @@ -1,23 +1,33 @@ #include "get_time.h" #ifdef PLATFORM_APERIOS + #include unsigned int get_time() { static struct SystemTime time; GetSystemTime(&time); return time.seconds*1000+time.useconds/1000; } + #else + #include "TimeET.h" namespace project_get_time { + unsigned int simulation_time=-1U; + + //! provides default implementation of #get_time_callback -- starts a TimeET instance on the first call and then returns its age thereafter unsigned int default_get_time_callback() { static TimeET first; return static_cast(first.Age().Value()*1000); } + unsigned int (*get_time_callback)()=&default_get_time_callback; + float (*get_timeScale_callback)()=NULL; + } + #endif /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_istream_src.cc ./Shared/jpeg-6b/jpeg_istream_src.cc --- ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_istream_src.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/jpeg-6b/jpeg_istream_src.cc 2007-07-19 18:48:35.000000000 -0400 @@ -0,0 +1,68 @@ +#include "jpeg_istream_src.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/* Theoretically, could be used to load several consecutive + * JPEGs from memory, but not really tested, some tweaks + * would probably be required */ + +//#include +#include + +typedef struct { + struct jpeg_source_mgr pub; + std::istream * is; + char c; +} JPEGStreamSource; + +static void init_sourceFunc(j_decompress_ptr cinfo) { + JPEGStreamSource *src = (JPEGStreamSource*)cinfo->src; + src->is->get(src->c); + src->pub.next_input_byte = (JOCTET*)&src->c; + src->pub.bytes_in_buffer = sizeof(char); +} +static boolean fill_input_bufferFunc(j_decompress_ptr cinfo) { + JPEGStreamSource *src = (JPEGStreamSource*)cinfo->src; + if(!src->is->get(src->c)) + return false; + src->pub.next_input_byte = (JOCTET*)&src->c; + src->pub.bytes_in_buffer = 1; + return true; +} +static void skip_input_dataFunc(j_decompress_ptr cinfo, long num_bytes) { + JPEGStreamSource *src = (JPEGStreamSource*)cinfo->src; + if (num_bytes > 0) { + if ((size_t)num_bytes > src->pub.bytes_in_buffer) { + num_bytes -= src->pub.bytes_in_buffer; + src->pub.bytes_in_buffer = 0; + src->is->ignore(num_bytes); + } else { + src->pub.bytes_in_buffer -= num_bytes; + } + } +} +static void term_sourceFunc(j_decompress_ptr) {} + +GLOBAL(void) +jpeg_istream_src (j_decompress_ptr cinfo, std::istream& inStream) { + JPEGStreamSource *src; + + if (cinfo->src == NULL) /* first time for this JPEG object? */ + cinfo->src = (struct jpeg_source_mgr *) (*cinfo->mem->alloc_small) ((j_common_ptr) cinfo, JPOOL_PERMANENT, sizeof(JPEGStreamSource)); + + src = (JPEGStreamSource*) cinfo->src; + src->pub.init_source = init_sourceFunc; + src->pub.fill_input_buffer = fill_input_bufferFunc; + src->pub.skip_input_data = skip_input_dataFunc; + src->pub.resync_to_restart = jpeg_resync_to_restart; /* use default method */ + src->pub.term_source = term_sourceFunc; + src->is = &inStream; + src->pub.next_input_byte = (JOCTET*)&src->c; + src->pub.bytes_in_buffer = 0; +} + +#ifdef __cplusplus +} +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_istream_src.h ./Shared/jpeg-6b/jpeg_istream_src.h --- ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_istream_src.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/jpeg-6b/jpeg_istream_src.h 2007-07-19 18:48:35.000000000 -0400 @@ -0,0 +1,15 @@ +#ifndef jpeg_istream_src_h_DEFINED +#define jpeg_istream_src_h_DEFINED + +#include + +#ifdef __cplusplus +extern "C" { +#endif +#include +void jpeg_istream_src (j_decompress_ptr cinfo, std::istream& inStream); +#ifdef __cplusplus +} +#endif + +#endif /* jpeg_istream_dest_h_DEFINED */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_mem_src.cc ./Shared/jpeg-6b/jpeg_mem_src.cc --- ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_mem_src.cc 2006-06-23 17:55:40.000000000 -0400 +++ ./Shared/jpeg-6b/jpeg_mem_src.cc 2007-07-19 18:49:06.000000000 -0400 @@ -38,9 +38,9 @@ } static boolean fill_input_bufferFunc(j_decompress_ptr JPEGMEMSRC_UNUSED(cinfo)) { JPEGMEMSRC_BODY_UNUSED(cinfo); - return FALSE; + return false; } -void skip_input_dataFunc(j_decompress_ptr cinfo, long num_bytes) { +static void skip_input_dataFunc(j_decompress_ptr cinfo, long num_bytes) { JPEGSource *src = (JPEGSource*)cinfo->src; if (num_bytes > 0) { if ((size_t)num_bytes > src->pub.bytes_in_buffer) @@ -51,7 +51,7 @@ } } } -void term_sourceFunc(j_decompress_ptr cinfo) { +static void term_sourceFunc(j_decompress_ptr cinfo) { JPEGSource* src = (JPEGSource*) cinfo->src; if(src->pub.next_input_byte==NULL) src->lastused=0; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_mem_src.h ./Shared/jpeg-6b/jpeg_mem_src.h --- ../Tekkotsu_3.0/Shared/jpeg-6b/jpeg_mem_src.h 2006-06-23 17:55:40.000000000 -0400 +++ ./Shared/jpeg-6b/jpeg_mem_src.h 2007-07-19 18:49:24.000000000 -0400 @@ -9,7 +9,6 @@ #endif #include void jpeg_mem_src (j_decompress_ptr cinfo, JOCTET * inbuf, size_t maxlen); -int jpeg_mem_read (j_compress_ptr cinfo); #ifdef __cplusplus } #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/jpeg-6b/write_jpeg.cc ./Shared/jpeg-6b/write_jpeg.cc --- ../Tekkotsu_3.0/Shared/jpeg-6b/write_jpeg.cc 2005-06-01 01:47:53.000000000 -0400 +++ ./Shared/jpeg-6b/write_jpeg.cc 2007-04-09 18:23:42.000000000 -0400 @@ -48,9 +48,9 @@ jpeg_set_defaults(&cinfo); jpeg_set_quality(&cinfo, - quality, TRUE /* limit to baseline-JPEG values */); + quality, true /* limit to baseline-JPEG values */); - jpeg_start_compress(&cinfo, TRUE); + jpeg_start_compress(&cinfo, true); row_stride = image_width * 3; /* JSAMPLEs per row in image_buffer */ @@ -93,9 +93,9 @@ jpeg_set_defaults(&cinfo); jpeg_set_quality(&cinfo, - quality, TRUE /* limit to baseline-JPEG values */); + quality, true /* limit to baseline-JPEG values */); - jpeg_start_compress(&cinfo, TRUE); + jpeg_start_compress(&cinfo, true); row_stride = image_width * 3; /* JSAMPLEs per row in image_buffer */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/mathutils.h ./Shared/mathutils.h --- ../Tekkotsu_3.0/Shared/mathutils.h 2005-10-14 18:25:38.000000000 -0400 +++ ./Shared/mathutils.h 2007-11-09 14:01:14.000000000 -0500 @@ -4,34 +4,44 @@ #include +//! a variety of handy mathematical functions, many of which are templated namespace mathutils { - template - inline num squareDistance(num x1, num ya, num x2, num yb) { - return (x1-x2)*(x1-x2)+(ya-yb)*(ya-yb); - } - - template - inline num distance(num x1, num ya, num x2, num yb) { - return sqrt(squareDistance(x1, ya, x2, yb)); - } - - template - inline num limitRange(num n, num low, num high) { - if (nhigh) n=high; - return n; - } - - template - inline num squared(num n) { - return n*n; - } - - template - inline num abs_t(num n) { - return (n>-n)?n:-n; - } - + //! euclidean distance of two points (squared), see distance() + template + inline num squareDistance(num x1, num ya, num x2, num yb) { + return (x1-x2)*(x1-x2)+(ya-yb)*(ya-yb); + } + + //! euclidean distance of two points, see squareDistance() + template + inline num distance(num x1, num ya, num x2, num yb) { + return sqrt(squareDistance(x1, ya, x2, yb)); + } + + //! Clips @a n to a minimum of @a low or maximum of @a high. + /*! If @a low and @a high are inverted, high is returned. */ + template + inline num limitRange(num n, num low, num high) { + if (nhigh) n=high; + return n; + } + + //! returns n*n; + template + inline num squared(num n) { + return n*n; + } + + //! returns the maximum of n or -n + template + inline num abs_t(num n) { + return (n>-n)?n:-n; + } + + //! Returns the log base 2 of a number + /*! This template implementation does a bit shifting method appropriate for + * integers. Specializations are provided for float and double to use the 'real' log() */ template inline num log2t(num x) { num ans=0; @@ -44,25 +54,29 @@ } return ans; } + //! returns the log base 2 for a 'float' value template <> inline float log2t(float x) { return log(x)/M_LN2; } + //! returns the log base 2 for a 'double' value template <> inline double log2t(double x) { return log(x)/M_LN2; } - - template - inline num deg2rad(num x) { - return x*M_PI/180; - } - - template - inline num rad2deg(num x) { - return x*180/M_PI; - } - + + //! converts from degrees to radians + template + inline num deg2rad(num x) { + return x*M_PI/180; + } + + //! converts from radians to degrees + template + inline num rad2deg(num x) { + return x*180/M_PI; + } + } #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/Makefile ./Shared/newmat/Makefile --- ../Tekkotsu_3.0/Shared/newmat/Makefile 2006-03-28 12:08:21.000000000 -0500 +++ ./Shared/newmat/Makefile 2007-11-12 23:14:46.000000000 -0500 @@ -6,22 +6,23 @@ ifndef TEKKOTSU_ENVIRONMENT_CONFIGURATION $(error An error has occured, TEKKOTSU_ENVIRONMENT_CONFIGURATION was not defined) endif -TEKKOTSU_ROOT:=../.. +TEKKOTSU_ROOT:=$(shell cd ../.. && pwd) include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g') BUILDDIR=$(TK_LIB_BD)/Shared/newmat SRCSUFFIX=.cpp # You may need to adjust these cc options: -CXXFLAGS= $(if $(TEKKOTSU_DEBUG),-g -fno-inline -DDEBUG,) \ - -Wall -W -Wlarger-than-8192 -Wpointer-arith -Wcast-qual \ +CXXFLAGS:= -g $(if $(TEKKOTSU_DEBUG),-g -fno-inline -DDEBUG,) \ + -Wall -W -Wlarger-than-8192 -Wpointer-arith \ -Woverloaded-virtual -Wdeprecated -Wnon-virtual-dtor \ - -O3 -frename-registers -fomit-frame-pointer -fno-common \ - -DWANT_MATH -DWANT_STREAM -DWANT_STRING + -fmessage-length=0 \ + -DWANT_MATH -DWANT_STREAM -DWANT_STRING $(CXXFLAGS) $(ENV_CXXFLAGS) +# -O3 -frename-registers -fomit-frame-pointer -fno-common \ # -Wshadow -Weffc++ # Link-time cc options: -LDFLAGS= +LDFLAGS:= $(LDFLAGS) # To link any special libraries, add the necessary -l commands here. LDLIBS= @@ -60,6 +61,9 @@ # newmat1.o newmat2.o newmat3.o newmat4.o newmat5.o newmat6.o newmat7.o newmat8.o newmat9.o newmatex.o bandmat.o submat.o myexcept.o cholesky.o evalue.o fft.o hholder.o jacobi.o newfft.o sort.o svd.o newmatrm.o newmatnl.o all: $(BUILDDIR)/libnewmat.a +ifneq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS) +all: $(BUILDDIR)/libnewmat.$(if $(findstring Darwin,$(shell uname)),dylib,so) +endif .PHONY: all clean @@ -69,6 +73,16 @@ @$(AR) $@ $(LIBOBJECTS) @$(AR2) $@ +$(BUILDDIR)/libnewmat.dylib: $(LIBOBJECTS) + $(RM) $@ + @echo "Linking $@..." + @libtool -dynamic -undefined dynamic_lookup -o $@ $(LIBOBJECTS); + +$(BUILDDIR)/libnewmat.so: $(LIBOBJECTS) + $(RM) $@ + @echo "Linking $@..." + @$(CXX) -shared -o $@ $(LIBOBJECTS); + clean: $(RM) *.o *.a *.log core $(PCH) $(RM) -r $(BUILDDIR) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/include.h ./Shared/newmat/include.h --- ../Tekkotsu_3.0/Shared/newmat/include.h 2004-07-01 20:19:33.000000000 -0400 +++ ./Shared/newmat/include.h 2007-11-11 18:57:27.000000000 -0500 @@ -80,7 +80,6 @@ #ifdef WANT_FSTREAM #include #endif - using namespace std; #else #define DEFAULT_HEADER // use AT&T style header diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/myexcept.cpp ./Shared/newmat/myexcept.cpp --- ../Tekkotsu_3.0/Shared/newmat/myexcept.cpp 2006-03-23 19:37:14.000000000 -0500 +++ ./Shared/newmat/myexcept.cpp 2007-11-11 18:57:27.000000000 -0500 @@ -15,6 +15,8 @@ #include "myexcept.h" // for exception handling +using namespace std; + #ifdef use_namespace namespace RBD_COMMON { #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/newmat.h ./Shared/newmat/newmat.h --- ../Tekkotsu_3.0/Shared/newmat/newmat.h 2006-03-21 16:30:02.000000000 -0500 +++ ./Shared/newmat/newmat.h 2007-02-06 17:25:06.000000000 -0500 @@ -1401,6 +1401,7 @@ friend class GeneralMatrix; friend class GenericMatrix; public: + ShiftedMatrix(const ShiftedMatrix& im) : BaseMatrix(im), bm(im.bm), f(im.f) {} ~ShiftedMatrix() {} GeneralMatrix* Evaluate(MatrixType mt=MatrixTypeUnSp); friend ShiftedMatrix operator+(Real f, const BaseMatrix& BM); @@ -1428,6 +1429,7 @@ friend class GeneralMatrix; friend class GenericMatrix; public: + ScaledMatrix(const ScaledMatrix& im) : ShiftedMatrix(im) {} ~ScaledMatrix() {} GeneralMatrix* Evaluate(MatrixType mt=MatrixTypeUnSp); MatrixBandWidth BandWidth() const; @@ -1444,6 +1446,7 @@ private: friend class BaseMatrix; public: + NegatedMatrix(const NegatedMatrix& im) : BaseMatrix(im), bm(im.bm) {} ~NegatedMatrix() {} GeneralMatrix* Evaluate(MatrixType mt=MatrixTypeUnSp); MatrixBandWidth BandWidth() const; @@ -1809,6 +1812,17 @@ inline bool operator>(const BaseMatrix& A, const BaseMatrix&) { A.IEQND(); return true; } +// these had been prototypes via 'friend' declaration, but +// apparently newer versions of gcc now require an explicit prototype +bool Rectangular(MatrixType a, MatrixType b, MatrixType c); +bool Compare(const MatrixType&, MatrixType&); +Real DotProduct(const Matrix& A, const Matrix& B); +SPMatrix SP(const BaseMatrix&, const BaseMatrix&); +KPMatrix KP(const BaseMatrix&, const BaseMatrix&); +ShiftedMatrix operator+(Real f, const BaseMatrix& BM); +NegShiftedMatrix operator-(Real, const BaseMatrix&); +ScaledMatrix operator*(Real f, const BaseMatrix& BM); + bool IsZero(const BaseMatrix& A); Matrix CrossProduct(const Matrix& A, const Matrix& B); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/newmat9.cpp ./Shared/newmat/newmat9.cpp --- ../Tekkotsu_3.0/Shared/newmat/newmat9.cpp 2005-07-25 23:21:59.000000000 -0400 +++ ./Shared/newmat/newmat9.cpp 2007-11-11 18:57:27.000000000 -0500 @@ -14,6 +14,8 @@ #include "newmatrc.h" #include +using namespace std; + #ifdef use_namespace namespace NEWMAT { #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/newmatio.h ./Shared/newmat/newmatio.h --- ../Tekkotsu_3.0/Shared/newmat/newmatio.h 2004-12-14 22:56:28.000000000 -0500 +++ ./Shared/newmat/newmatio.h 2007-11-11 18:57:27.000000000 -0500 @@ -19,9 +19,9 @@ /**************************** input/output *****************************/ -ostream& operator<<(ostream&, const BaseMatrix&); +std::ostream& operator<<(std::ostream&, const BaseMatrix&); -ostream& operator<<(ostream&, const GeneralMatrix&); +std::ostream& operator<<(std::ostream&, const GeneralMatrix&); /**************************** Matlab-code printer *****************************/ @@ -31,7 +31,7 @@ printmat(const Matrix &m) : mat(m) {} }; -ostream& operator<<(ostream&, const printmat&); +std::ostream& operator<<(std::ostream&, const printmat&); /**************************** Old stuff *****************************/ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/newmatnl.cpp ./Shared/newmat/newmatnl.cpp --- ../Tekkotsu_3.0/Shared/newmat/newmatnl.cpp 2005-07-25 23:21:59.000000000 -0400 +++ ./Shared/newmat/newmatnl.cpp 2007-11-11 18:57:27.000000000 -0500 @@ -15,12 +15,12 @@ #include "newmatnl.h" #include +using namespace std; + #ifdef use_namespace namespace NEWMAT { #endif - - void FindMaximum2::Fit(ColumnVector& Theta, int n_it) { Tracer tr("FindMaximum2::Fit"); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/newmat/precisio.h ./Shared/newmat/precisio.h --- ../Tekkotsu_3.0/Shared/newmat/precisio.h 2004-06-16 17:16:41.000000000 -0400 +++ ./Shared/newmat/precisio.h 2007-11-21 15:56:33.000000000 -0500 @@ -5,6 +5,7 @@ #ifdef _STANDARD_ // standard library available #include +#include #endif #ifdef use_namespace @@ -13,51 +14,49 @@ #ifdef _STANDARD_ // standard library available -using namespace std; - class FloatingPointPrecision { public: static int Dig() // number of decimal digits or precision - { return numeric_limits::digits10 ; } + { return std::numeric_limits::digits10 ; } static Real Epsilon() // smallest number such that 1+Eps!=Eps - { return numeric_limits::epsilon(); } + { return std::numeric_limits::epsilon(); } static int Mantissa() // bits in mantisa - { return numeric_limits::digits; } + { return std::numeric_limits::digits; } static Real Maximum() // maximum value - { return numeric_limits::max(); } + { return std::numeric_limits::max(); } static int MaximumDecimalExponent() // maximum decimal exponent - { return numeric_limits::max_exponent10; } + { return std::numeric_limits::max_exponent10; } static int MaximumExponent() // maximum binary exponent - { return numeric_limits::max_exponent; } + { return std::numeric_limits::max_exponent; } static Real LnMaximum() // natural log of maximum - { return (Real)log(Maximum()); } + { return (Real)std::log(Maximum()); } static Real Minimum() // minimum positive value - { return numeric_limits::min(); } + { return std::numeric_limits::min(); } static int MinimumDecimalExponent() // minimum decimal exponent - { return numeric_limits::min_exponent10; } + { return std::numeric_limits::min_exponent10; } static int MinimumExponent() // minimum binary exponent - { return numeric_limits::min_exponent; } + { return std::numeric_limits::min_exponent; } static Real LnMinimum() // natural log of minimum - { return (Real)log(Minimum()); } + { return (Real)std::log(Minimum()); } static int Radix() // exponent radix - { return numeric_limits::radix; } + { return std::numeric_limits::radix; } static int Rounds() // addition rounding (1 = does round) { - return numeric_limits::round_style == - round_to_nearest ? 1 : 0; + return std::numeric_limits::round_style == + std::round_to_nearest ? 1 : 0; } }; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plist.cc ./Shared/plist.cc --- ../Tekkotsu_3.0/Shared/plist.cc 2006-09-16 16:11:53.000000000 -0400 +++ ./Shared/plist.cc 2007-11-08 14:48:47.000000000 -0500 @@ -6,19 +6,23 @@ ObjectBase* loadXML(xmlNode* node) { ObjectBase* obj=NULL; - if(ObjectBase::xNodeHasName(node,"array")==0) - obj=new Array(true); - else if(ObjectBase::xNodeHasName(node,"dict")==0) - obj=new Dictionary(true); - else if(ObjectBase::xNodeHasName(node,"real")==0) + if(ObjectBase::xNodeHasName(node,"array")) { + Array * a=new Array; + a->setLoadSavePolicy(Collection::SYNC,Collection::SYNC); // just in case defaults change... + obj=a; + } else if(ObjectBase::xNodeHasName(node,"dict")) { + Dictionary * d=new Dictionary; + d->setLoadSavePolicy(Collection::SYNC,Collection::SYNC); // just in case defaults change... + obj=d; + } else if(ObjectBase::xNodeHasName(node,"real")) obj=new Primitive; - else if(ObjectBase::xNodeHasName(node,"integer")==0) + else if(ObjectBase::xNodeHasName(node,"integer")) obj=new Primitive; - else if(ObjectBase::xNodeHasName(node,"string")==0) + else if(ObjectBase::xNodeHasName(node,"string")) obj=new Primitive; - else if(ObjectBase::xNodeHasName(node,"true")==0) + else if(ObjectBase::xNodeHasName(node,"true")) obj=new Primitive; - else if(ObjectBase::xNodeHasName(node,"false")==0) + else if(ObjectBase::xNodeHasName(node,"false")) obj=new Primitive; else return NULL; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plist.h ./Shared/plist.h --- ../Tekkotsu_3.0/Shared/plist.h 2006-09-09 00:33:02.000000000 -0400 +++ ./Shared/plist.h 2007-11-08 22:33:58.000000000 -0500 @@ -6,6 +6,36 @@ #include "plistPrimitives.h" #include "plistCollections.h" +/*! The plist namespace provides convenient serialization for persistent storage, + * dynamic introspection, and polymorphic primitive values. The classes happen + * to use Apple's XML-based "property list" format for serialization, using libxml2 + * for the low level parsing. + * + * The choice of storage format was based on a desire for human readability, + * including per-value comments and inline documentation, as well as the desire + * to make use of syntax hilighting or high-level editing tools. + * + * Individual values are based on templated instances of the Primitive class, + * while groups of values are based on the Collection interface. Currently, the + * concrete collections available are Array (one dimensional ordered list of mixed + * primitive types), ArrayOf (ordered list of a single type), or Dictionary (unordered + * mapping from string names to mixed primitives). + * + * Generally, there are two ways you might use the functionality contained within + * this namespace. One is as an external storage interface, such as the STL + * vector and map classes are used. This might be only a intermediary instance + * for conversion to and from existing data structures, as a higher-level interface + * than directly accessing libxml. + * + * However, to fully benefit from this namespace's functionality, you will generally + * want your classes to inherit from plist::Dictionary, define your members + * as public plist Primitives and Collections, and register listeners for notification + * when these values are modified (either by loading from file or programmatic + * modification.) + * + * Example usage is shown below, you can find this code and more in Tekkotsu/tools/test/plist/. + * @include plist-example.cc + */ namespace plist { //! From the name of @a node, will instantiate a new ObjectBase subclass to load it diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plistBase.cc ./Shared/plistBase.cc --- ../Tekkotsu_3.0/Shared/plistBase.cc 2005-12-22 16:32:28.000000000 -0500 +++ ./Shared/plistBase.cc 2007-11-14 21:00:50.000000000 -0500 @@ -1,4 +1,5 @@ #include "plistBase.h" +#include "plistPrimitives.h" #include #include @@ -17,27 +18,30 @@ XMLLoadSave::setParseTree(doc); if(xmldocument==NULL) return; + xmlNode* root=XMLLoadSave::FindRootXMLElement(doc); + if(root != NULL && xmlStrcmp(root->name, (const xmlChar *)"plist")==0) + return; xmlNodePtr cur = xmlNewNode(NULL,(const xmlChar*)"plist"); xmlNewProp(cur,(const xmlChar*)"version",(const xmlChar*)"1.0"); xmlDocSetRootElement(xmldocument,cur); - xmlCreateIntSubset(xmldocument,(const xmlChar*)"plist",(const xmlChar*)"-//Apple Computer//DTD PLIST 1.0//EN",(const xmlChar*)"http://www.apple.com/DTDs/PropertyList-1.0.dtd"); + xmlCreateIntSubset(xmldocument,(const xmlChar*)"plist",(const xmlChar*)"-//Apple//DTD PLIST 1.0//EN",(const xmlChar*)"http://www.apple.com/DTDs/PropertyList-1.0.dtd"); } xmlNode* ObjectBase::FindRootXMLElement(xmlDoc* doc) const { if(doc==NULL) return NULL; xmlNode* root=XMLLoadSave::FindRootXMLElement(doc); + if(root == NULL) + throw bad_format(root,"Error: plist read empty document"); + if(xmlStrcmp(root->name, (const xmlChar *)"plist")) + throw bad_format(root,"Error: plist read document of the wrong type, root node != plist"); string filename; if(doc->name!=NULL && doc->name[0]!='\0') { filename="document '"; filename+=doc->name; filename+="' "; } - if (root == NULL) - throw bad_format(root,"Error: plist read empty document"); - if (xmlStrcmp(root->name, (const xmlChar *)"plist")) - throw bad_format(root,"Error: plist read document of the wrong type, root node != plist"); - if (!xmlHasProp(root,(const xmlChar*)"version")) + if(!xmlHasProp(root,(const xmlChar*)"version")) cerr << "Warning: plist " << filename << "does not carry version number, assuming 1.0" << endl; else { xmlChar* strv=xmlGetProp(root,(const xmlChar*)"version"); @@ -67,16 +71,37 @@ xmlNode* ObjectBase::xNodeGetChildren(xmlNode* node) { return node->children; } + xmlNode* ObjectBase::xNodeGetLastChild(xmlNode* node) { + return node->last; + } xmlNode* ObjectBase::xNodeGetNextNode(xmlNode* node) { return node->next; } + xmlNode* ObjectBase::xNodeGetPrevNode(xmlNode* node) { + return node->prev; + } xmlNode* ObjectBase::xNodeGetParent(xmlNode* node) { return node->parent; } xmlDoc* ObjectBase::xNodeGetDoc(xmlNode* node) { return node->doc; } - + bool ObjectBase::xNodeIsText(xmlNode* node) { + return node->type==XML_TEXT_NODE; + } + bool ObjectBase::xNodeIsElement(xmlNode* node) { + return node->type==XML_ELEMENT_NODE; + } + bool ObjectBase::xNodeIsComment(xmlNode* node) { + return node->type==XML_COMMENT_NODE; + } + + + PrimitiveBase& PrimitiveBase::operator=(const Primitive& v) { *this = static_cast(v); return *this; } + PrimitiveBase& PrimitiveBase::operator=(const std::string& v) { *this=static_cast(Primitive(v)); return *this; } + PrimitiveBase& PrimitiveBase::operator=(long v) { *this=Primitive(v); return *this; } + PrimitiveBase& PrimitiveBase::operator=(unsigned long v) { *this=Primitive(v); return *this; } + PrimitiveBase& PrimitiveBase::operator=(double v) { *this=Primitive(v); return *this; } PrimitiveBase::~PrimitiveBase() { delete primitiveListeners; @@ -86,14 +111,14 @@ void PrimitiveBase::addPrimitiveListener(PrimitiveListener* vl) { if(vl!=NULL) { if(primitiveListeners==NULL) - primitiveListeners=new std::list; - primitiveListeners->push_back(vl); + primitiveListeners=new std::set; + primitiveListeners->insert(vl); } } void PrimitiveBase::removePrimitiveListener(PrimitiveListener* vl) { if(primitiveListeners==NULL) return; - std::list::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl); + std::set::iterator it=primitiveListeners->find(vl); if(it!=primitiveListeners->end()) { primitiveListeners->erase(it); if(primitiveListeners->empty()) { @@ -107,16 +132,26 @@ return false; if(primitiveListeners==NULL) return false; - std::list::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl); + std::set::iterator it=primitiveListeners->find(vl); return it!=primitiveListeners->end(); } - void PrimitiveBase::fireValueChanged() const { + void PrimitiveBase::fireValueChanged(bool touchOnly) const { if(primitiveListeners==NULL) return; - std::list::const_iterator it=primitiveListeners->begin(); - while(it!=primitiveListeners->end()) { - std::list::const_iterator cur=it++; //increment early in case the listener changes subscription - (*cur)->plistValueChanged(*this); + // copy primitive listeners so we aren't screwed if a listener is removed during processing, particularly if it's the *last* listener + std::set pls=*primitiveListeners; + if(touchOnly) { + for(std::set::const_iterator it=pls.begin(); primitiveListeners!=NULL && it!=pls.end(); ++it) { + // make sure current listener hasn't been removed + if(primitiveListeners->find(*it)!=primitiveListeners->end()) + (*it)->plistValueTouched(*this); + } + } else { + for(std::set::const_iterator it=pls.begin(); primitiveListeners!=NULL && it!=pls.end(); ++it) { + // make sure current listener hasn't been removed + if(primitiveListeners->find(*it)!=primitiveListeners->end()) + (*it)->plistValueChanged(*this); + } } } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plistBase.h ./Shared/plistBase.h --- ../Tekkotsu_3.0/Shared/plistBase.h 2006-09-22 16:29:45.000000000 -0400 +++ ./Shared/plistBase.h 2007-11-14 21:44:06.000000000 -0500 @@ -9,10 +9,11 @@ #include #include #include -#include +#include +#include /* - From: + From: @@ -71,7 +72,9 @@ //! implements clone() using polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise; returns @a RETVAL # define PLIST_CLONE_IMP(TYPE,RETVAL) TYPE* TYPE::clone() const { return RETVAL; } //! implements clone() using templated polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise; returns @a RETVAL -# define PLIST_CLONE_IMPT(TEMPL,TYPE,RETVAL) template TYPE* TYPE::clone() const { return RETVAL; } +# define PLIST_CLONE_IMPT(TEMPL,TYPE,RETVAL) template TYPE* TYPE::clone() const { return RETVAL; } +//! implements clone() using templated polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise; returns @a RETVAL +# define PLIST_CLONE_IMPT2(TEMPL1,TEMPL2,TYPE,RETVAL) template TYPE* TYPE::clone() const { return RETVAL; } # else //! declares clone() using polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise; returns @a RETVAL # define PLIST_CLONE_DEF(TYPE,RETVAL) virtual Cloneable* clone() const { return RETVAL; } @@ -79,6 +82,8 @@ # define PLIST_CLONE_IMP(TYPE,RETVAL) //! implements clone() using templated polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise; returns @a RETVAL # define PLIST_CLONE_IMPT(TEMPL,TYPE,RETVAL) +//! implements clone() using templated polymorphic return type @a TYPE if supported by current version of gcc, Cloneable otherwise; returns @a RETVAL +# define PLIST_CLONE_IMPT2(TEMPL1,TEMPL2,TYPE,RETVAL) # endif #endif @@ -98,6 +103,12 @@ * accidental modification of @a pl's value -- use a const cast * if you're sure you know what you're doing */ virtual void plistValueChanged(const PrimitiveBase& pl)=0; + + //! This will be called whenever a plist you have registered with is reassigned is current value (usually something you'll want to ignore...) + /*! Argument is const to help you avoid infinite recursion from an + * accidental modification of its value -- use a const cast + * if you're sure you know what you're doing */ + virtual void plistValueTouched(const PrimitiveBase& /*pl*/) {} }; class ObjectBase; @@ -114,16 +125,32 @@ }; //! This base class provides the root functionality for all plist entities -- Dictionary and the various templated subclasses of PrimitiveBase - /*! The subclasses may throw std::bad_format if the - * document is poorly structured or bad values are found. */ + /*! The subclasses may throw std::bad_format if the document is poorly structured or bad values are found. */ class ObjectBase : public XMLLoadSave, public Cloneable { friend ObjectBase* loadXML(xmlNode* node); public: + //! specifies that collections (e.g. plist::Array or plist::Dictionary) of these abstract base classes (ObjectBase, PrimitiveBase) can convert any primitive type to a plist::Primitive wrapper + template struct conversion_policy { typedef typename U::template WrapValueConversion value_conversion; }; + ObjectBase(); //!< constructor virtual ~ObjectBase()=0; //!< destructor + //! polymorphic assignment (throws std::bad_cast if the assignment is between invalid types, i.e. a primitive and a collection, or different collection types) + virtual void set(const ObjectBase&)=0; + + //! casting operator: return current value as specified type (throws std::runtime_error exception if bad cast, e.g. dictionary or array to value type) + /*! The implementation for this function is defined by a series of specializations. + * This allows you to add casts for additional user-defined types, as well as get + * compile time error if you attempt to cast to an unsupported type. + * (I really wish we had virtual templated functions...) */ + template T to() const; + //! return current value as a string virtual std::string toString() const=0; + //! return current value as an (long) integer (throws std::runtime_error exception if incompatable, e.g. dictionary or array to value type) + virtual long toLong() const=0; + //! return current value as a double (throws std::runtime_error exception if incompatable, e.g. dictionary or array to value type) + virtual double toDouble() const=0; //! subclasses are expected to provide a working implementation virtual void loadXML(xmlNode* node)=0; @@ -134,6 +161,13 @@ PLIST_CLONE_ABS(ObjectBase); protected: + //! polymorphic assignment operator, see assign() + /*! This is protected for two reasons: one, so you don't accidentally use it via simple '=' statement, + * and two, to avoid 'operator= was hidden' warnings in every base class (because they keep + * reintroducing their default operator=(), hiding/shadowing this one (if it were virtual, as it would + * need to be to take on the role filled by assign(). */ + ObjectBase& operator=(const ObjectBase&) { return *this; } + //!@name Inherited from XMLLoadSave virtual void setParseTree(xmlDoc * doc) const; virtual xmlNode* FindRootXMLElement(xmlDoc* doc) const; @@ -144,9 +178,14 @@ static bool xNodeHasName(xmlNode* node, const char* name); //!< returns true if the name of @a node matches @a name static const xmlChar* xNodeGetName(xmlNode* node); //!< returns name of @a node (not a libxml function) static xmlNode* xNodeGetChildren(xmlNode* node); //!< returns children of @a node (not a libxml function) + static xmlNode* xNodeGetLastChild(xmlNode* node); //!< returns last child of @a node (not a libxml function) static xmlNode* xNodeGetNextNode(xmlNode* node); //!< returns next node (sibling) after @a node (not a libxml function) + static xmlNode* xNodeGetPrevNode(xmlNode* node); //!< returns previous node (sibling) before @a node (not a libxml function) static xmlNode* xNodeGetParent(xmlNode* node); //!< returns parent node of @a node (not a libxml function) static xmlDoc* xNodeGetDoc(xmlNode* node); //!< returns document node of @a node (not a libxml function) + static bool xNodeIsText(xmlNode* node); //!< returns true if node is an XML_TEXT_NODE (not a libxml function) + static bool xNodeIsElement(xmlNode* node); //!< returns true if node is an XML_ELEMENT_NODE (not a libxml function) + static bool xNodeIsComment(xmlNode* node); //!< returns true if node is an XML_COMMENT_NODE (not a libxml function) //@} //! returns true if @a str is some form of affirmative (e.g. "true" or "yes") @@ -159,6 +198,26 @@ return os << pb.toString(); } + // specializations to funnel cast requests through the appropriate conversion + /// @cond INTERNAL + template<> inline bool ObjectBase::to() const { return toLong(); } + template<> inline char ObjectBase::to() const { return toLong(); } + template<> inline unsigned char ObjectBase::to() const { return toLong(); } + template<> inline short ObjectBase::to() const { return toLong(); } + template<> inline unsigned short ObjectBase::to() const { return toLong(); } + template<> inline int ObjectBase::to() const { return toLong(); } + template<> inline unsigned int ObjectBase::to() const { return toLong(); } + template<> inline long ObjectBase::to() const { return toLong(); } + template<> inline unsigned long ObjectBase::to() const { return toLong(); } + template<> inline long long ObjectBase::to() const { return toLong(); } + template<> inline unsigned long long ObjectBase::to() const { return toLong(); } + template<> inline float ObjectBase::to() const { return toDouble(); } + template<> inline double ObjectBase::to() const { return toDouble(); } + template<> inline const char* ObjectBase::to() const { return toString().c_str(); } + template<> inline std::string ObjectBase::to() const { return toString(); } + /// @endcond + + template class Primitive; // forward declaration so we can solve string/Primitive ambiguity in operator= below //! Provides common functionality to all primitive value classes (implemented in a templated subclass Primitive) /*! This class supports callbacks upon modification through the use of the @@ -178,13 +237,24 @@ PrimitiveBase() : ObjectBase(), primitiveListeners() {} //! copy constructor (don't copy listeners) PrimitiveBase(const PrimitiveBase& pb) : ObjectBase(pb), primitiveListeners() {} - //! assignment (don't assign listeners) - PrimitiveBase& operator=(const PrimitiveBase& pb) { ObjectBase::operator=(pb); fireValueChanged(); return *this; } + //! assignment (don't assign listeners); doesn't trigger fireValueChanged, subclass should do that from its own operator=() following assignment + virtual PrimitiveBase& operator=(const PrimitiveBase& pb) { ObjectBase::operator=(pb); return *this; } + //! assignment from Primitive, solely to resolve ambiguity with this type between operator=(PrimitiveBase) and operator=(std::string) + PrimitiveBase& operator=(const Primitive& v); + //! assignment from std::string, wraps it in a plist::Primitive and passes on to operator=(PrimitiveBase) + PrimitiveBase& operator=(const std::string& v); + //! assignment from long value, wraps it in a plist::Primitive and passes on to operator=(PrimitiveBase) + PrimitiveBase& operator=(long v); + //! assignment from unsigned long value, wraps it in a plist::Primitive and passes on to operator=(PrimitiveBase) + PrimitiveBase& operator=(unsigned long v); + //! assignment from double value, wraps it in a plist::Primitive and passes on to operator=(PrimitiveBase) + PrimitiveBase& operator=(double v); //! destructor ~PrimitiveBase(); //! assign a new value virtual void set(const std::string& str)=0; + virtual void set(const ObjectBase& ob) { const PrimitiveBase& pb = dynamic_cast(ob); *this=pb; } //! return current value as a string virtual std::string get() const=0; @@ -198,10 +268,10 @@ virtual bool isPrimitiveListener(PrimitiveListener * vl); protected: - //! run through #primitiveListeners, calling PrimitiveListener::plistValueChanged(*this) - virtual void fireValueChanged() const; + //! run through #primitiveListeners, calling PrimitiveListener::plistValueChanged(*this) or PrimitiveListener::plistValueTouched(*this) + virtual void fireValueChanged(bool touch) const; //! stores a list of the current listeners - std::list* primitiveListeners; + std::set* primitiveListeners; }; //! output stringified value (from PrimitiveBase::get()) to stream inline std::ostream& operator<<(std::ostream& os, const PrimitiveBase& pb) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plistCollections.cc ./Shared/plistCollections.cc --- ../Tekkotsu_3.0/Shared/plistCollections.cc 2006-09-16 02:01:41.000000000 -0400 +++ ./Shared/plistCollections.cc 2007-10-26 18:33:20.000000000 -0400 @@ -13,18 +13,18 @@ collectionListeners=NULL; } - void Collection::addCollectionListener(CollectionListener* l) { + void Collection::addCollectionListener(CollectionListener* l) const { if(l!=NULL) { if(collectionListeners==NULL) - collectionListeners=new std::list; - collectionListeners->push_back(l); + collectionListeners=new std::set; + collectionListeners->insert(l); } } - void Collection::removeCollectionListener(CollectionListener* l) { + void Collection::removeCollectionListener(CollectionListener* l) const { if(collectionListeners==NULL) return; - std::list::iterator it=find(collectionListeners->begin(),collectionListeners->end(),l); + std::set::iterator it=collectionListeners->find(l); if(it!=collectionListeners->end()) { collectionListeners->erase(it); if(collectionListeners->empty()) { @@ -34,252 +34,206 @@ } } - bool Collection::isCollectionListener(CollectionListener* l) { + bool Collection::isCollectionListener(CollectionListener* l) const { if(l==NULL) return false; if(collectionListeners==NULL) return false; - std::list::iterator it=find(collectionListeners->begin(),collectionListeners->end(),l); + std::set::iterator it=collectionListeners->find(l); return it!=collectionListeners->end(); } + long Collection::toLong() const { throw std::runtime_error("Unable to cast collection to integer value"); } + double Collection::toDouble() const { throw std::runtime_error("Unable to cast collection to floating point value"); } + void Collection::fireEntryAdded(ObjectBase& val) { if(collectionListeners==NULL) return; - std::list::iterator it=collectionListeners->begin(); - while(it!=collectionListeners->end()) { - std::list::iterator cur=it++; //increment early in case the listener changes subscription - (*cur)->plistCollectionEntryAdded(*this,val); + // copy primitive listeners so we aren't screwed if a listener is removed during processing, particularly if it's the *last* listener + std::set pls=*collectionListeners; + for(std::set::const_iterator it=pls.begin(); collectionListeners!=NULL && it!=pls.end(); ++it) { + // make sure current listener hasn't been removed + if(collectionListeners->find(*it)!=collectionListeners->end()) + (*it)->plistCollectionEntryAdded(*this,val); } } void Collection::fireEntryRemoved(ObjectBase& val) { if(collectionListeners==NULL) return; - std::list::iterator it=collectionListeners->begin(); - while(it!=collectionListeners->end()) { - std::list::iterator cur=it++; //increment early in case the listener changes subscription - (*cur)->plistCollectionEntryRemoved(*this,val); + // copy primitive listeners so we aren't screwed if a listener is removed during processing, particularly if it's the *last* listener + std::set pls=*collectionListeners; + for(std::set::const_iterator it=pls.begin(); collectionListeners!=NULL && it!=pls.end(); ++it) { + // make sure current listener hasn't been removed + if(collectionListeners->find(*it)!=collectionListeners->end()) + (*it)->plistCollectionEntryRemoved(*this,val); } } void Collection::fireEntriesChanged() { if(collectionListeners==NULL) return; - std::list::iterator it=collectionListeners->begin(); - while(it!=collectionListeners->end()) { - std::list::iterator cur=it++; //increment early in case the listener changes subscription - (*cur)->plistCollectionEntriesChanged(*this); + // copy primitive listeners so we aren't screwed if a listener is removed during processing, particularly if it's the *last* listener + std::set pls=*collectionListeners; + for(std::set::const_iterator it=pls.begin(); collectionListeners!=NULL && it!=pls.end(); ++it) { + // make sure current listener hasn't been removed + if(collectionListeners->find(*it)!=collectionListeners->end()) + (*it)->plistCollectionEntriesChanged(*this); } } - - - - - void Dictionary::setEntry(const std::string& name, ObjectBase& val, bool warnExists/*=false*/) { - storage_t::iterator it=dict.find(name); - if(it!=dict.end()) { - //found exact name match - if(&val==it->second) - return; // same val reference already registered - if(warnExists) { - cerr << "Warning: new entry ("<second)<<")"<(it->second); - d->setEntry(name.substr(p+1),val,warnExists); - return; + std::string Collection::getIndentationPrefix(xmlNode* node) { + std::string indentStr; + for(xmlNode* cur=node->parent; cur!=NULL; cur=cur->parent) { + if((void*)cur==(void*)node->doc) { //if we hit the document node, discount it and we're done + if(indentStr.size()>0) + indentStr=indentStr.substr(0,indentStr.size()-perIndent().size()); + break; } - //if still here, no sub-collection, fall through to add new entry + indentStr+=perIndent(); } - dict[name]=&val; - fireEntryAdded(val); + return indentStr; } - void Dictionary::addEntry(const std::string& name, ObjectBase& val, const std::string& comment, bool warnExists) { - storage_t::iterator it=dict.find(name); - if(it!=dict.end()) { - //found exact name match - if(&val==it->second) - return; // same val reference already registered - if(warnExists) { - cerr << "Warning: new entry ("<second)<<")"<(it->second); - d->addEntry(name.substr(p+1),val,comment); - return; - } - //if still here, no sub-collection, fall through to add new entry - } - if(comment.size()>0) - comments[name]=comment; - dict[name]=&val; - fireEntryAdded(val); + + size_t Collection::getIndex(const std::string& name) { + char * endp=0; + long index=strtol(name.c_str(),&endp,0); + if(index<0) + return (size_t)-1; + //throw bad_format(NULL,"Collection::getIndex passed negative index encoded in string: "+name); + if(*endp!='\0') + return (size_t)-1; + //throw bad_format(NULL,"Collection::getIndex was called with a non-numeric value"); + return index; } - void Dictionary::setEntry(const std::string& name, ObjectBase* val, bool warnExists/*=false*/) { + + bool DictionaryBase::removeEntry(const std::string& name) { storage_t::iterator it=dict.find(name); - if(it!=dict.end()) { - //found exact name match - if(val==it->second) - return; // same val reference already registered - if(warnExists) { - cerr << "Warning: new entry ("<second)<<")"<(it->second); - d->setEntry(name.substr(p+1),val,warnExists); - return; - } - //if still here, no sub-collection, fall through to add new entry - } - dict[name]=val; - takeObject(name,val); - fireEntryAdded(*val); + if(it==dict.end()) + return false; + //still here, then we found exact name match + ObjectBase* obj=it->second; + dict.erase(it); + comments.erase(name); + fireEntryRemoved(*obj); + return true; } - void Dictionary::addEntry(const std::string& name, ObjectBase* val, const std::string& comment, bool warnExists) { - storage_t::iterator it=dict.find(name); - if(it!=dict.end()) { - //found exact name match - if(val==it->second) - return; // same val reference already registered - if(warnExists) { - cerr << "Warning: new entry ("<second)<<")"<second; + dict.erase(nit); + comments.erase(newname); + fireEntryRemoved(*obj); + } + + ObjectBase* val=oit->second; + dict.erase(oit); + dict[newname]=val; + + // now move comment along too + comments_t::iterator cit=comments.find(oldname); + if(cit==comments.end()) { // no comment for item being moved... + // any comments by a previous resident of the new name? + cit = comments.find(newname); + if(cit!=comments.end()) // if so, remove them + comments.erase(cit); } else { - //perhaps there's a sub-dictionary - string::size_type p; - it=getSubEntry(name,p); - if(it!=dict.end()) { - //found a matching sub-collection, have it find the rest recursively - if(Dictionary* d=dynamic_cast(it->second)) { - d->addEntry(name.substr(p+1),val,comment,warnExists); - } else { - Collection* c=dynamic_cast(it->second); - c->addEntry(name.substr(p+1),val,comment); - } - return; - } - //if still here, no sub-collection, fall through to add new entry + // item being moved has a comment, bring it along... + string com = cit->second; + comments.erase(cit); + comments[newname]=com; } - dict[name]=val; - if(comment.size()>0) - comments[name]=comment; - takeObject(name,val); - fireEntryAdded(*val); + fireEntriesChanged(); + return true; } - - void Dictionary::removeEntry(const std::string& name) { - storage_t::iterator it=dict.find(name); - if(it!=dict.end()) { - //found exact name match - ObjectBase* obj=it->second; - dict.erase(it); - fireEntryRemoved(*obj); - } else { - //perhaps there's a sub-dictionary - string::size_type p; - it=getSubEntry(name,p); - if(it!=dict.end()) { - //found a matching sub-collection, have it find the rest recursively - Collection* d=dynamic_cast(it->second); - d->removeEntry(name.substr(p+1)); + bool DictionaryBase::swapEntry(const std::string& a, const std::string& b) { + storage_t::iterator ait = dict.find(a); + storage_t::iterator bit = dict.find(b); + if(ait==dict.end() && bit==dict.end()) + return false; + else if(ait==dict.end()) + return renameEntry(b,a); + else if(bit==dict.end()) + return renameEntry(a,b); + + swap(ait->second,bit->second); + + // swap comments too + comments_t::iterator acit = comments.find(a); + comments_t::iterator bcit = comments.find(b); + if(acit != comments.end()) { + if(bcit != comments.end()) { + // have comments for both + swap(acit->second,bcit->second); + } else { + // only have a comment for a + string com = acit->second; + comments.erase(acit); + comments[b]=com; } + } else if(bcit != comments.end()) { + // only have a comment for b + string com = bcit->second; + comments.erase(bcit); + comments[a]=com; } + fireEntriesChanged(); + return true; } - ObjectBase* Dictionary::getEntry(const std::string& name) const { + ObjectBase* DictionaryBase::resolveEntry(const std::string& path) const { //do we have a key with this name? - const_iterator it=dict.find(name); + const_iterator it=dict.find(path); if(it!=dict.end()) return it->second; //yes, return it //perhaps there's a sub-dictionary string::size_type p; - it=getSubEntry(name,p); - if(it!=dict.end()) { - //found a matching sub-collection, have it find the rest recursively - const Collection* d=dynamic_cast(it->second); - return d->getEntry(name.substr(p+1)); + it=getSubEntry(path,p); + if(it==dict.end()) { + // got noth'n + return NULL; } - //got nothin' - return NULL; + //found a matching sub-collection, have it find the rest recursively + const Collection* d=dynamic_cast(it->second); + return d->resolveEntry(path.substr(p+1)); } - void Dictionary::setComment(const std::string& name, const std::string& comment) { - storage_t::iterator it=dict.find(name); - if(it==dict.end()) { - //perhaps there's a sub-dictionary - string::size_type p; - it=getSubEntry(name,p); - if(it!=dict.end()) { - //found a matching sub-collection, have it find the rest recursively - Collection* d=dynamic_cast(it->second); - d->setComment(name.substr(p+1),comment); - return; - } - } + void DictionaryBase::setComment(const std::string& name, const std::string& comment) { if(comment.size()>0) comments[name]=comment; else comments.erase(name); } - const std::string& Dictionary::getComment(const std::string& name) const { + const std::string& DictionaryBase::getComment(const std::string& name) const { storage_t::const_iterator it=dict.find(name); - if(it!=dict.end()) { - //found exact name match - comments_t::const_iterator cit=comments.find(name); - return (cit!=comments.end()) ? cit->second : emptyStr(); - } else { - //perhaps there's a sub-dictionary - string::size_type p; - it=getSubEntry(name,p); - if(it!=dict.end()) { - //found a matching sub-collection, have it find the rest recursively - const Collection* d=dynamic_cast(it->second); - return d->getComment(name.substr(p+1)); - } + if(it==dict.end()) return emptyStr(); - } + //found exact name match + comments_t::const_iterator cit=comments.find(name); + return (cit!=comments.end()) ? cit->second : emptyStr(); } - - void Dictionary::loadXML(xmlNode* node) { + + void DictionaryBase::loadXML(xmlNode* node) { //check if our node has been set to NULL (invalid or not found) if(node==NULL) return; - + if(!xNodeHasName(node,"dict")) + throw bad_format(node,"Dictionary::loadXML expected value, got "+std::string((const char*)xNodeGetName(node))); + std::string comment; - set seen; + std::set seen; //process children nodes for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur->next,comment)) { @@ -303,18 +257,18 @@ seen.insert(key); loadXMLNode(key,v,comment); } - if(trimExtraLoad && seen.size()!=size()) { - set rem; + if((loadPolicy&REMOVALS) && seen.size()!=size()) { + std::set rem; for(const_iterator it=begin(); it!=end(); ++it) { if(seen.find(it->first)==seen.end()) rem.insert(it->first); } - for(set::const_iterator it=rem.begin(); it!=rem.end(); ++it) + for(std::set::const_iterator it=rem.begin(); it!=rem.end(); ++it) removeEntry(*it); } } - void Dictionary::saveXML(xmlNode* node) const { + void DictionaryBase::saveXML(xmlNode* node, bool onlyOverwrite, std::set& seen) const { //check if our node has been set to NULL (invalid or not found) if(node==NULL) return; @@ -322,21 +276,8 @@ //set the type of the current node xmlNodeSetName(node,(const xmlChar*)"dict"); - // we'll use this to keep track of which nodes were already present, so we'll - // know which ones were missing for which we need to make new nodes - storage_t seen; - //find the depth of the target node in the xml tree to maintain proper indentation - std::string perIndent(" "); - std::string indentStr; - for(xmlNode* cur=node->parent; cur!=NULL; cur=cur->parent) { - if((void*)cur==(void*)node->doc) { //if we hit the document node, discount it and we're done - if(indentStr.size()>0) - indentStr=indentStr.substr(0,indentStr.size()-perIndent.size()); - break; - } - indentStr+=perIndent; - } + std::string indentStr=getIndentationPrefix(node); //This will hold any comments found between elements -- if no comment is found, a new one may be added std::string comment; @@ -358,14 +299,12 @@ if(!xmlStrcmp(v->name, (const xmlChar *)"key")) throw bad_format(v,"Dictionary format error: expect data in pairs of key and value (two keys found in a row)"); - //find corresponding entry xmlChar* cont=xmlNodeGetContent(k); - string key=(const char*)cont; + std::string key=(const char*)cont; xmlFree(cont); - storage_t::const_iterator it=dict.find(key); - if(it==dict.end()) { + if(!saveOverXMLNode(k,v,key,comment,indentStr,seen)) { cur=xNodeGetNextNode(cur); - if(trimExtraSave) { + if(savePolicy&REMOVALS) { while(prev!=cur) { xmlNode* n=prev; prev=xNodeGetNextNode(prev); @@ -373,95 +312,60 @@ xmlFreeNode(n); } } else { - if(warnUnused) + if(warnUnused && savePolicy==FIXED) cerr << "Warning: saving over existing plist dictionary, key '" << key << "' does not match a registered variable. Ignoring..." << endl; } prev=cur; - continue; - } - if(comment.size()==0) { - bool isSub=dynamic_cast(it->second); - if(isSub) { - xmlAddPrevSibling(k,xmlNewText((const xmlChar*)"\n")); - xmlAddPrevSibling(k,xmlNewComment((const xmlChar*)("======== "+it->first+" ========").c_str())); - } - comments_t::const_iterator cit=comments.find(key); - if(cit!=comments.end()) { - if(isSub || cit->second.substr(0,key.size())==key) - comment=cit->second; - else //if not a sub-dictionary, and comment doesn't already start with entry name, prepend entry name - comment=key+": "+cit->second; - xmlAddPrevSibling(k,xmlNewText((const xmlChar*)"\n")); - xmlAddPrevSibling(k,xmlNewComment((const xmlChar*)comment.c_str())); - xmlAddPrevSibling(k,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); - } } - it->second->saveXML(v); - seen.insert(*it); prev=cur=xNodeGetNextNode(cur); } - if(seen.size()!=dict.size()) { + if(!onlyOverwrite && seen.size()!=dict.size()) { + // clear text nodes from end of dictionary back to last entry + for(xmlNode* cur=node->last; cur!=NULL && cur->type==XML_TEXT_NODE; cur=node->last) { + xmlUnlinkNode(cur); + xmlFreeNode(cur); + } + // the main dictionary has entries that weren't seen... find which ones // if needed, this could be made faster (O(n) vs. current O(n lg n)) by assuming the maps // are sorted and moving two iterators through together instead of repeated find()'s for(storage_t::const_iterator it=dict.begin(); it!=dict.end(); ++it) { if(seen.find(it->first)==seen.end()) { //we didn't see this node in the existing xml tree, have to add a new node pair for it - bool isSub=dynamic_cast(it->second); - if(isSub) { - xmlAddChild(node,xmlNewText((const xmlChar*)"\n")); - xmlAddChild(node,xmlNewComment((const xmlChar*)("======== "+it->first+" ========").c_str())); - } - comments_t::const_iterator cit=comments.find(it->first); - if(cit!=comments.end()) { - if(isSub || cit->second.substr(0,it->first.size())==it->first) - comment=cit->second; - else - comment=it->first+": "+cit->second; - xmlAddChild(node,xmlNewText((const xmlChar*)"\n")); - xmlAddChild(node,xmlNewComment((const xmlChar*)comment.c_str())); - } - xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); - xmlNode* k=xmlNewChild(node,NULL,(const xmlChar*)"key",(const xmlChar*)it->first.c_str()); - if(k==NULL) - throw bad_format(node,"Error: plist Dictionary xml error on saving key"); - xmlAddChild(node,xmlNewText((const xmlChar*)" ")); - xmlNode* v=xmlNewChild(node,NULL,(const xmlChar*)"",NULL); - if(v==NULL) - throw bad_format(node,"Error: plist Dictionary xml error on saving value"); - if(indentStr.size()>=perIndent.size()) - xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+indentStr.substr(perIndent.size())).c_str())); - else - xmlAddChild(node,xmlNewText((const xmlChar*)("\n"))); - it->second->saveXML(v); + saveXMLNode(node,it->first,it->second,indentStr); } } + std::string parentIndent; + if(indentStr.size()>=perIndent().size()) + parentIndent=indentStr.substr(perIndent().size()); + xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+parentIndent).c_str())); } } - std::string Dictionary::toString() const { + std::string DictionaryBase::toString() const { stringstream s; s << *this; return s.str(); } - //! implements the clone function for Dictionaries - PLIST_CLONE_IMP(Dictionary,new Dictionary(*this)); - - unsigned int Dictionary::getLongestKeyLen() const { + unsigned int DictionaryBase::getLongestKeyLen(const regex_t* reg/*=NULL*/, unsigned int depth/*=-1*/) const { + if(depth==0) + return 0; size_t longest=0; size_t seplen=subCollectionSep().size(); - for(Dictionary::const_iterator it=begin(); it!=end(); ++it) { + for(DictionaryBase::const_iterator it=begin(); it!=end(); ++it) { + if(reg!=NULL && regexec(reg,it->first.c_str(),0,NULL,0)!=0) + continue; size_t cur=it->first.size(); if(Collection* dp=dynamic_cast(it->second)) - cur+=getLongestKeyLenOther(*dp)+seplen; + cur+=dp->getLongestKeyLen(reg,depth-1)+seplen; longest=std::max(longest,cur); } return longest; } - Dictionary::iterator Dictionary::getSubEntry(const std::string& name, std::string::size_type& seppos) { + DictionaryBase::iterator DictionaryBase::getSubEntry(const std::string& name, std::string::size_type& seppos) { seppos=name.find(subCollectionSep()); if(seppos==string::npos) return dict.end(); //no '.'s found -- go away @@ -473,7 +377,7 @@ return dict.end(); //matching prefix is not a collection -- go away return it; } - Dictionary::const_iterator Dictionary::getSubEntry(const std::string& name, std::string::size_type& seppos) const { + DictionaryBase::const_iterator DictionaryBase::getSubEntry(const std::string& name, std::string::size_type& seppos) const { seppos=name.find(subCollectionSep()); if(seppos==string::npos) return dict.end(); //no '.'s found -- go away @@ -486,195 +390,199 @@ return it; } - std::ostream& operator<<(std::ostream& os, const Dictionary& d) { - unsigned int longest=std::max(Collection::getLongestKeyLenOther(d),static_cast(os.width())); - unsigned int seplen=Collection::subCollectionSep().size(); - for(Dictionary::storage_t::const_iterator it=d.dict.begin(); it!=d.dict.end(); ++it) { - if(Collection* dp=dynamic_cast(it->second)) { - stringstream ss; - ss << setw(longest-it->first.size()-seplen) << *dp; - string line; - for(getline(ss,line); ss; getline(ss,line)) - os << it->first << Collection::subCollectionSep() << line << endl; - } else { - os << left << setw(longest) << it->first << " = " << *it->second << endl; - } - } - return os; + void DictionaryBase::clear() { + storage_t::size_type s=dict.size(); + // this bit of trickiness is to handle element destructors doing things to the list while it's being cleared + std::set refs=myRef; + dict.clear(); + myRef.clear(); + comments.clear(); + if(s>0) //only fire if we had entries to begin with + fireEntriesChanged(); + for(std::set::iterator it=refs.begin(); it!=refs.end(); ++it) + delete *it; } + void DictionaryBase::takeObject(const std::string& /*name*/, ObjectBase* obj) { + myRef.insert(obj); + } - + void DictionaryBase::fireEntryRemoved(ObjectBase& val) { + Collection::fireEntryRemoved(val); + std::set::iterator it=myRef.find(&val); + if(it!=myRef.end()) { + myRef.erase(it); + delete &val; + } + } - void Array::setEntry(size_t index, ObjectBase& val, bool warnExists/*=false*/) { - if(index==size()) { - arr.push_back(&val); - fireEntryAdded(val); - } else { - if(arr[index]==&val) - return; - if(warnExists) { - cerr << "Warning: new entry "<::iterator rit=myRef.find(dit->second); + if(rit!=myRef.end()) { + myRef.erase(rit); + myRef.insert(dit->second=dynamic_cast((dit->second)->clone())); } - arr[index]=&val; - fireEntriesChanged(); } - } - void Array::addEntry(size_t index, ObjectBase& val, const std::string& comment/*=""*/) { - if(index==size()) { - arr.push_back(&val); - } else { - storage_t::iterator it=arr.begin(); - advance(it,index); - arr.insert(it,&val); + + //slower implementation, but can handle multiple pointers to the same instance (which we don't support elsewhere, so no point in doing it) + /* + std::set ns; + for(std::set::iterator it=myRef.begin(); it!=myRef.end(); ++it) { + ObjectBase* n=dynamic_cast((*it)->clone()); + bool used=false; + for(iterator dit=dict.begin(); dit!=dict.end(); ++dit) { + if(*it==dit->second) { + dit->second=n; + used=true; + } + } + if(!used) { + cerr << "Warning: dictionary claims control over pointer not found in dictionary" << endl; + delete n; + } else + ns.insert(n); } - if(comment.size()>0) - setComment(index,comment); - fireEntryAdded(val); + myRef=ns; + */ } - void Array::setEntry(size_t index, ObjectBase* val, bool warnExists/*=false*/) { - if(index>size()) - throw bad_format(NULL,"Error: attempted to setEntry() past end of Array"); - else if(index==size()) { - arr.push_back(val); - fireEntryAdded(*val); - } else { - if(arr[index]==val) - return; - if(warnExists) { - cerr << "Warning: new entry "<& seen) const { + //find corresponding entry + storage_t::const_iterator it=findEntry(key); + if(it==dict.end()) + return false; + if(comment.size()==0) { + bool isSub=dynamic_cast(it->second); + bool isFirst=true; + const std::string indentedNewline="\n"+indentStr; + const std::string headline=("======== "+it->first+" ========"); + comments_t::const_iterator cit=comments.find(key); + if(cit!=comments.end()) { + while(k->prev!=NULL && xNodeIsText(k->prev)) { + xmlNode* n=k->prev; + xmlUnlinkNode(n); + xmlFreeNode(n); + } } - std::set::iterator it=myRef.find(arr[index]); - if(it!=myRef.end()) { - myRef.erase(*it); - delete arr[index]; + if(isSub) { + isFirst=(skipToElement(k->parent->children)==k); + xmlAddPrevSibling(k,xmlNewText((const xmlChar*)(isFirst ? indentedNewline : indentedNewline+indentedNewline).c_str())); + xmlAddPrevSibling(k,xmlNewComment((const xmlChar*)headline.c_str())); + } + if(cit!=comments.end()) { + if(isSub || cit->second.find(key)second; + else //if not a sub-dictionary, and comment doesn't already start with entry name, prepend entry name + comment=key+": "+cit->second; + string::size_type pos=comment.rfind('\n'); + while(pos!=string::npos) { + if(comment.compare(pos+1,indentStr.size(),indentStr)!=0) + comment.insert(pos+1,indentStr); + if(pos==0) + break; + pos = comment.rfind('\n',pos-1); + } + if(!isSub) + isFirst=(skipToElement(k->parent->children)==k); + xmlAddPrevSibling(k,xmlNewText((const xmlChar*)(isFirst ? indentedNewline : indentedNewline+indentedNewline).c_str())); + xmlAddPrevSibling(k,xmlNewComment((const xmlChar*)comment.c_str())); + xmlAddPrevSibling(k,xmlNewText((const xmlChar*)indentedNewline.c_str())); } - arr[index]=val; - takeObject(index,val); - fireEntriesChanged(); } - } - void Array::addEntry(size_t index, ObjectBase* val, const std::string& comment/*=""*/) { - if(index>size()) - throw bad_format(NULL,"Error: attempted to setEntry() past end of Array"); - else if(index==size()) { - arr.push_back(val); + it->second->saveXML(val); + if(seen.find(key)!=seen.end()) { + std::cerr << "WARNING: plist::Dictionary found duplicate key " << key << " during save" << std::endl; } else { - storage_t::iterator it=arr.begin(); - advance(it,index); - arr.insert(it,val); + seen.insert(key); } - takeObject(index,val); - if(comment.size()>0) - setComment(index,comment); - fireEntryAdded(*val); + return true; } - void Array::removeEntry(size_t index) { + void DictionaryBase::saveXMLNode(xmlNode* node, const std::string& key, const ObjectBase* val, const std::string& indentStr) const { + bool isSub=dynamic_cast(val); + bool isFirst=(node->children==NULL); + const std::string indentedNewline="\n"+indentStr; + const std::string headline=("======== "+key+" ========"); + if(isSub) { + xmlAddChild(node,xmlNewText((const xmlChar*)(isFirst ? indentedNewline : indentedNewline+indentedNewline).c_str())); + xmlAddChild(node,xmlNewComment((const xmlChar*)headline.c_str())); + } + std::string comment; + comments_t::const_iterator cit=comments.find(key); + if(cit!=comments.end()) { + if(isSub || cit->second.find(key)second; + else + comment=key+": "+cit->second; + string::size_type pos=comment.rfind('\n'); + while(pos!=string::npos) { + if(comment.compare(pos+1,indentStr.size(),indentStr)!=0) + comment.insert(pos+1,indentStr); + if(pos==0) + break; + pos = comment.rfind('\n',pos-1); + } + xmlAddChild(node,xmlNewText((const xmlChar*)(isSub || isFirst ? indentedNewline : indentedNewline+indentedNewline).c_str())); + xmlAddChild(node,xmlNewComment((const xmlChar*)comment.c_str())); + } + xmlAddChild(node,xmlNewText((const xmlChar*)indentedNewline.c_str())); + xmlNode* k=xmlNewChild(node,NULL,(const xmlChar*)"key",(const xmlChar*)key.c_str()); + if(k==NULL) + throw bad_format(node,"Error: plist Dictionary xml error on saving key"); + xmlAddChild(node,xmlNewText((const xmlChar*)" ")); + xmlNode* v=xmlNewChild(node,NULL,(const xmlChar*)"",NULL); + if(v==NULL) + throw bad_format(node,"Error: plist Dictionary xml error on saving value"); + val->saveXML(v); + } + + + bool ArrayBase::removeEntry(size_t index) { + if(index>=arr.size()) + return false; storage_t::iterator it=arr.begin(); advance(it,index); ObjectBase* obj=*it; arr.erase(it); + comments.erase(index); fireEntryRemoved(*obj); + return true; } - - void Array::setEntry(const std::string& name, ObjectBase& val, bool warnExists/*=false*/) { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - Collection * d=dynamic_cast(*it); - d->setEntry(name.substr(p+1),val,warnExists); - } else - throw bad_format(NULL,("Array::setEntry(name,val,warn) was called with an invalid numeric name:" + name).c_str()); - } else { - setEntry(index,val,warnExists); - } - } - void Array::addEntry(const std::string& name, ObjectBase& val, const std::string& comment/*=""*/) { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - Collection * d=dynamic_cast(*it); - d->addEntry(name.substr(p+1),val,comment); - } else - throw bad_format(NULL,("Array::addEntry(name,val,comment) was called with an invalid numeric name:" + name).c_str()); - } else { - addEntry(index,val,comment); - } - } - void Array::setEntry(const std::string& name, ObjectBase* val, bool warnExists/*=false*/) { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - Collection * d=dynamic_cast(*it); - d->setEntry(name.substr(p+1),val,warnExists); - } else - throw bad_format(NULL,("Array::setEntry(name,*val,warn) was called with an invalid numeric name:" + name).c_str()); - } else { - setEntry(index,val,warnExists); - } - } - void Array::addEntry(const std::string& name, ObjectBase* val, const std::string& comment/*=""*/) { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - Collection * d=dynamic_cast(*it); - d->addEntry(name.substr(p+1),val,comment); - } else - throw bad_format(NULL,("Array::addEntry(name,*val,comment) was called with an invalid numeric name:" + name).c_str()); - } else { - addEntry(index,val,comment); - } - } - - void Array::removeEntry(const std::string& name) { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - Collection * d=dynamic_cast(*it); - d->removeEntry(name.substr(p+1)); - } else - throw bad_format(NULL,("Array::removeEntry(name) was called with an invalid numeric name:" + name).c_str()); - } else { - removeEntry(index); - } - } - ObjectBase* Array::getEntry(const std::string& name) const { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - const Collection * d=dynamic_cast(*it); - return d->getEntry(name.substr(p+1)); - } else - throw bad_format(NULL,("Array::getEntry(name) was called with an invalid numeric name:" + name).c_str()); - } else { + ObjectBase* ArrayBase::resolveEntry(const std::string& path) const { + size_t index=getIndex(path); + if(index(*it); + return d->resolveEntry(path.substr(p+1)); } - void Array::setComment(size_t index, const std::string& comment) { + void ArrayBase::clear() { + storage_t::size_type s=arr.size(); + // this bit of trickiness is to handle element destructors doing things to the list while it's being cleared + std::set refs=myRef; + arr.clear(); + comments.clear(); + myRef.clear(); + if(s>0) //only fire if we had entries to begin with + fireEntriesChanged(); + for(std::set::iterator it=refs.begin(); it!=refs.end(); ++it) + delete *it; + } + + void ArrayBase::setComment(size_t index, const std::string& comment) { if(comment.size()>0) comments[index]=comment; else comments.erase(index); } - const std::string& Array::getComment(size_t index) const { + const std::string& ArrayBase::getComment(size_t index) const { comments_t::const_iterator it=comments.find(index); if(it==comments.end()) return emptyStr(); @@ -682,54 +590,26 @@ return it->second; } - void Array::setComment(const std::string& name, const std::string& comment) { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - Collection * d=dynamic_cast(*it); - d->setComment(name.substr(p+1),comment); - } else - throw bad_format(NULL,("Array::setComment(name,comment) was called with an invalid numeric name:" + name).c_str()); - } else { - setComment(index,comment); - } - } - - const std::string& Array::getComment(const std::string& name) const { - size_t index=getIndex(name); - if(index>size()) { - string::size_type p; - const_iterator it=getSubEntry(name,p); - if(it!=arr.end()) { - const Collection * d=dynamic_cast(*it); - return d->getComment(name.substr(p+1)); - } else - throw bad_format(NULL,("Array::getComment(name) was called with an invalid numeric name:" + name).c_str()); - } else { - return getComment(index); - } - } - - void Array::loadXML(xmlNode* node) { + void ArrayBase::loadXML(xmlNode* node) { //check if our node has been set to NULL (invalid or not found) if(node==NULL) return; + if(!xNodeHasName(node,"array")) + throw bad_format(node,"Array::loadXML expected value, got "+std::string((const char*)xNodeGetName(node))); std::string comment; unsigned int i=0; - for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur->next,comment)) { + for(xmlNode* cur = skipToElement(xNodeGetChildren(node),comment); cur!=NULL; cur = skipToElement(xNodeGetNextNode(cur),comment)) { if(!loadXMLNode(i++, cur, comment)) break; } - if(trimExtraLoad) { + if(loadPolicy&REMOVALS) { while(iparent; cur!=NULL; cur=cur->parent) { - if((void*)cur==(void*)node->doc) { //if we hit the document node, discount it and we're done - if(indentStr.size()>0) - indentStr=indentStr.substr(0,indentStr.size()-perIndent.size()); - break; - } - indentStr+=perIndent; - } + std::string indentStr=getIndentationPrefix(node); std::string parentIndent; - if(indentStr.size()>=perIndent.size()) - parentIndent=indentStr.substr(perIndent.size()); + if(indentStr.size()>=perIndent().size()) + parentIndent=indentStr.substr(perIndent().size()); //This will hold any comments found between elements -- if no comment is found, a new one may be added std::string comment; @@ -759,11 +630,11 @@ unsigned int i=0; //process children nodes - xmlNode * prev=node->children; - for(xmlNode* cur = skipToElement(node->children,comment); cur!=NULL; cur = skipToElement(cur,comment)) { + xmlNode * prev=xNodeGetChildren(node); + for(xmlNode* cur = skipToElement(prev,comment); cur!=NULL; cur = skipToElement(cur,comment)) { if(i==arr.size()) { - if(trimExtraSave) { + if(savePolicy&REMOVALS) { while(prev!=NULL) { xmlNode* n=prev; prev=xNodeGetNextNode(prev); @@ -771,8 +642,8 @@ xmlFreeNode(n); } } else { - if(warnUnused) - cerr << "Warning: plist::Array ignoring extraneous items in destination during save..." << endl; + if(warnUnused && savePolicy==FIXED) + std::cerr << "Warning: plist::Array ignoring extraneous items in destination during save..." << std::endl; } break; } @@ -788,15 +659,26 @@ comment=buf; comment+=": "+cit->second; } - xmlAddPrevSibling(cur,xmlNewText((const xmlChar*)"\n")); + xmlAddPrevSibling(cur,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); + std::string::size_type pos=comment.rfind('\n'); + while(pos!=std::string::npos) { + if(comment.compare(pos+1,indentStr.size(),indentStr)!=0) + comment.insert(pos+1,indentStr); + if(pos==0) + break; + pos = comment.rfind('\n',pos-1); + } xmlAddPrevSibling(cur,xmlNewComment((const xmlChar*)comment.c_str())); xmlAddPrevSibling(cur,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); } } - arr[i]->saveXML(cur); + arr[i++]->saveXML(cur); prev=cur=xNodeGetNextNode(cur); } + if(!(savePolicy&ADDITIONS)) + return; + bool hadUnsaved = (isecond; } - xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+parentIndent).c_str())); + xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); + std::string::size_type pos=comment.rfind('\n'); + while(pos!=std::string::npos) { + if(comment.compare(pos+1,indentStr.size(),indentStr)!=0) + comment.insert(pos+1,indentStr); + if(pos==0) + break; + pos = comment.rfind('\n',pos-1); + } xmlAddChild(node,xmlNewComment((const xmlChar*)comment.c_str())); } xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+indentStr).c_str())); @@ -823,51 +713,46 @@ xmlAddChild(node,xmlNewText((const xmlChar*)("\n"+parentIndent).c_str())); } - std::string Array::toString() const { - stringstream s; + std::string ArrayBase::toString() const { + std::stringstream s; s << *this; return s.str(); } - //! implements the clone function for Array - PLIST_CLONE_IMP(Array,new Array(*this)); - - size_t Array::getIndex(const std::string& name) const { - char * endp=0; - long index=strtol(name.c_str(),&endp,0); - if(index<0) - return (size_t)-1; - //throw bad_format(NULL,"Array passed negative index encoded in string: "+name); - /* - if(*endp=='.') { - const Collection* d=dynamic_cast(arr[index]); - if(d==NULL) - return (size_t)-1; //matching prefix is not a dictionary -- go away - - //found a matching sub-dictionary, have it find the rest recursively - return index; - }*/ - if(*endp!='\0') - return (size_t)-1; - //throw bad_format(NULL,"Array::setEntry(name,val) was called with a non-numeric name"); - return index; - } - - unsigned int Array::getLongestKeyLen() const { + unsigned int ArrayBase::getLongestKeyLen(const regex_t* reg/*=NULL*/, unsigned int depth/*=-1*/) const { + if(depth==0) + return 0; size_t longest=0; size_t seplen=subCollectionSep().size(); for(size_t i=0; i(i)); + std::stringstream s; + s << i; + if(reg!=NULL && regexec(reg,s.str().c_str(),0,NULL,0)!=0) + continue; + size_t cur=s.str().size(); if(Collection* dp=dynamic_cast(arr[i])) - cur+=getLongestKeyLenOther(*dp)+seplen; + cur+=dp->getLongestKeyLen(reg,depth-1)+seplen; longest=std::max(longest,cur); } return longest; } - Array::iterator Array::getSubEntry(const std::string& name, std::string::size_type& seppos) { + void ArrayBase::takeObject(size_t /*index*/, ObjectBase* obj) { + myRef.insert(obj); + } + + void ArrayBase::fireEntryRemoved(ObjectBase& val) { + Collection::fireEntryRemoved(val); + std::set::iterator it=myRef.find(&val); + if(it!=myRef.end()) { + myRef.erase(it); + delete &val; + } + } + + ArrayBase::iterator ArrayBase::getSubEntry(const std::string& name, std::string::size_type& seppos) { seppos=name.find(subCollectionSep()); - if(seppos==string::npos) + if(seppos==std::string::npos) return arr.end(); //no '.'s found -- go away size_t index=getIndex(name.substr(0,seppos)); if(index>=size()) @@ -879,9 +764,9 @@ return arr.end(); //matching prefix is not a collection -- go away return it; } - Array::const_iterator Array::getSubEntry(const std::string& name, std::string::size_type& seppos) const { + ArrayBase::const_iterator ArrayBase::getSubEntry(const std::string& name, std::string::size_type& seppos) const { seppos=name.find(subCollectionSep()); - if(seppos==string::npos) + if(seppos==std::string::npos) return arr.end(); //no '.'s found -- go away size_t index=getIndex(name.substr(0,seppos)); if(index>=size()) @@ -893,97 +778,8 @@ return arr.end(); //matching prefix is not a collection -- go away return it; } - std::ostream& operator<<(std::ostream& os, const Array& d) { - unsigned int longest=std::max(Collection::getLongestKeyLenOther(d),static_cast(os.width())); - unsigned int seplen=Collection::subCollectionSep().size(); - for(unsigned long i=0; i(d.arr[i])) { - stringstream ss; - ss << setw(longest-snprintf(NULL,0,"%lu",i)-seplen) << *dp; - string line; - for(getline(ss,line); ss; getline(ss,line)) - os << i << Collection::subCollectionSep() << line << endl; - } else { - os << left << setw(longest) << i << " = " << *d.arr[i] << endl; - } - }//Array::storage_t::const_iterator it=d.arr.begin(); it!=d.arr.end(); ++it) { - return os; - } - - void Dictionary::clear() { - for(std::set::iterator it=myRef.begin(); it!=myRef.end(); ++it) - delete *it; - myRef.clear(); - dict.clear(); - fireEntriesChanged(); - } - - void Dictionary::takeObject(const std::string& /*name*/, ObjectBase* obj) { - myRef.insert(obj); - } - - void Dictionary::fireEntryRemoved(ObjectBase& val) { - Dictionary::fireEntryRemoved(val); - std::set::iterator it=myRef.find(&val); - if(it!=myRef.end()) { - delete &val; - myRef.erase(it); - } - } - void Dictionary::cloneMyRef() { - for(iterator dit=dict.begin(); dit!=dict.end(); ++dit) { - std::set::iterator rit=myRef.find(dit->second); - if(rit!=myRef.end()) { - myRef.erase(rit); - myRef.insert(dit->second=dynamic_cast((dit->second)->clone())); - } - } - - //slower implementation, but can handle multiple pointers to the same instance (which we don't support elsewhere, so no point in doing it) - /* - std::set ns; - for(std::set::iterator it=myRef.begin(); it!=myRef.end(); ++it) { - ObjectBase* n=dynamic_cast((*it)->clone()); - bool used=false; - for(iterator dit=dict.begin(); dit!=dict.end(); ++dit) { - if(*it==dit->second) { - dit->second=n; - used=true; - } - } - if(!used) { - cerr << "Warning: dictionary claims control over pointer not found in dictionary" << endl; - delete n; - } else - ns.insert(n); - } - myRef=ns; - */ - } - - void Array::clear() { - for(std::set::iterator it=myRef.begin(); it!=myRef.end(); ++it) - delete *it; - myRef.clear(); - arr.clear(); - fireEntriesChanged(); - } - - void Array::takeObject(size_t /*index*/, ObjectBase* obj) { - myRef.insert(obj); - } - - void Array::fireEntryRemoved(ObjectBase& val) { - Array::fireEntryRemoved(val); - std::set::iterator it=myRef.find(&val); - if(it!=myRef.end()) { - delete &val; - myRef.erase(it); - } - } - - void Array::cloneMyRef() { + void ArrayBase::cloneMyRef() { for(iterator dit=arr.begin(); dit!=arr.end(); ++dit) { std::set::iterator rit=myRef.find(*dit); if(rit!=myRef.end()) { @@ -991,80 +787,72 @@ myRef.insert(*dit=dynamic_cast((*dit)->clone())); } } - - //slower implementation, but can handle multiple pointers to the same instance (which we don't support elsewhere, so no point in doing it) - /* - std::set ns; - for(std::set::iterator it=myRef.begin(); it!=myRef.end(); ++it) { - ObjectBase* n=dynamic_cast((*it)->clone()); - bool used=false; - for(iterator dit=arr.begin(); dit!=arr.end(); ++dit) { - if(*it==*dit) { - *dit=n; - used=true; - } - } - if(!used) { - cerr << "Warning: dictionary claims control over pointer not found in dictionary" << endl; - delete n; - } else - ns.insert(n); - } - myRef=ns; - */ } - bool Dictionary::loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment) { - storage_t::const_iterator it=dict.find(key); - if(it!=dict.end()) { - //found pre-existing entry - try { - //it's reasonable to assume that in common usage, the same type will be used each time - //so let's try to load into the current entry as is - it->second->loadXML(val); - if(comment.size()>0) - setComment(key,comment); - return true; - } catch(const bad_format& ex) { - //apparently that didn't work, let's try a fresh load using the polymorphic loader (fall through below) - removeEntry(key); - } - } else if(!trimExtraLoad) { - if(warnUnused) - std::cerr << "Warning: reading plist dictionary, key '" << key << "' does not match a registered variable. Ignoring..." << std::endl; - return false; - } - ObjectBase * obj=plist::loadXML(val); - if(obj==NULL) - throw bad_format(val,"Dictionary encountered an unknown value type"); - addEntry(key,obj,comment); - return true; + std::ostream& filteredDisplay(std::ostream& os, const ObjectBase& c, const std::string& sel, int selType, unsigned int depth) { + if(sel.size()==0) + return filteredDisplay(os,c,NULL,depth); + regex_t r; + if(regcomp(&r,sel.c_str(),selType|REG_NOSUB)==0) + filteredDisplay(os,c,&r,depth); + regfree(&r); + return os; } - - bool Array::loadXMLNode(size_t index, xmlNode* val, const std::string& comment) { - if(indexloadXML(val); - if(comment.size()>0) - setComment(index,comment); - return true; - } catch(const bad_format& ex) { - //apparently that didn't work, let's try a fresh load using the polymorphic loader (fall through below) - removeEntry(index); + + std::ostream& filteredDisplay(std::ostream& os, const ObjectBase& c, const regex_t* reg, unsigned int depth) { + unsigned int seplen=Collection::subCollectionSep().size(); + unsigned int out=0; + + if(const ArrayBase* a=dynamic_cast(&c)) { + unsigned int longest=std::max(a->getLongestKeyLen(reg,depth),static_cast(os.width())); + for(unsigned long i=0; isize(); ++i) { + stringstream ns; + ns << i; + if(reg!=NULL && regexec(reg,ns.str().c_str(),0,NULL,0)!=0) + continue; + out++; + if(depth==0) + return os << right << setw(longest) << "" << " = [...]" << endl; + if(Collection* dp=dynamic_cast(&(*a)[i])) { + stringstream ss; + ss << left << std::setw(longest-snprintf(NULL,0,"%lu",i)-seplen); + filteredDisplay(ss,*dp,reg,depth-1); + std::string line; + for(getline(ss,line); ss; std::getline(ss,line)) + os << (ns.str() + Collection::subCollectionSep() + line) << std::endl; + } else { + os << std::left << std::setw(longest) << ns.str() << " = " << (*a)[i] << std::endl; + } } - } else if(!trimExtraLoad) { - if(warnUnused) - cerr << "Warning: plist::Array ran out of registered items (" << size() << ") during load. Ignoring extraneous items from source..." << endl; - return false; + if(out==0) + return os << right << setw(longest) << "" << " = (empty array)" << endl; + + } else if(const DictionaryBase* d=dynamic_cast(&c)) { + unsigned int longest=std::max(d->getLongestKeyLen(reg,depth),static_cast(os.width())); + for(DictionaryBase::storage_t::const_iterator it=d->begin(); it!=d->end(); ++it) { + if(reg!=NULL && regexec(reg,it->first.c_str(),0,NULL,0)!=0) + continue; + out++; + if(depth==0) + return os << right << setw(longest) << "" << " = [...]" << endl; + if(Collection* dp=dynamic_cast(it->second)) { + stringstream ss; + ss << left << setw(longest-it->first.size()-seplen); + filteredDisplay(ss,*dp,reg,depth-1); + string line; + for(getline(ss,line); ss; getline(ss,line)) + os << (it->first + Collection::subCollectionSep() + line) << endl; + } else { + os << left << setw(longest) << it->first << " = " << *it->second << endl; + } + } + if(out==0) + return os << right << setw(longest) << "" << " = (empty dictionary)" << endl; + + } else { + os << c.toString(); } - ObjectBase * obj=plist::loadXML(val); - if(obj==NULL) - throw bad_format(val,"Array encountered an unknown value type"); - addEntry(index,obj,comment); - return true; + return os; } } //namespace plist diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plistCollections.h ./Shared/plistCollections.h --- ../Tekkotsu_3.0/Shared/plistCollections.h 2006-09-19 01:39:33.000000000 -0400 +++ ./Shared/plistCollections.h 2007-11-20 13:11:48.000000000 -0500 @@ -6,59 +6,123 @@ #include #include #include +#include +namespace plist { + ObjectBase* loadXML(xmlNode* node); // defined in plist.h, we need the prototype +} namespace plist { - //! Provides a common base class for the collection-oriented primitives, Dictionary, Map, Array, and Vector + //! Provides a common base class for the collection-oriented primitives, Dictionary and Array + /*! + * When a collection, you can call addEntry() or setEntry() you can either: + * - pass a pointer to an ObjectBase or directly pass a primitive value (int, float, char, etc.), + * in which case the Array will assume management of the corresponding ObjectBase + * instance (freeing the memory region when removed) + * - pass a reference to an ObjectBase, in which case you retain control over the object's + * allocation + * + * This class supports callbacks upon modification through the use of the + * CollectionListener interface. Note that we only store a pointer to the + * listener list, which is typically unallocated when no listeners are + * active. This should ensure minimal memory usage per object, as well as + * support safe storage of plist objects in inter-process shared memory + * regions. + * + * If you are using these in a shared memory region, just be sure that only + * the process with listeners does any and all modifications, and that it + * unsubscribes before detaching from the region (or else destroys the region + * itself) + * + * There isn't a callback if entries themselves are modified, only when new + * entries are added, or old ones removed. If you want to know any time any + * aspect of any entry is modified, listen for the add and remove callbacks, + * and then add yourself as a listener to each entry individually. */ class Collection : public ObjectBase { public: - //! get notified of changes; be sure to call removeCollectionListener() before destructing @a l! - virtual void addCollectionListener(CollectionListener* l); - //! no longer take notification of changes to this object's value - virtual void removeCollectionListener(CollectionListener* l); - //! test if @a l is currently registered as a listener - virtual bool isCollectionListener(CollectionListener* l); + //! Specifies that a collection of collections cannot contain any primitive values + template struct conversion_policy { typedef typename U::DeniedValueConversions value_conversion; }; + + //! used to define values for LoadSavePolicy values so we can test a bit out of the policy value + enum LoadSaveActionBitMask { + ADDITIONS=1, //!< if this bit is set in #loadPolicy's value, entries not found in the collection will be added, or for #savePolicy, entries will be added to the file + REMOVALS=2 //!< if this bit is set in #loadPolicy's value, entries not found in the file will be removed from the collection, or for #savePolicy, entries will be removed from the file + }; + + //! Arguments for setLoadPolicy() and setSavePolicy(), specifies how to handle orphaned entries when loading or saving + /*! An entry is considered "orphaned" if you are loading or saving into a pre-existing file, + * and an entry exists in one location (the collection or the file), but not the other. + * The results look like this... (add/remove refer to the destination i.e. collection if loading, file if saving): + * + * + * + * + * + * + * + *
@b LoadingSYNCINTERSECTUNIONFIXED
not in file, in collectionremoveremoveignoreignore
in file, not in collectionaddignoreaddignore
@b SavingSYNCINTERSECTUNIONFIXED
not in file, in collectionaddignoreaddignore
in file, not in collectionremoveremoveignoreignore
+ * + * Commonly, you'll want to use SYNC (the default) to support dynamic storage, and FIXED load/SYNC save + * for configuration settings (or perhaps FIXED load and UNION save to keep 'extra' values in the file...)*/ + enum LoadSavePolicy { + FIXED = 0, //!< destination will have the same entries as before, ignores orphans and only updates entries with matching keys + UNION = ADDITIONS, //!< destination will have its current entries, as well as new ones from the source + INTERSECT = REMOVALS, //!< destination will only hold entries which are in both locations, removes entries not found in source, ignores new entries + SYNC = ADDITIONS|REMOVALS //!< destination will mirror source, new entries are added, missing entries are removed + }; - //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but gives a warning) - virtual void setEntry(const std::string& name, ObjectBase& val, bool warnExists=false)=0; - //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but gives a warning) - virtual void addEntry(const std::string& name, ObjectBase& val, const std::string& comment="")=0; - //! insert a new entry to the dictionary, with key @a name and value @a val, control of deallocation given to collection - virtual void setEntry(const std::string& name, ObjectBase* val, bool warnExists=false)=0; - //! insert a new entry to the dictionary, with key @a name and value @a val, control of deallocation given to collection - virtual void addEntry(const std::string& name, ObjectBase* val, const std::string& comment="")=0; + //! assignment (don't assign listeners); subclass should call fireEntriesChanged after calling this (and updating its own storage) + Collection& operator=(const Collection& d) { if(&d==this) return *this; ObjectBase::operator=(d); return *this; } - //! remove the entry with key @a name - virtual void removeEntry(const std::string& name)=0; - //! return the value of the key @a name, or NULL if it doesn't exist - virtual ObjectBase* getEntry(const std::string& name) const=0; - //! return the value of the key @a name, or NULL if it doesn't exist (equivalent to getEntry(name)) - virtual ObjectBase* operator[](const std::string& name) const { return getEntry(name); } + //! destructor + ~Collection(); + + //! recursively resolves @a path interpreted as a series of collection entry names separated by '.', returns NULL if it doesn't exist + virtual ObjectBase* resolveEntry(const std::string& path) const=0; //! remove all entries in one fell swoop virtual void clear()=0; + //! return the size of the collection + virtual size_t size() const=0; + + //! get notified of changes; be sure to call removeCollectionListener() before destructing @a l! + virtual void addCollectionListener(CollectionListener* l) const; + //! no longer take notification of changes to this object's value + virtual void removeCollectionListener(CollectionListener* l) const; + //! test if @a l is currently registered as a listener + virtual bool isCollectionListener(CollectionListener* l) const; - //! replaces previous comment for @a name, or adds it if it doesn't already exist (can preceed actual entry!) - virtual void setComment(const std::string& name, const std::string& comment)=0; - //! returns comment retrieved from loaded file, or any subsequent call to setComment - virtual const std::string& getComment(const std::string& name) const=0; - void setUnusedWarning(bool b) { warnUnused=b; } //!< set #warnUnused - bool getUnusedWarning() { return warnUnused; } //!< returns #warnUnused + bool getUnusedWarning() const { return warnUnused; } //!< returns #warnUnused - virtual bool getTrimExtraLoad() const { return trimExtraLoad; } //!< returns #trimExtraLoad - virtual bool getTrimExtraSave() const { return trimExtraSave; } //!< returns #trimExtraSave - virtual void setTrimExtra(bool trim) { trimExtraLoad=trimExtraSave=trim; } //!< sets #trimExtraLoad and #trimExtraSave to the save value - virtual void setTrimExtra(bool trimLoad, bool trimSave) { trimExtraLoad=trimLoad; trimExtraSave=trimSave; } //!< sets #trimExtraLoad and #trimExtraSave + virtual LoadSavePolicy getLoadPolicy() const { return loadPolicy; } //!< returns #loadPolicy + virtual LoadSavePolicy getSavePolicy() const { return savePolicy; } //!< returns #savePolicy + virtual void setLoadPolicy(LoadSavePolicy lp) { loadPolicy=lp; } //!< assigns #loadPolicy + virtual void setSavePolicy(LoadSavePolicy sp) { savePolicy=sp; } //!< assigns #savePolicy + virtual void setLoadSavePolicy(LoadSavePolicy lp, LoadSavePolicy sp) { setLoadPolicy(lp); setSavePolicy(sp); } //!< assigns #loadPolicy and #savePolicy respectively + + //! defines separator between sub-collections + /*! (defined as a function instead of just a constant member so there's no issues with initialization order) */ + static const std::string& subCollectionSep() { + static std::string sep(1,'.'); + return sep; + } + + //! returns longest key length which matches the regular expression + virtual unsigned int getLongestKeyLen(const regex_t* reg=NULL, unsigned int depth=-1) const=0; + + //! returns true if the Collection subclass allows storage of the argument + virtual bool canContain(const ObjectBase& obj)=0; + + virtual long toLong() const; + virtual double toDouble() const; protected: //! constructor - explicit Collection(bool bl, bool bs) : ObjectBase(), collectionListeners(), warnUnused(true), trimExtraLoad(bl), trimExtraSave(bs) {autoFormat=false;} + Collection() : ObjectBase(), collectionListeners(), warnUnused(true), loadPolicy(SYNC), savePolicy(SYNC) {autoFormat=false;} + //! constructor + Collection(LoadSavePolicy lp, LoadSavePolicy sp) : ObjectBase(), collectionListeners(), warnUnused(true), loadPolicy(lp), savePolicy(sp) {autoFormat=false;} //! copy constructor (don't assign listeners) - Collection(const Collection& d) : ObjectBase(d), collectionListeners(), warnUnused(d.warnUnused), trimExtraLoad(d.trimExtraLoad), trimExtraSave(d.trimExtraSave) {autoFormat=false;} - //! assignment (don't assign listeners); subclass should call fireEntriesChanged after calling this (and updating it storage) - Collection& operator=(const Collection& d) { if(&d==this) return *this; ObjectBase::operator=(d); return *this; } - //! destructor - ~Collection(); + Collection(const Collection& d) : ObjectBase(d), collectionListeners(), warnUnused(d.warnUnused), loadPolicy(d.loadPolicy), savePolicy(d.savePolicy) {autoFormat=false;} //! run through #collectionListeners, calling CollectionListener::plistCollectionEntryAdded(*this,val) virtual void fireEntryAdded(ObjectBase& val); @@ -67,53 +131,51 @@ //! run through #collectionListeners, calling CollectionListener::plistCollectionEntriesChanged(*this) virtual void fireEntriesChanged(); //! stores a list of the current listeners - std::list* collectionListeners; + mutable std::set* collectionListeners; - //! return the length of the longest key for formatting purposes - virtual unsigned int getLongestKeyLen() const=0; - //! a forwarding function to allow recursive flow of control (gets around not being able to call protected functions on non-this objects) - static unsigned int getLongestKeyLenOther(const Collection& c) { return c.getLongestKeyLen(); } + //! returns index corresponding to @a name, which should encode an integer value less than or equal to the current size + static size_t getIndex(const std::string& name); - //! if true (the default) loadXML will give warnings if there are unused entries in the node it is passed (can only happen if trimExtraLoad is false), or extra values in a file being saved into (can only happen if trimExtraSave is false) - bool warnUnused; - //! if true, unloaded items in the collection will be removed after a load, and new entries will be created for extras in the source (brings storage into complete sync with input) - bool trimExtraLoad; - //! if true, unsaved items in the destination will be removed after a save (brings output XML tree into complete sync with storage) - bool trimExtraSave; + //! returns a prefix for items within the collection + static std::string getIndentationPrefix(xmlNode* node); //! when an empty string is needed for not found items /*! (defined as a function instead of just a constant member so there's no issues with initialization order) */ - static const std::string& Collection::emptyStr() { + static const std::string& emptyStr() { static std::string mt; return mt; } - //! defines separator between sub-collections + //! how much to indent each sub-collection /*! (defined as a function instead of just a constant member so there's no issues with initialization order) */ - static const std::string& Collection::subCollectionSep() { - static std::string sep="."; - return sep; + static const std::string& perIndent() { + static std::string pi(1,'\t'); + return pi; } + //! when saving comments to file, the key name will automatically be prepended to the comment, unless the key is found within this many characters from the beginning of the comment + static const unsigned int KEY_IN_COMMENT_MAX_POS=10; + + //! if true (the default) loadXML will give warnings using FIXED policy and there are ignored entries in the source while loading or ignored entries in the destination while saving + bool warnUnused; + //! specifies how to handle "orphaned" entries while loading + LoadSavePolicy loadPolicy; + //! specifies how to handle "orphaned" entries while saving + LoadSavePolicy savePolicy; }; - //! Maintains a set of (key,value) pairs, where a value can be any subclass of ObjectBase - /*! This class supports callbacks upon modification through the use of the - * CollectionListener interface. Note that we only store a pointer to the - * listener list, which is typically unallocated when no listeners are - * active. This should ensure minimal memory usage per object, as well as - * support safe storage of plist objects in inter-process shared memory - * regions. - * - * If you are using these in a shared memory region, just be sure that only - * the process with listeners does any and all modifications, and that it - * unsubscribes before detaching from the region (or else destroys the region - * itself) - * - * There isn't a callback if entries themselves are modified, only when new - * entries are added, or old ones removed. If you want to know any time any - * aspect of any entry is modified, listen for the add and remove callbacks, - * and then add yourself as a listener to each entry individually. */ - class Dictionary : public Collection { - friend std::ostream& operator<<(std::ostream& os, const Dictionary& d); + + + + //! Maintains a set of (key,value) pairs, see DictionaryOf, and the Dictionary typedef + /*! You can add or set entries by a quite a few variations on addEntry(), setEntry(), or addValue(). + * Basically these boil down to either: + * - pass a pointer to an ObjectBase or directly pass a primitive value (int, float, char, etc.), + * in which case the dictionary will assume management of the corresponding ObjectBase + * instance (freeing the memory region when removed) + * - pass a reference to an ObjectBase, in which case you retain control over the object's + * allocation + */ + class DictionaryBase : virtual public Collection { + friend std::ostream& operator<<(std::ostream& os, const DictionaryBase& d); public: //! shorthand for the type of the storage typedef std::map storage_t; @@ -122,46 +184,124 @@ //! shorthand for iterators to be returned typedef storage_t::const_iterator const_iterator; - //! constructor - Dictionary() : Collection(false,false), dict(), myRef(), comments() {} - //! constructor - explicit Dictionary(bool growable) : Collection(growable,growable), dict(), myRef(), comments() {} - //! copy constructor (don't assign listeners) - Dictionary(const Dictionary& d) : Collection(d), dict(d.dict), myRef(d.myRef), comments(d.comments) { cloneMyRef(); } - //! assignment (don't assign listeners); subclass should call fireEntriesChanged after calling this (and updating its own storage) - Dictionary& operator=(const Dictionary& d) { if(&d==this) return *this; clear(); Collection::operator=(d); dict=d.dict; myRef=d.myRef; comments=d.comments; cloneMyRef(); fireEntriesChanged(); return *this; } - //! destructor - ~Dictionary() { clear(); } - - //! insert a new entry to the map; expects @a val to be either a primitive type, like int, float, etc., or one of the variable-sized Collection's, like Vector - template - void setValue(const std::string& name, const T& val, bool warnExists=false) { setEntry(name,new Primitive(val),warnExists); } - //! insert a new entry to the map, and corresponding comment; expects @a val to be either a primitive type, like int, float, etc., or one of the variable-sized Collection's, like Vector - template - void addValue(const std::string& name, const T& val, const std::string& comment="", bool warnExists=true) { addEntry(name,new Primitive(val),comment,warnExists); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void setValue(const std::string& name, const char val[], bool warnExists=false) { setEntry(name,new Primitive(val),warnExists); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void addValue(const std::string& name, const char val[], const std::string& comment="") { addEntry(name,new Primitive(val),comment,true); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void addValue(const std::string& name, const char val[], const std::string& comment, bool warnExists) { addEntry(name,new Primitive(val),comment,warnExists); } + //! Indicates that no value conversions are allowed + /*! The actual storage type is still allowed, so technically we could use EntryConstraint + * instead as the conversion policy, but that doesn't gain anything because you would need + * to know the PO to test for it. At least with this you can test for DeniedValueConversions as a base + * class and then fall back to testing individual PO's if you want. */ + struct DeniedValueConversions { + virtual ~DeniedValueConversions() {} //!< no-op destructor + }; - //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but can give a warning) - virtual void setEntry(const std::string& name, ObjectBase& val, bool warnExists=false); - //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but can give a warning) - virtual void addEntry(const std::string& name, ObjectBase& val, const std::string& comment="") { addEntry(name,val,comment,true); } - //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but can give a warning) - virtual void addEntry(const std::string& name, ObjectBase& val, const std::string& comment, bool warnExists); - virtual void setEntry(const std::string& name, ObjectBase* val, bool warnExists=false); - virtual void addEntry(const std::string& name, ObjectBase* val, const std::string& comment="") { addEntry(name,val,comment,true); } - //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but can give a warning) - virtual void addEntry(const std::string& name, ObjectBase* val, const std::string& comment, bool warnExists); - - //! remove the entry with key @a name - virtual void removeEntry(const std::string& name); - //! return the value of the key @a name, or NULL if it doesn't exist - virtual ObjectBase* getEntry(const std::string& name) const; + //! This base conversion policy doesn't actually specify any conversions at all -- this serves as a base class to provide the ability to directly add entries of the specified type; the subclasses will add value conversions + /*! This class is useless to end users: to use it they would have to know the template type being used, + * which if they knew, they could just dynamic_cast to the DictionaryOf type directly. The point of this + * class is to provide the abstract functions to the its subclasses, which use them to implement their + * various conversions. */ + template + struct EntryConstraint { + virtual ~EntryConstraint() {} //!< no-op destructor + //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but can give a warning) + virtual void setEntry(const std::string& name, PO& val, bool warnExists=false)=0; + //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name with a warning) + virtual void addEntry(const std::string& name, PO& val, const std::string& comment="", bool warnExists=true)=0; + //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name, but can give a warning); control of (de)allocation will be assumed by the dictionary + virtual void setEntry(const std::string& name, PO* val, bool warnExists=false)=0; + //! insert a new entry to the dictionary, with key @a name and value @a val (replaces any previous entry by same name with a warning); control of (de)allocation will be assumed by the dictionary + virtual void addEntry(const std::string& name, PO* val, const std::string& comment="", bool warnExists=true)=0; + }; + + //! Abstract base class to test whether the collection will accept strings (possibly converting to a value type, or storing directly as string depending on concrete type) + /*! The point of this class is to handle the situation where you have a DictionaryBase and user input to append, and + * you don't want to have to test every combination of template parameters to DictionaryOf to find out if you can + * add the data. Instead, test dynamic_cast, and if it is successful, you + * can pass the string without having to know the actual value type of the dictionary. */ + struct StringConversion { + virtual ~StringConversion() {} //!< no-op destructor + //! generic addition of value, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, const std::string& val, const std::string& comment="", bool warnExists=true)=0; + }; + + //! Abstract base class to test whether the collection will accept integers (possibly converting to another value type, or storing directly as a [unsigned] long depending on concrete type) + /*! The point of this class is to handle the situation where you have a DictionaryBase and user input to append, and + * you don't want to have to test every combination of template parameters to DictionaryOf to find out if you can + * add the data. Instead, test dynamic_cast, and if it is successful, you + * can pass the data without having to know the actual value type of the dictionary. */ + struct IntegerConversion { + virtual ~IntegerConversion() {} //!< no-op destructor + //! generic addition of value, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, long val, const std::string& comment="", bool warnExists=true)=0; + //! generic addition of value, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, unsigned long val, const std::string& comment="", bool warnExists=true)=0; + }; + + //! Abstract base class to test whether the collection will accept floating point numbers (possibly converting to another value type, or storing directly as a double depending on concrete type) + /*! The point of this class is to handle the situation where you have a DictionaryBase and user input to append, and + * you don't want to have to test every combination of template parameters to DictionaryOf to find out if you can + * add the data. Instead, test dynamic_cast, and if it is successful, you + * can pass the data without having to know the actual value type of the dictionary. */ + struct RealConversion { + virtual ~RealConversion() {} //!< no-op destructor + //! generic addition of value, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, double val, const std::string& comment="", bool warnExists=true)=0; + }; + + //! This conversion policy accepts entries of the specified template type, and will try to create new instances of that type constructed from any values which are passed. + /*! Use of this conversion policy requires that the template parameter is not abstract, + * as the policy will be trying to create new instances directly from the specified type. */ + template + struct ConversionTo : public StringConversion, public IntegerConversion, public RealConversion, public EntryConstraint { + //! insert a new entry to the map, and corresponding comment; expects @a val to be either a primitive type, like int, float, etc., or one of the variable-sized Collection's, like Array, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + template + void addValue(const std::string& name, const T& val, const std::string& comment="", bool warnExists=true) { addEntry(name,new PO(val),comment,warnExists); } + virtual void addValue(const std::string& name, const std::string& val, const std::string& comment="", bool warnExists=true) { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(name,po,comment,warnExists); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, char val[], const std::string& comment="", bool warnExists=true) { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(name,po,comment,warnExists); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, const char val[], const std::string& comment="", bool warnExists=true) { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(name,po,comment,warnExists); } + virtual void addValue(const std::string& name, long val, const std::string& comment="", bool warnExists=true) { addEntry(name,new PO(val),comment,warnExists); } + virtual void addValue(const std::string& name, unsigned long val, const std::string& comment="", bool warnExists=true) { addEntry(name,new PO(val),comment,warnExists); } + virtual void addValue(const std::string& name, double val, const std::string& comment="", bool warnExists=true) { addEntry(name,new PO(val),comment,warnExists); } + }; + + //! This conversion policy accepts any entries of the specified template type, values will be directly wrapped as Primitives so no conversion at all is actually performed + /*! Use addEntry() to add ObjectBase subclasses -- addValue is for POD types */ + template + struct WrapValueConversion : public StringConversion, public IntegerConversion, public RealConversion, public EntryConstraint { + //! insert a new entry to the map, and corresponding comment; expects @a val to be either a primitive type, like int, float, etc., control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + template + void addValue(const std::string& name, const T& val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + virtual void addValue(const std::string& name, const std::string& val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, char val[], const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the dictionary + virtual void addValue(const std::string& name, const char val[], const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + virtual void addValue(const std::string& name, long val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + virtual void addValue(const std::string& name, unsigned long val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + virtual void addValue(const std::string& name, double val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive(val),comment,warnExists); } + }; + + //! remove the entry with key @a name, returns true if something was actually removed (if false, wasn't there to begin with) + virtual bool removeEntry(const std::string& name); + + //! change the key for an entry from @a oldname to @a newname, returns false if @a oldname didn't exist (thus no change was made) + /*! If the collection owns the reference to the object, you have to use this function instead + * of a pair of calls to removeEntry/addEntry, otherwise you will wind up with an invalid pointer! */ + virtual bool renameEntry(const std::string& oldname, const std::string& newname); + //! exchange the values for a pair of keys -- if either key doesn't exist, forwards call to renameEntry() + /*! returns true if the swap was successful, only returns false if both keys are invalid */ + virtual bool swapEntry(const std::string& a, const std::string& b); + + //! returns a reference to the entry with the specified name, creating it if it doesn't exist + virtual ObjectBase& getEntry(const std::string& name)=0; + //! returns a reference to the entry with the specified name, creating it if it doesn't exist + virtual ObjectBase& operator[](const std::string& name)=0; + //! returns a pointer to entry with the specified 'path', which may recurse through sub-collections + virtual ObjectBase* resolveEntry(const std::string& path) const; + //! returns an iterator to an entry in the current dictionary + const_iterator findEntry(const std::string& name) const { return dict.find(name); } + virtual void clear(); //! return an STL const_iterator to the first entry @@ -169,7 +309,7 @@ //! return the one-past-end const_iterator const_iterator end() const { return dict.end(); } //! return the size of the dictionary - size_t size() const { return dict.size(); } + virtual size_t size() const { return dict.size(); } //! replaces previous comment for @a name, or adds it if it doesn't already exist (can preceed actual entry!) void setComment(const std::string& name, const std::string& comment); @@ -177,23 +317,38 @@ const std::string& getComment(const std::string& name) const; virtual void loadXML(xmlNode* node); - virtual void saveXML(xmlNode* node) const; + virtual void saveXML(xmlNode* node) const { std::set seen; saveXML(node,!(savePolicy&ADDITIONS),seen); } + //! saves the dictionary into the specified node + /*! @param[in] node the xml node which should be saved into + * @param[in] onlyOverwrite if is true, only saves entries for keys already found in the node (this overrides the current savePolicy value) + * @param[in] seen used to keep track of which nodes have been seen in @a node -- may be of particular interest with @a onlyOverride set + * + * @a seen is not cleared before being used.*/ + virtual void saveXML(xmlNode* node, bool onlyOverwrite, std::set& seen) const; virtual std::string toString() const; - //! clone implementation for Dictionary - PLIST_CLONE_DEF(Dictionary,new Dictionary(*this)); + //! returns the length of the longest key, subject to an optional regular expression and max depth + virtual unsigned int getLongestKeyLen(const regex_t* reg=NULL, unsigned int depth=-1) const; + + //! returns true if the specified object will be deallocated when removed from the dictionary + bool ownsReference(ObjectBase * val) const { return myRef.find(val)==myRef.end(); } protected: - virtual void fireEntryRemoved(ObjectBase& val); + //! constructor + explicit DictionaryBase(bool growable) : Collection(growable?UNION:FIXED,SYNC), dict(), myRef(), comments() { setLoadSavePolicy(growable?UNION:FIXED,SYNC); } + //! copy constructor (don't assign listeners) + DictionaryBase(const DictionaryBase& d) : Collection(d), dict(d.dict), myRef(d.myRef), comments(d.comments) { cloneMyRef(); setLoadSavePolicy(d.getLoadPolicy(),d.getSavePolicy()); } + //! assignment (don't assign listeners) + DictionaryBase& operator=(const DictionaryBase& d) { Collection::operator=(d); return *this; } + + //! destructor + ~DictionaryBase() { clear(); } //! indicates that the storage implementation should mark this as an externally supplied heap reference, which needs to be deleted on removal/destruction virtual void takeObject(const std::string& name, ObjectBase* obj); - //! called with each node being loaded so subclass can handle appropriately - virtual bool loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment); - - virtual unsigned int getLongestKeyLen() const; + virtual void fireEntryRemoved(ObjectBase& val); //! returns an entry matching just the prefix /*! @param[in] name the name being looked up @@ -209,6 +364,15 @@ //! called after an assignment or copy to clone the objects in #myRef to perform a deep copy virtual void cloneMyRef(); + //! called with each node being loaded so subclass can handle appropriately + virtual bool loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment)=0; + + //! called with each node being saved so subclass can handle appropriately, return true if successful and reset key if changed + virtual bool saveOverXMLNode(xmlNode* k, xmlNode* val, const std::string& key, std::string comment, const std::string& indentStr, std::set& seen) const; + + //! called with each node being saved so subclass can handle appropriately, return true if successful and set key + virtual void saveXMLNode(xmlNode* node, const std::string& key, const ObjectBase* val, const std::string& indentStr) const; + //! storage of entries -- mapping from keys to value pointers storage_t dict; @@ -221,21 +385,431 @@ /*! not every key necessarily has a comment! */ comments_t comments; }; - //! provides textual output - std::ostream& operator<<(std::ostream& os, const Dictionary& d); - //! A collection of plist objects, similar to a Dictionary, but no keys -- order matters! - /*! There's two versions of the plist array -- one is this Array class, the other is - * the Vector. This class is designed to be a fixed size -- you should add the entries - * which you expect to find in the array, and extra entries will be ignored when loading - * (with an optional warning). You can mix different primitive types in any order - * you choose. + //! A dictionary which requires all elements to be subtypes of the PO template argument + /*! You can add or set entries by a quite a few variations on addEntry(), setEntry(), and addValue (via the Alloc conversion policy) + * Basically these boil down to either: + * - pass a pointer to an ObjectBase or directly pass a primitive value (int, float, char, etc.), + * in which case the dictionary will assume management of the corresponding ObjectBase + * instance (freeing the memory region when removed) + * - pass a reference to an ObjectBase, in which case you retain control over the object's + * allocation + * + * You have probably noticed this is a templated class -- you can provide any of the ObjectBase + * subclasses to restrict the storage to that particular type, which will make life easier when + * retrieving objects since their type will be known. * - * The other class, Vector, takes the opposite tack -- it handles loading a variable - * number of entries, but handles the allocation of those objects internally. + * However, if you @e want an dictionary of mixed types, you can pass ObjectBase itself for the + * template parameter, and you can then insert any combination of the plist types into the + * same dictionary. For convenience, a plist::Dictionary typedef is provided which does exactly this. + * + * So plist::Dictionary can handle any mixture of types, whereas plist::DictionaryOf will @e only + * accept the plist objects of type PO (or their subclasses). The Alloc template argument + * allows you to define how new string values will be handled from DictionaryBase. + * + * The optional conversion policy template specifies a base class for the dictionary which + * can control how the dictionary will handle conversions from non-PO-based types. */ - class Array : public Collection { - friend std::ostream& operator<<(std::ostream& os, const Array& d); + template::value_conversion > + class DictionaryOf : public DictionaryBase, public Alloc { + /// @cond INTERNAL + typedef typename storage_t::const_iterator::iterator_category const_iterator_category; + typedef typename std::pair const_iterator_value; + typedef typename storage_t::const_iterator::difference_type const_iterator_difference; + /// @endcond + public: + //! shorthand for the type of the storage + typedef typename DictionaryBase::storage_t storage_t; + + /// @cond INTERNAL + + //! iterator implementation which wraps storage_t::const_iterator to transparently dynamic_cast to the PO for client + class const_iterator : std::iterator { + public: + const_iterator(const storage_t::const_iterator& sit) : it(sit), tmp() {} + const const_iterator_value& operator*() const { return std::make_pair(it->first,dynamic_cast(it->second)); } + const const_iterator_value* operator->() const { tmp=std::make_pair(it->first,dynamic_cast(it->second)); return &tmp; } + const_iterator& operator++() { ++it; return *this; } + const_iterator operator++(int) { return const_iterator(it++); } + const_iterator& operator--() { --it; return *this; } + const_iterator operator--(int) { return const_iterator(it--); } + bool operator==(const const_iterator& rhs) const { return it==rhs.it; } + bool operator!=(const const_iterator& rhs) const { return it!=rhs.it; } + + protected: + storage_t::const_iterator it; + mutable const_iterator_value tmp; + }; + /// @endcond + + //! constructor + DictionaryOf() : DictionaryBase(true), Alloc() {} + //! constructor + explicit DictionaryOf(bool growable) : DictionaryBase(growable), Alloc() {} + //! copy constructor (don't assign listeners) + DictionaryOf(const DictionaryOf& d) : DictionaryBase(d), Alloc(d) {} + //! assignment (don't assign listeners); subclass should call fireEntriesChanged after calling this (and updating its own storage) + DictionaryOf& operator=(const DictionaryOf& a); + + virtual void set(const ObjectBase& ob) { const DictionaryBase& d=dynamic_cast(ob); set(d); } + //! handles actual setting of one dictionary to another, similar to operator=(DictionaryOf), but allows for polymorphic conversion to the template type + virtual void set(const DictionaryBase& a); + + //! destructor + ~DictionaryOf() { } + + //! Replaces the entry with the specified key, optionally warns as it does so. If you simply want to set the *value* of the specified entry, try getEntry() and assignment... + /*! By passing a reference to the entry, you indicate you will retain responsibility for deallocation */ + virtual void setEntry(const std::string& name, PO& val, bool warnExists=false); + //! Convenience method for adding new entries, with optional comment and warning if replacing a previous entry + /*! By passing a reference to the entry, you indicate you will retain responsibility for deallocation */ + virtual void addEntry(const std::string& name, PO& val, const std::string& comment="", bool warnExists=true); + //! Replaces the entry with the specified key, optionally warns as it does so. If you simply want to set the *value* of the specified entry, try getEntry() and assignment... + /*! By passing a pointer to the entry, you indicate you wish the dictionary to assume responsibility for deallocation */ + virtual void setEntry(const std::string& name, PO* val, bool warnExists=false); + //! Convenience method for adding new entries, with optional comment and warning if replacing a previous entry + /*! By passing a pointer to the entry, you indicate you wish the dictionary to assume responsibility for deallocation */ + virtual void addEntry(const std::string& name, PO* val, const std::string& comment="", bool warnExists=true); + + //! returns a reference to the entry with the specified name, creating it if it doesn't exist + PO& getEntry(const std::string& name) { + DictionaryBase::const_iterator it=dict.find(name); + if(it!=dict.end()) + return dynamic_cast(*it->second); + else { + PO* p = allocatePO(); // do before dictionary access (next line) in case of exception (don't leak NULL dictionary entries!) + dict[name]=p; + return *p; + } + } + //! returns a reference to the entry with the specified name, creating it if it doesn't exist + PO& operator[](const std::string& name) { return getEntry(name); } + //! returns an iterator the \ pair with the specified key (returns end() if not found) + const_iterator findEntry(const std::string& name) const { return dict.find(name); } + + //! return an STL const_iterator to the first entry (note implicit conversion to specialized const_iterator) + const_iterator begin() const { return dict.begin(); } + //! return the one-past-end const_iterator (note implicit conversion to specialized const_iterator) + const_iterator end() const { return dict.end(); } + + virtual bool canContain(const ObjectBase& obj) { return (dynamic_cast(&obj)!=NULL); } + + //! clone implementation for Dictionary + PLIST_CLONE_DEF(DictionaryOf,(new DictionaryOf(*this))); + + protected: + //! allocates a new PO instance, unless PO is an abstract type, in which case a template specialization will throw a bad_cast + static PO* allocatePO() { return new PO; } + //! assigns one PO to another, unless PO is ObjectBase, in which case set() is used (via template specialization) + static void assignPO(PO& a, const PO& b) { a=b; } + + //! called with each node being loaded so subclass can handle appropriately + virtual bool loadXMLNode(const std::string& name, xmlNode* val, const std::string& comment); + }; + + + /*! plist::Dictionary can handle any mixture of types, whereas plist::DictionaryOf will @e only + * accept the plist objects of type PO (or their subclasses). This typedef is simply for + * convenience and passes ObjectBase for the template parameter. */ + typedef DictionaryOf Dictionary; + + template + void DictionaryOf::setEntry(const std::string& name, PO& val, bool warnExists/*=false*/) { + DictionaryBase::iterator it=dict.find(name); + if(it!=dict.end()) { + //found exact name match + if(&val==it->second) { + if(warnExists) + std::cerr << "Warning: entry ("<second)<<")" << std::endl; + std::cerr << " (use setEntry(...,false) if you expect you might need to overwrite)" << std::endl; + } + removeEntry(name); + //fall through to add new val + } + dict[name]=&val; + fireEntryAdded(val); + } + template + void DictionaryOf::addEntry(const std::string& name, PO& val, const std::string& comment, bool warnExists) { + DictionaryBase::storage_t::iterator it=dict.find(name); + if(it!=dict.end()) { + //found exact name match + if(&val==it->second) { + if(warnExists) + std::cerr << "Warning: entry ("<second)<<")" << std::endl; + std::cerr << " (use setEntry() if you expect you might need to overwrite)" << std::endl; + } + removeEntry(name); + //fall through to add new val + } + if(comment.size()>0) + comments[name]=comment; + dict[name]=&val; + fireEntryAdded(val); + } + template + void DictionaryOf::setEntry(const std::string& name, PO* val, bool warnExists/*=false*/) { + DictionaryBase::iterator it=dict.find(name); + if(it!=dict.end()) { + //found exact name match + if(val==it->second) { + if(warnExists) + std::cerr << "Warning: entry ("<second)<<")" << std::endl; + std::cerr << " (use setEntry(...,false) if you expect you might need to overwrite)" << std::endl; + } + removeEntry(name); + //fall through to add new val + } + dict[name]=val; + takeObject(name,val); + fireEntryAdded(*val); + } + template + void DictionaryOf::addEntry(const std::string& name, PO* val, const std::string& comment, bool warnExists) { + DictionaryBase::iterator it=dict.find(name); + if(it!=dict.end()) { + //found exact name match + if(val==it->second) { + if(warnExists) + std::cerr << "Warning: entry ("<second)<<")" << std::endl; + std::cerr << " (use setEntry() if you expect you might need to overwrite)" << std::endl; + } + removeEntry(name); + //fall through to add new val + } + dict[name]=val; + if(comment.size()>0) + comments[name]=comment; + takeObject(name,val); + fireEntryAdded(*val); + } + + //! implements the clone function for dictionary + PLIST_CLONE_IMPT2(PO,Alloc,DictionaryOf,(new DictionaryOf(*this))); + + /// @cond INTERNAL + template<> inline ObjectBase* DictionaryOf::value_conversion>:: + allocatePO() { throw std::runtime_error("plist::Dictionary cannot allocate new generic instances (ObjectBase)"); } + template<> inline PrimitiveBase* DictionaryOf::value_conversion>:: + allocatePO() { throw std::runtime_error("plist::Dictionary cannot allocate new generic instances (PrimitiveBase)"); } + template<> inline Collection* DictionaryOf::value_conversion>:: + allocatePO() { throw std::runtime_error("plist::Dictionary cannot allocate new generic instances (Collection)"); } + template<> inline void DictionaryOf::value_conversion>:: + assignPO(ObjectBase& a, const ObjectBase& b) { a.set(b); } + /// @endcond + + template + bool DictionaryOf::loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment) { + DictionaryBase::const_iterator it=dict.find(key); + if(it!=dict.end()) { + //found pre-existing entry + try { + //it's reasonable to assume that in common usage, the same type will be used each time + //so let's try to load into the current entry as is + it->second->loadXML(val); + if(dynamic_cast(it->second)!=NULL) { + const std::string headline=("======== "+key+" ========"); + if(comment.compare(0,headline.size(),headline)!=0) + setComment(key,comment); + else if(comment.size()>headline.size()) + setComment(key,comment.substr(headline.size())); + } else if(comment.size()>0) + setComment(key,comment); + return true; + } catch(...) { + // apparently that didn't work, we'll need to make a new reference or clone + if(loadPolicy!=SYNC) // can we do that? + throw; // nope -- give up + // still here? let's try a fresh load using the polymorphic loader (fall through below) + removeEntry(key); + } + } else if(!(loadPolicy&ADDITIONS)) { + if(warnUnused) + std::cerr << "Warning: reading plist dictionary, key '" << key << "' does not match a registered variable. Ignoring..." << std::endl; + return false; + } + ObjectBase * obj=plist::loadXML(val); + if(obj==NULL) + throw bad_format(val,"Dictionary encountered an unknown value type"); + PO * cobj = dynamic_cast(obj); + if(cobj==NULL) + throw bad_format(val,"Dictionary encountered a value of unexpected type"); + if(dynamic_cast(cobj)!=NULL) { + const std::string headline=("======== "+key+" ========"); + if(comment.compare(0,headline.size(),headline)!=0) + addEntry(key,cobj,comment); + else + addEntry(key,cobj,comment.substr(headline.size())); + } else + addEntry(key,cobj,comment); + return true; + } + + template + void DictionaryOf::set(const DictionaryBase& d) { + // if we're doing a large dictionary, might be worth checking if we're actually the same type + if(const DictionaryOf* od = dynamic_cast(&d)) { + operator=(*od); // same template type, use faster version! + return; + } + DictionaryBase::operator=(d); + + std::set seen; + for(DictionaryBase::const_iterator dit=d.begin(); dit!=d.end(); ++dit) { + const std::string key=dit->first; + ObjectBase* val=dit->second; + const std::string comment=d.getComment(key); + seen.insert(key); + DictionaryBase::storage_t::const_iterator it=dict.find(key); + if(it!=dict.end()) { + //found pre-existing entry + try { + //it's reasonable to assume that in common usage, the same type will be used each time + //so let's try to load into the current entry as is + it->second->set(*val); + if(comment.size()>0) + setComment(key,comment); + continue; + } catch(...) { + // apparently that didn't work, we'll need to make a new reference or clone + if(loadPolicy!=SYNC) // can we do that? + throw; // nope -- give up + // still here? let's try a fresh load using the polymorphic loader (fall through below) + removeEntry(key); + } + } else if(!(loadPolicy&ADDITIONS)) { + if(warnUnused) + std::cerr << "Warning: reading plist dictionary, key '" << key << "' does not match a registered variable. Ignoring..." << std::endl; + continue; + } + PO* obj=dynamic_cast(val); + if(obj==NULL) { + obj = allocatePO(); + try { + obj->set(*val); + } catch(...) { + delete obj; + throw; + } + myRef.insert(obj); + } else if(d.ownsReference(val)) { + // currently only clones the other collection's references -- should we clone everything? + obj = dynamic_cast(obj->clone()); + myRef.insert(obj); + } + if(dynamic_cast(obj)!=NULL) { + const std::string headline=("======== "+key+" ========"); + if(comment.compare(0,headline.size(),headline)!=0) + addEntry(key,*obj,comment); + else + addEntry(key,*obj,comment.substr(headline.size())); + } else + addEntry(key,*obj,comment); + } + if((loadPolicy&REMOVALS) && seen.size()!=size()) { + std::set rem; + for(const_iterator it=begin(); it!=end(); ++it) { + if(seen.find(it->first)==seen.end()) + rem.insert(it->first); + } + for(std::set::const_iterator it=rem.begin(); it!=rem.end(); ++it) + removeEntry(*it); + } + } + + template + DictionaryOf& DictionaryOf::operator=(const DictionaryOf& d) { + if(&d==this) + return *this; + DictionaryBase::operator=(d); + + std::set seen; + for(const_iterator dit=d.begin(); dit!=d.end(); ++dit) { + const std::string key=dit->first; + PO* val=dit->second; + const std::string comment=d.getComment(key); + seen.insert(key); + DictionaryBase::const_iterator it=dict.find(key); + if(it!=dict.end()) { + //found pre-existing entry + try { + //it's reasonable to assume that in common usage, the same type will be used each time + //so let's try to load into the current entry as is + assignPO(*dynamic_cast(it->second),*val); + if(comment.size()>0) + setComment(key,comment); + continue; + } catch(...) { + // apparently that didn't work, we'll need to make a new reference or clone + if(loadPolicy!=SYNC) // can we do that? + throw; // nope -- give up + // still here? let's try a fresh load using the polymorphic loader (fall through below) + removeEntry(key); + } + } else if(!(loadPolicy&ADDITIONS)) { + if(warnUnused) + std::cerr << "Warning: reading plist dictionary, key '" << key << "' does not match a registered variable. Ignoring..." << std::endl; + continue; + } + PO* obj=val; + // currently only clones the other dictionary's references -- should we clone everything? + if(d.myRef.find(val)!=d.myRef.end()) { + obj = dynamic_cast(obj->clone()); + myRef.insert(obj); + } + if(dynamic_cast(obj)!=NULL) { + const std::string headline=("======== "+key+" ========"); + if(comment.compare(0,headline.size(),headline)!=0) + addEntry(key,*obj,comment); + else + addEntry(key,*obj,comment.substr(headline.size())); + } else + addEntry(key,*obj,comment); + } + if((loadPolicy&REMOVALS) && seen.size()!=size()) { + std::set rem; + for(const_iterator it=begin(); it!=end(); ++it) { + if(seen.find(it->first)==seen.end()) + rem.insert(it->first); + } + for(std::set::const_iterator it=rem.begin(); it!=rem.end(); ++it) + removeEntry(*it); + } + return *this; + } + + + //! Maintains an array of value, see ArrayOf, and the Array typedef + /*! You can add or set entries by a quite a few variations on addEntry(), setEntry(), or addValue(). + * Basically these boil down to either: + * - pass a pointer to an ObjectBase or directly pass a primitive value (int, float, char, etc.), + * in which case the Array will assume management of the corresponding ObjectBase + * instance (freeing the memory region when removed) + * - pass a reference to an ObjectBase, in which case you retain control over the object's + * allocation + */ + class ArrayBase : virtual public Collection { + friend std::ostream& operator<<(std::ostream& os, const ArrayBase& d); public: //! shorthand for the type of the storage typedef std::vector storage_t; @@ -244,119 +818,195 @@ //! shorthand for iterators to be returned typedef storage_t::const_iterator const_iterator; - //! constructor - Array() : Collection(false,false), arr(), myRef(), comments() {} - //! constructor - explicit Array(bool growable) : Collection(growable,growable), arr(), myRef(), comments() {} - //! copy constructor (don't assign listeners) - Array(const Array& d) : Collection(d), arr(d.arr), myRef(d.myRef), comments(d.comments) { cloneMyRef(); } - //! assignment (don't assign listeners); subclass should call fireEntriesChanged after calling this (and updating it storage) - Array& operator=(const Array& d) { if(&d==this) return *this; clear(); Collection::operator=(d); arr=d.arr; myRef=d.myRef; comments=d.comments; cloneMyRef(); return *this; } - //! destructor - ~Array() { clear(); } + //! Indicates that no value conversions are allowed + /*! The actual storage type is still allowed, so technically we could use EntryConstraint + * instead as the conversion policy, but that doesn't gain anything because you would need + * to know the PO to test for it. At least with this you can test for DeniedValueConversions as a base + * class and then fall back to testing individual PO's if you want. */ + struct DeniedValueConversions { + virtual ~DeniedValueConversions() {} //!< no-op destructor + }; - //! insert a new entry to the end of the vector, and corresponding comment; expects @a val to be either a primitive type, like int, float, etc., or one of the variable-sized Collection's, like Vector, control of (de)allocation will be assumed by the Vector - template - void addValue(const T& val, const std::string& comment="") { addEntry(new Primitive(val),comment); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void addValue(const char val[], const std::string& comment="") { if(comment.size()>0) setComment(size(),comment); arr.push_back(new Primitive(val)); takeObject(size()-1,arr.back()); fireEntryAdded(*arr.back()); } + template + struct EntryConstraint { + virtual ~EntryConstraint() {} //!< no-op destructor + //! replaces previous entry at the specified @a index, which must represent an integer value less than or equal to the current array size + virtual void addEntry(PO& val, const std::string& comment="")=0; + //! replaces previous entry at the specified @a index, which must represent an integer value less than or equal to the current array size + virtual void addEntry(PO* val, const std::string& comment="")=0; + + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size + virtual void setEntry(size_t index, PO& val, bool warnExists=false)=0; + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size + virtual void addEntry(size_t index, PO& val, const std::string& comment="")=0; + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; control of (de)allocation will be assumed by the Array + virtual void setEntry(size_t index, PO* val, bool warnExists=false)=0; + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; control of (de)allocation will be assumed by the Array + virtual void addEntry(size_t index, PO* val, const std::string& comment="")=0; + }; - //! replaces previous entry at the specified @a index, which must represent an integer value less than or equal to the current array size; clone of @a val will be added - virtual void addEntry(ObjectBase& val, const std::string& comment="") { if(comment.size()>0) setComment(size(),comment); arr.push_back(&val); fireEntryAdded(*arr.back()); } - //! replaces previous entry at the specified @a index, which must represent an integer value less than or equal to the current array size; clone of @a val will be added - virtual void addEntry(ObjectBase* val, const std::string& comment="") { if(comment.size()>0) setComment(size(),comment); arr.push_back(val); takeObject(size()-1,val); fireEntryAdded(*arr.back()); } + //! Abstract base class to test whether the collection will accept strings (possibly converting to a value type, or storing directly as string depending on concrete type) + /*! The point of this class is to handle the situation where you have a DictionaryBase and user input to append, and + * you don't want to have to test every combination of template parameters to DictionaryOf to find out if you can + * add the data. Instead, test dynamic_cast, and if it is successful, you + * can pass the string without having to know the actual value type of the dictionary. */ + struct StringConversion { + virtual ~StringConversion() {} //!< no-op destructor + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(const std::string& val, const std::string& comment="")=0; + //! generic addition of value at a specified position + virtual void addValue(size_t index, const std::string&, const std::string& comment="")=0; + }; - //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size, control of (de)allocation will be assumed by the Vector - template - void setValue(size_t index, const T& val, bool warnExists=false) { setEntry(index,new Primitive(val),warnExists); } - //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size, control of (de)allocation will be assumed by the Vector - template - void addValue(size_t index, const T& val, const std::string& comment="") { addEntry(index,new Primitive(val),comment); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void setValue(size_t index, const char val[], bool warnExists=false) { setEntry(index,new Primitive(val),warnExists); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void addValue(size_t index, const char val[], const std::string& comment="") { addEntry(index,new Primitive(val),comment); } + //! Abstract base class to test whether the collection will accept integers (possibly converting to another value type, or storing directly as a [unsigned] long depending on concrete type) + /*! The point of this class is to handle the situation where you have a DictionaryBase and user input to append, and + * you don't want to have to test every combination of template parameters to DictionaryOf to find out if you can + * add the data. Instead, test dynamic_cast, and if it is successful, you + * can pass the data without having to know the actual value type of the dictionary. */ + struct IntegerConversion { + virtual ~IntegerConversion() {} //!< no-op destructor + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(long val, const std::string& comment="", bool warnExists=true)=0; + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(unsigned long val, const std::string& comment="", bool warnExists=true)=0; + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, long val, const std::string& comment="", bool warnExists=true)=0; + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, unsigned long val, const std::string& comment="", bool warnExists=true)=0; + }; - //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; clone will be added - virtual void setEntry(size_t index, ObjectBase& val, bool warnExists=false); - //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; clone will be added - virtual void addEntry(size_t index, ObjectBase& val, const std::string& comment=""); - //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; clone will be added - virtual void setEntry(size_t index, ObjectBase* val, bool warnExists=false); - //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; clone will be added - virtual void addEntry(size_t index, ObjectBase* val, const std::string& comment=""); + //! Abstract base class to test whether the collection will accept floating point numbers (possibly converting to another value type, or storing directly as a double depending on concrete type) + /*! The point of this class is to handle the situation where you have a DictionaryBase and user input to append, and + * you don't want to have to test every combination of template parameters to DictionaryOf to find out if you can + * add the data. Instead, test dynamic_cast, and if it is successful, you + * can pass the data without having to know the actual value type of the dictionary. */ + struct RealConversion { + virtual ~RealConversion() {} //!< no-op destructor + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(double val, const std::string& comment="", bool warnExists=true)=0; + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, double val, const std::string& comment="", bool warnExists=true)=0; + }; - //! replaces previous entry of the same name, which must represent an integer value less than or equal to the current array size, control of (de)allocation will be assumed by the Vector - template - void setValue(const std::string& name, const T& val,bool warnExists=false) { setEntry(name,new Primitive(val),warnExists); } - //! replaces previous entry of the same name, which must represent an integer value less than or equal to the current array size, control of (de)allocation will be assumed by the Vector - template - void addValue(const std::string& name, const T& val, const std::string& comment="") { addEntry(name,new Primitive(val),comment); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void setValue(const std::string& name, const char val[], bool warnExists=false) { setEntry(name,new Primitive(val),warnExists); } - //! "specialization" (actually just another override) for handling character arrays as strings - virtual void addValue(const std::string& name, const char val[], const std::string& comment="") { addEntry(name,new Primitive(val),comment); } - //! replaces previous entry of the same name, which must represent an integer value less than or equal to the current array size; clone will be added - virtual void setEntry(const std::string& name, ObjectBase& val, bool warnExists=false); - //! replaces previous entry of the same name, which must represent an integer value less than or equal to the current array size; clone will be added - virtual void addEntry(const std::string& name, ObjectBase& val, const std::string& comment=""); - //! replaces previous entry of the same name, which must represent an integer value less than or equal to the current array size; clone will be added - virtual void setEntry(const std::string& name, ObjectBase* val, bool warnExists=false); - //! replaces previous entry of the same name, which must represent an integer value less than or equal to the current array size; clone will be added - virtual void addEntry(const std::string& name, ObjectBase* val, const std::string& comment=""); + //! This conversion policy accepts entries of the specified template type, and will try to create new instances of that type constructed from any values which are passed. + /*! Use of this conversion policy requires that the template parameter is not abstract, + * as the policy will be trying to create new instances directly from the specified type. */ + template + struct ConversionTo : public StringConversion, public EntryConstraint { + //! insert a new entry to the end of the vector, and corresponding comment; expects @a val to be either a primitive type, like int, float, etc., or one of the variable-sized Collection's, like Array, control of (de)allocation will be assumed by the Array + template + void addValue(const T& val, const std::string& comment="") { addEntry(new PO(val),comment); } + virtual void addValue(const std::string& val, const std::string& comment="") { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(po,comment); } + //! "specialization" (actually just another override) for handling character arrays as strings + virtual void addValue(char val[], const std::string& comment="") { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(po,comment); } + //! "specialization" (actually just another override) for handling character arrays as strings + virtual void addValue(const char val[], const std::string& comment="") { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(po,comment); } + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(long val, const std::string& comment="") { addEntry(new PO(val),comment); } + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(unsigned long val, const std::string& comment="") { addEntry(new PO(val),comment); } + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(double val, const std::string& comment="") { addEntry(new PO(val),comment); } + + //! inserts new entry at the specified @a index, which must be less than or equal to the current array size, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + template + void addValue(size_t index, const T& val, const std::string& comment="") { addEntry(index,new PO(val),comment); } + virtual void addValue(size_t index, const std::string& val, const std::string& comment="") { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(index,po,comment); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, char val[], const std::string& comment="") { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(index,po,comment); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, const char val[], const std::string& comment="") { PO * po=new PO; try { po->set(val); } catch(...) { delete po; throw; } addEntry(index,po,comment); } + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(size_t index, long val, const std::string& comment="") { addEntry(index,new PO(val),comment); } + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(size_t index, unsigned long val, const std::string& comment="") { addEntry(index,new PO(val),comment); } + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(size_t index, double val, const std::string& comment="") { addEntry(index,new PO(val),comment); } + }; - //! remove the entry at position @a index - virtual void removeEntry(size_t index); - //! return the value at position @a index + //! This conversion policy accepts any entries of the specified template type, values will be directly wrapped as Primitives so no conversion at all is actually performed + /*! Use addEntry() to add ObjectBase subclasses -- addValue is for POD types */ + template + struct WrapValueConversion : public StringConversion, public EntryConstraint { + //! insert a new entry to the end of the vector, and corresponding comment; expects @a val to be either a primitive type, like int, float, etc., control of (de)allocation will be assumed by the Array + template + void addValue(const T& val, const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + virtual void addValue(const std::string& val, const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + //! "specialization" (actually just another override) for handling character arrays as strings + virtual void addValue(char val[], const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + //! "specialization" (actually just another override) for handling character arrays as strings + virtual void addValue(const char val[], const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(long val, const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(unsigned long val, const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + //! generic addition of value at end of collection, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(double val, const std::string& comment="") { this->addEntry(new Primitive(val),comment); } + + //! inserts new entry at the specified @a index, which must be less than or equal to the current array size, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + template + void addValue(size_t index, const T& val, const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + virtual void addValue(size_t index, const std::string& val, const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, char val[], const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + //! "specialization" (actually just another override) for handling character arrays as strings, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + virtual void addValue(size_t index, const char val[], const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(size_t index, long val, const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(size_t index, unsigned long val, const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + //! generic addition of value at specified position, control of (de)allocation of corresponding Primitive instance will be assumed by the Array + void addValue(size_t index, double val, const std::string& comment="") { this->addEntry(index,new Primitive(val),comment); } + }; + + //! remove the entry at position @a index, returns true if something was actually removed (if false, wasn't there to begin with) + virtual bool removeEntry(size_t index); + //! return the value at position @a index, which must exist (no range checking) ObjectBase& getEntry(size_t index) const { return *arr[index]; } - //! return the value of the key @a name, or NULL if it doesn't exist (equivalent to getEntry(index)) + //! return the value at position @a index, which must exist (no range checking, equivalent to getEntry(index)) ObjectBase& operator[](size_t index) const { return *arr[index]; } - - virtual void removeEntry(const std::string& name); - virtual ObjectBase* getEntry(const std::string& name) const; - virtual ObjectBase* operator[](const std::string& name) const { return getEntry(name); } + virtual ObjectBase* resolveEntry(const std::string& path) const; virtual void clear(); //! return an STL const_iterator to the first entry - const_iterator begin() const { return arr.begin(); } + const_iterator begin() const { ArrayBase::const_iterator tmp=arr.begin(); return reinterpret_cast(tmp); } // nasty hack //! return the one-past-end const_iterator - const_iterator end() const { return arr.end(); } - //! return the size of the dictionary - size_t size() const { return arr.size(); } + const_iterator end() const { ArrayBase::const_iterator tmp=arr.end(); return reinterpret_cast(tmp); } // nasty hack + //! return the size of the array + virtual size_t size() const { return arr.size(); } //! replaces previous comment for @a name, or adds it if it doesn't already exist (can preceed actual entry!) virtual void setComment(size_t index, const std::string& comment); //! returns comment retrieved from loaded file, or any subsequent call to setComment virtual const std::string& getComment(size_t index) const; - //! replaces previous comment for @a name, or adds it if it doesn't already exist (can preceed actual entry!) - virtual void setComment(const std::string& name, const std::string& comment); - //! returns comment retrieved from loaded file, or any subsequent call to setComment - virtual const std::string& getComment(const std::string& name) const; - virtual void loadXML(xmlNode* node); virtual void saveXML(xmlNode* node) const; - //! returns index corresponding to @a name, which should encode an integer value less than or equal to the current size - size_t getIndex(const std::string& name) const; - virtual std::string toString() const; - //! clone implementation for Array - PLIST_CLONE_DEF(Array,new Array(*this)); - - protected: - virtual void fireEntryRemoved(ObjectBase& val); + virtual unsigned int getLongestKeyLen(const regex_t* reg=NULL, unsigned int depth=-1) const; + + //! returns true if the specified object will be deallocated when removed from the array + bool ownsReference(ObjectBase * val) const { return myRef.find(val)==myRef.end(); } + +protected: + //! constructor + ArrayBase(bool growable) : Collection(growable?SYNC:FIXED,SYNC), arr(), myRef(), comments() { setLoadSavePolicy(growable?SYNC:FIXED,SYNC); } + //! copy constructor + ArrayBase(const ArrayBase& d) : Collection(d), arr(d.arr), myRef(d.myRef), comments(d.comments) { cloneMyRef(); setLoadSavePolicy(d.getLoadPolicy(),d.getSavePolicy()); } + //! assignment + ArrayBase& operator=(const ArrayBase& d) { Collection::operator=(d); return *this; } + + //! destructor + ~ArrayBase() { clear(); } //! indicates that the storage implementation should mark this as an externally supplied heap reference, which needs to be deleted on removal/destruction virtual void takeObject(size_t index, ObjectBase* obj); - //! called with each node being loaded so subclass can handle appropriately - virtual bool loadXMLNode(size_t index, xmlNode* val, const std::string& comment); - - virtual unsigned int getLongestKeyLen() const; + virtual void fireEntryRemoved(ObjectBase& val); //! returns an entry matching just the prefix /*! @param[in] name the name being looked up @@ -368,11 +1018,14 @@ * @param[out] seppos the position of the separator (sub-collections are separated by '.') * @return iterator of the sub entry*/ const_iterator getSubEntry(const std::string& name, std::string::size_type& seppos) const; - + //! called after an assignment or copy to clone the objects in #myRef to perform a deep copy virtual void cloneMyRef(); - //! storage of entries -- mapping from keys to value pointers + //! called by loadXML(), loads a single xmlNode into a specified position, replacing previous entry if it can't accept the new value (subject to the load/save policy...) + virtual bool loadXMLNode(size_t index, xmlNode* val, const std::string& comment)=0; + + //! storage of entries storage_t arr; //! objects which have been handed over to the collection for eventual de-allocation @@ -384,75 +1037,384 @@ /*! not every key necessarily has a comment! */ comments_t comments; }; - //! provides textual output - std::ostream& operator<<(std::ostream& os, const Array& d); - //! specialization of Dictionary::setValue() for ObjectBase subclasses - template<> - inline void Dictionary::setValue(const std::string& name, const ObjectBase& val, bool warnExists) { setEntry(name,dynamic_cast(val.clone()),warnExists); } - //! specialization of Dictionary::addValue() for ObjectBase subclasses - template<> - inline void Dictionary::addValue(const std::string& name, const ObjectBase& val, const std::string& comment, bool warnExists/*=true*/) { addEntry(name,dynamic_cast(val.clone()),comment,warnExists); } - //! specialization of Dictionary::setValue() for char* strings - template<> - inline void Dictionary::setValue(const std::string& name, const char* const& val, bool warnExists) { setEntry(name,new Primitive(val),warnExists); } - //! specialization of Dictionary::addValue() for char* strings - template<> - inline void Dictionary::addValue(const std::string& name, const char* const& val, const std::string& comment, bool warnExists/*=true*/) { addEntry(name,new Primitive(val),comment,warnExists); } - //! specialization of Dictionary::setValue() for char* strings - template<> - inline void Dictionary::setValue(const std::string& name, char* const& val, bool warnExists) { setEntry(name,new Primitive(val),warnExists); } - //! specialization of Dictionary::addValue() for char* strings - template<> - inline void Dictionary::addValue(const std::string& name, char* const& val, const std::string& comment, bool warnExists/*=true*/) { addEntry(name,new Primitive(val),comment,warnExists); } + + //! A collection of plist objects, similar to a Dictionary, but no keys -- order matters!, see plist::Array + /*! You can add or set entries by a quite a few variations on addEntry(), setEntry(), and addValue (via the Alloc conversion policy) + * Basically these boil down to either: + * - pass a pointer to an ObjectBase or directly pass a primitive value (int, float, char, etc.), + * in which case the Array will assume management of the corresponding ObjectBase + * instance (freeing the memory region when removed) + * - pass a reference to an ObjectBase, in which case you retain control over the object's + * allocation + * + * You have probably noticed this is a templated class -- you can provide any of the ObjectBase + * subclasses to restrict the storage to that particular type, which will make life easier when + * retrieving objects since their type will be known. + * + * However, if you @e want an Array of mixed types, you can pass ObjectBase itself for the + * template parameter, and you can then insert any combination of the plist types into the + * same array. For convenience, a plist::Array typedef is provided which does exactly this. + * + * So plist::Array can handle any mixture of types, whereas plist::ArrayOf will @e only + * accept the plist objects of type PO (or their subclasses). The Alloc template argument + * allows you to define how new string values will be handled from ArrayBase. + * + * The optional conversion policy template specifies a base class for the dictionary which + * can control how the dictionary will handle conversions from non-PO-based types. + */ + template::value_conversion > + class ArrayOf : public ArrayBase, public Alloc { + /// @cond INTERNAL + typedef typename storage_t::const_iterator::iterator_category const_iterator_category; + typedef typename storage_t::const_iterator::difference_type const_iterator_difference; + /// @endcond + public: + //! shorthand for the type of the storage + typedef typename ArrayBase::storage_t storage_t; - //! specialization of Array::addValue() for ObjectBase subclasses - template<> - inline void Array::addValue(const ObjectBase& val, const std::string& comment/*=""*/) { addEntry(dynamic_cast(val.clone()),comment); } - //! specialization of Array::addValue() for char* strings - template<> - inline void Array::addValue(const char* const& val, const std::string& comment/*=""*/) { addEntry(new Primitive(val),comment); } - //! specialization of Array::addValue() for char* strings - template<> - inline void Array::addValue(char* const& val, const std::string& comment/*=""*/) { addEntry(new Primitive(val),comment); } + /// @cond INTERNAL + + //! iterator implementation which wraps storage_t::const_iterator to transparently dynamic_cast to the PO for client + class const_iterator : std::iterator { + public: + typedef const PO* value_type; + typedef const_iterator_difference difference_type; + + const_iterator(const storage_t::const_iterator& sit) : it(sit) {} + const value_type& operator*() const { return dynamic_cast(**it); } + const value_type* operator->() const { return &dynamic_cast(*it); } + const_iterator& operator++() { ++it; return *this; } + const_iterator operator++(int) { return const_iterator(it++); } + const_iterator& operator--() { --it; return *this; } + const_iterator operator--(int) { return const_iterator(it--); } + + bool operator==(const const_iterator& rhs) const { return it==rhs.it; } + bool operator!=(const const_iterator& rhs) const { return it!=rhs.it; } + + // Random access iterator requirements + const value_type& operator[](const difference_type& __n) const { return it[__n]; } + const_iterator& operator+=(const difference_type& __n) { it += __n; return *this; } + const_iterator operator+(const difference_type& __n) const { return const_iterator(it + __n); } + const_iterator& operator-=(const difference_type& __n) { it -= __n; return *this; } + const_iterator operator-(const difference_type& __n) const { return const_iterator(it - __n); } + bool operator<(const const_iterator& __rhs) { return it < __rhs.it; } + bool operator>(const const_iterator& __rhs) { return it > __rhs.it; } + bool operator<=(const const_iterator& __rhs) { return it <= __rhs.it; } + bool operator>=(const const_iterator& __rhs) { return it >= __rhs.it; } + + protected: + storage_t::const_iterator it; + }; + /// @endcond + + //! constructor + ArrayOf() : ArrayBase(true), Alloc() {} + //! constructor + ArrayOf(typename storage_t::size_type n, const PO& t, bool growable=true) : ArrayBase(growable), Alloc() { + arr.resize(n); + for(ArrayBase::iterator it=arr.begin(); it!=arr.end(); ++it) + *it=new PO(t); + myRef.insert(arr.begin(),arr.end()); + } + //! copy constructor (don't assign listeners) + ArrayOf(const ArrayOf& d) : ArrayBase(d), Alloc(d) {} + //! assignment (don't assign listeners); subclass should call fireEntriesChanged after calling this (and updating its own storage) + ArrayOf& operator=(const ArrayOf& a); + + virtual void set(const ObjectBase& ob) { const ArrayBase& a=dynamic_cast(ob); set(a); } + virtual void set(const ArrayBase& a); //!< handles polymorphic assignment of ArrayBase subclasses, similar to operator=(ArrayOf), but allows conversion of entries + + //! destructor + ~ArrayOf() { } + + //! adds a new entry to the end of the array, (de)allocation retained by caller + virtual void addEntry(PO& val, const std::string& comment="") { if(comment.size()>0) setComment(size(),comment); arr.push_back(&val); fireEntryAdded(*arr.back()); } + //! adds a new entry to the end of the array, (de)allocation responsibility of array + virtual void addEntry(PO* val, const std::string& comment="") { if(comment.size()>0) setComment(size(),comment); arr.push_back(val); takeObject(size()-1,val); fireEntryAdded(*arr.back()); } + + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size + virtual void setEntry(size_t index, PO& val, bool warnExists=false); + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size + virtual void addEntry(size_t index, PO& val, const std::string& comment=""); + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; control of (de)allocation will be assumed by the Array + virtual void setEntry(size_t index, PO* val, bool warnExists=false); + //! replaces previous entry at the specified @a index, which must be less than or equal to the current array size; control of (de)allocation will be assumed by the Array + virtual void addEntry(size_t index, PO* val, const std::string& comment=""); + + //! return the value at position @a index, which must exist (no range checking) + PO& getEntry(size_t index) const { return dynamic_cast(*arr[index]); } + //! return the value at position @a index, which must exist (no range checking, equivalent to getEntry(index)) + PO& operator[](size_t index) const { return dynamic_cast(*arr[index]); } + + //! return an STL const_iterator to the first entry + const_iterator begin() const { return arr.begin(); } + //! return the one-past-end const_iterator + const_iterator end() const { return arr.end(); } + + //! returns true if the array can store the specified object + virtual bool canContain(const ObjectBase& obj) { return (dynamic_cast(&obj)!=NULL); } + + //! clone implementation for Array + PLIST_CLONE_DEF(ArrayOf,(new ArrayOf(*this))); + + protected: + //! allocates a new PO instance, unless PO is an abstract type, in which case a template specialization will throw a bad_cast + static PO* allocatePO() { return new PO; } + //! assigns one PO to another, unless PO is ObjectBase, in which case set() is used (via template specialization) + static void assignPO(PO& a, const PO& b) { a=b; } + + //! called with each node being loaded so subclass can handle appropriately + virtual bool loadXMLNode(size_t index, xmlNode* val, const std::string& comment); + }; - //! specialization of Array::setValue() for ObjectBase subclasses - template<> - inline void Array::setValue(size_t index, const ObjectBase& val, bool warnExists) { setEntry(index,dynamic_cast(val.clone()),warnExists); } - //! specialization of Array::setValue() for char* strings - template<> - inline void Array::setValue(size_t index, const char* const& val, bool warnExists) { setEntry(index,new Primitive(val),warnExists); } - //! specialization of Array::setValue() for char* strings - template<> - inline void Array::setValue(size_t index, char* const& val, bool warnExists) { setEntry(index,new Primitive(val),warnExists); } - //! specialization of Array::addValue() for ObjectBase subclasses - template<> - inline void Array::addValue(size_t index, const ObjectBase& val, const std::string& comment) { addEntry(index,dynamic_cast(val.clone()),comment); } - //! specialization of Array::addValue() for char* strings - template<> - inline void Array::addValue(size_t index, const char* const& val, const std::string& comment) { addEntry(index,new Primitive(val),comment); } - //! specialization of Array::addValue() for char* strings - template<> - inline void Array::addValue(size_t index, char* const& val, const std::string& comment) { addEntry(index,new Primitive(val),comment); } + /*! plist::Array can handle any mixture of types, whereas plist::ArrayOf will @e only + * accept the plist objects of type PO (or their subclasses). This typedef is simply for + * convenience and passes ObjectBase for the template parameter. */ + typedef ArrayOf Array; - //! specialization of Array::setValue() for ObjectBase subclasses - template<> - inline void Array::setValue(const std::string& name, const ObjectBase& val, bool warnExists) { setEntry(name,dynamic_cast(val.clone()),warnExists); } - //! specialization of Array::setValue() for char* strings - template<> - inline void Array::setValue(const std::string& name, const char* const& val, bool warnExists) { setEntry(name,new Primitive(val),warnExists); } - //! specialization of Array::setValue() for char* strings - template<> - inline void Array::setValue(const std::string& name, char* const& val, bool warnExists) { setEntry(name,new Primitive(val),warnExists); } - //! specialization of Array::addValue() for ObjectBase subclasses - template<> - inline void Array::addValue(const std::string& name, const ObjectBase& val, const std::string& comment) { addEntry(name,dynamic_cast(val.clone()),comment); } - //! specialization of Array::addValue() for char* strings - template<> - inline void Array::addValue(const std::string& name, const char* const& val, const std::string& comment) { addEntry(name,new Primitive(val),comment); } - //! specialization of Array::addValue() for char* strings - template<> - inline void Array::addValue(const std::string& name, char* const& val, const std::string& comment) { addEntry(name,new Primitive(val),comment); } + + template + void ArrayOf::setEntry(size_t index, PO& val, bool warnExists/*=false*/) { + if(index==size()) { + arr.push_back(&val); + fireEntryAdded(val); + } else { + if(arr[index]==&val) + return; + if(warnExists) { + std::cerr << "Warning: new entry "< + void ArrayOf::addEntry(size_t index, PO& val, const std::string& comment/*=""*/) { + if(index==size()) { + arr.push_back(&val); + } else { + ArrayBase::storage_t::iterator it=arr.begin(); + advance(it,index); + arr.insert(it,&val); + } + if(comment.size()>0) + setComment(index,comment); + fireEntryAdded(val); + } + template + void ArrayOf::setEntry(size_t index, PO* val, bool warnExists/*=false*/) { + if(index>size()) + throw bad_format(NULL,"Error: attempted to setEntry() past end of Array"); + else if(index==size()) { + arr.push_back(val); + fireEntryAdded(*val); + } else { + if(arr[index]==val) + return; + if(warnExists) { + std::cerr << "Warning: new entry "<::iterator it=myRef.find(arr[index]); + if(it!=myRef.end()) { + myRef.erase(*it); + delete arr[index]; + } + arr[index]=val; + takeObject(index,val); + fireEntriesChanged(); + } + } + template + void ArrayOf::addEntry(size_t index, PO* val, const std::string& comment/*=""*/) { + if(index>size()) + throw bad_format(NULL,"Error: attempted to setEntry() past end of Array"); + else if(index==size()) { + arr.push_back(val); + } else { + ArrayBase::storage_t::iterator it=arr.begin(); + advance(it,index); + arr.insert(it,val); + } + takeObject(index,val); + if(comment.size()>0) + setComment(index,comment); + fireEntryAdded(*val); + } + + //! implements the clone function for Array + PLIST_CLONE_IMPT2(PO,Alloc,ArrayOf,(new ArrayOf(*this))); + + /// @cond INTERNAL + template<> inline ObjectBase* ArrayOf::value_conversion>:: + allocatePO() { throw std::runtime_error("plist::Array cannot allocate new generic instances (ObjectBase)"); } + template<> inline PrimitiveBase* ArrayOf::value_conversion>:: + allocatePO() { throw std::runtime_error("plist::Array cannot allocate new generic instances (PrimitiveBase)"); } + template<> inline Collection* ArrayOf::value_conversion>:: + allocatePO() { throw std::runtime_error("plist::Array cannot allocate new generic instances (Collection)"); } + template<> inline void ArrayOf::value_conversion>:: + assignPO(ObjectBase& a, const ObjectBase& b) { a.set(b); } + /// @endcond + + template + bool ArrayOf::loadXMLNode(size_t index, xmlNode* val, const std::string& comment) { + if(indexloadXML(val); + if(comment.size()>0) + setComment(index,comment); + return true; + } catch(...) { + // apparently that didn't work, we'll need to make a new reference or clone + if(loadPolicy!=SYNC) // can we do that? + throw; // nope -- give up + // still here? let's try a fresh load using the polymorphic loader (fall through below) + } + } else if(!(savePolicy&ADDITIONS)) { + if(warnUnused && savePolicy==FIXED) + std::cerr << "Warning: plist::Array ran out of registered items (" << size() << ") during load. Ignoring extraneous items from source..." << std::endl; + return false; + } + ObjectBase * obj=plist::loadXML(val); + if(obj==NULL) + throw bad_format(val,"Array encountered an unknown value type"); + PO * cobj = dynamic_cast(obj); + if(cobj==NULL) + throw bad_format(val,"Array encountered a value of unexpected type"); + if(index + void ArrayOf::set(const ArrayBase& a) { + // if we're doing a large list, might be worth checking if we're actually the same type + if(const ArrayOf* ao = dynamic_cast(&a)) { + operator=(*ao); // same template type, use faster version! + return; + } + ArrayBase::operator=(a); + // otherwise we'll have to check the conversion on every single entry... + for(unsigned int index=0; indexset(*val); + if(comment.size()>0) + setComment(index,comment); + continue; + } catch(const bad_format& ex) { + // apparently that didn't work, we'll need to make a new reference or clone + if(loadPolicy!=SYNC) // can we do that? + throw; // nope -- give up + // still here? let's try a fresh load using the polymorphic loader (fall through below) + } + } else if(!(savePolicy&ADDITIONS)) { + if(warnUnused && savePolicy==FIXED) + std::cerr << "Warning: plist::Array ran out of registered items (" << size() << ") during load. Ignoring extraneous items from source..." << std::endl; + break; + } + PO* obj=dynamic_cast(val); + if(obj==NULL) { + obj = allocatePO(); + try { + obj->set(*val); + } catch(...) { + delete obj; + throw; + } + myRef.insert(obj); + } else if(a.ownsReference(val)) { + // currently only clones the other collection's references -- should we clone everything? + obj = dynamic_cast(obj->clone()); + myRef.insert(obj); + } + if(index + ArrayOf& ArrayOf::operator=(const ArrayOf& a) { + if(&a==this) + return *this; + ArrayBase::operator=(a); + for(unsigned int index=0; index(arr[index]),*val); + if(comment.size()>0) + setComment(index,comment); + continue; + } catch(const bad_format& ex) { + // apparently that didn't work, we'll need to make a new reference or clone + if(loadPolicy!=SYNC) // can we do that? + throw; // nope -- give up + // still here? let's try a fresh load using the polymorphic loader (fall through below) + } + } else if(!(savePolicy&ADDITIONS)) { + if(warnUnused && savePolicy==FIXED) + std::cerr << "Warning: plist::Array ran out of registered items (" << size() << ") during load. Ignoring extraneous items from source..." << std::endl; + break; + } + PO * obj = val; + // currently only clones the other collection's references -- should we clone everything? + if(a.ownsReference(val)) { + obj = dynamic_cast(obj->clone()); + myRef.insert(obj); + } + if(index> val; xmlFree(cont); - fireValueChanged(); + fireValueChanged(prevVal && val || !prevVal && !val); } else if(xNodeHasName(node,"string")) { xmlChar * cont=xmlNodeGetContent(node); try { @@ -40,6 +43,7 @@ xmlNodeSetContent(node,NULL); } void Primitive::set(const std::string& str) { + prevVal=val; if(matchTrue(str)) val=true; else if(matchFalse(str)) @@ -50,7 +54,7 @@ throw bad_format(NULL,"Error: plist boolean must be 'true', 'false', or numeric type"); val=t; } - fireValueChanged(); + fireValueChanged(prevVal && val || !prevVal && !val); } //! implements the clone function for Primitive PLIST_CLONE_IMP(Primitive,new Primitive(val)); @@ -64,17 +68,21 @@ if(xNodeHasName(node,"string")) { set((char*)cont); } else if(xNodeHasName(node,"integer")) { + prevVal=val; val=strtol((const char*)cont,NULL,0); - fireValueChanged(); + fireValueChanged(prevVal==val); } else if(xNodeHasName(node,"real")) { + prevVal=val; val=(char)strtod((const char*)cont,NULL); - fireValueChanged(); + fireValueChanged(prevVal==val); } else if(xNodeHasName(node,"true")) { + prevVal=val; val=true; - fireValueChanged(); + fireValueChanged(prevVal==val); } else if(xNodeHasName(node,"false")) { val=false; - fireValueChanged(); + prevVal=val; + fireValueChanged(prevVal==val); } else { throw bad_format(node,"Error: plist char must be either a string or integer"); } @@ -102,6 +110,7 @@ } } void Primitive::set(const std::string& str) { + prevVal=val; if(str.size()==0) throw bad_format(NULL,"Error: plist char must have non-empty content"); val=str[0]; @@ -117,11 +126,12 @@ } std::cerr << " (interpreted as boolean " << (bool)val << ")" << std::endl; } - fireValueChanged(); + fireValueChanged(prevVal==val); } //! implements the clone function for Primitive PLIST_CLONE_IMP(Primitive,new Primitive(val)); + void Primitive::loadXML(xmlNode* node) { if(node==NULL) return; @@ -130,17 +140,21 @@ if(xNodeHasName(node,"string")) { set((char*)cont); } else if(xNodeHasName(node,"integer")) { + prevVal=val; val=strtol((const char*)cont,NULL,0); - fireValueChanged(); + fireValueChanged(prevVal==val); } else if(xNodeHasName(node,"real")) { + prevVal=val; val=(char)strtod((const char*)cont,NULL); - fireValueChanged(); + fireValueChanged(prevVal==val); } else if(xNodeHasName(node,"true")) { + prevVal=val; val=true; - fireValueChanged(); + fireValueChanged(prevVal==val); } else if(xNodeHasName(node,"false")) { + prevVal=val; val=false; - fireValueChanged(); + fireValueChanged(prevVal==val); } else { throw bad_format(node,"Error: plist unsigned char must be either a string or integer"); } @@ -168,6 +182,7 @@ } } void Primitive::set(const std::string& str) { + prevVal=val; if(str.size()==0) throw bad_format(NULL,"Error: plist char must have non-empty content"); val=str[0]; @@ -183,83 +198,14 @@ } std::cerr << " (interpreted as boolean " << (bool)val << ")" << std::endl; } - fireValueChanged(); + fireValueChanged(prevVal==val); } //! implements the clone function for Primitive PLIST_CLONE_IMP(Primitive,new Primitive(val)); -//! a macro to provide template specializations for the numeric primitives, which only need to vary their string name -#define PLIST_OBJECT_SPECIALIZATION(T,PRIM) \ - void Primitive::loadXML(xmlNode* node) { \ - if(node==NULL) \ - return; \ - bool bt=xNodeHasName(node,"true"); \ - bool bf=xNodeHasName(node,"false"); \ - if(!bt && !bf && !xNodeHasName(node,"integer") && !xNodeHasName(node,"real") && !xNodeHasName(node,"string")) \ - throw bad_format(node,"Error: plist "#T" expects "PRIM" type"); \ - if(!xNodeHasName(node,PRIM)) \ - std::cerr << "Warning: plist expected "PRIM" got " << (const char*)xNodeGetName(node) << ", trying to convert. (line " << xmlGetLineNo(node) << ")" << std::endl; \ - if(bt) \ - val = true; \ - else if(bf) \ - val = false; \ - else { \ - xmlChar * cont=xmlNodeGetContent(node); \ - std::stringstream str((const char*)cont); \ - str >> val; \ - xmlFree(cont); \ - } \ - fireValueChanged(); \ - } \ - void Primitive::saveXML(xmlNode* node) const { \ - if(node==NULL) \ - return; \ - xmlNodeSetName(node,(const xmlChar*)PRIM); \ - std::stringstream str; \ - str <::set(const std::string& str) { \ - std::stringstream sstr(str); \ - sstr >> val; \ - while(sstr.good() && isspace(sstr.peek())) \ - sstr.get(); \ - if(sstr.fail()) { \ - if(matchTrue(str)) \ - val=true; \ - else if(matchFalse(str)) \ - val=false; \ - else { \ - std::string err="Expected "; err+=PRIM; err+=" value, got '"+str+"'"; \ - throw bad_format(NULL,err); \ - } \ - std::cerr << "Warning: expected " << PRIM << " value, interpreting '" << str << "' as boolean (value of " << val << ")" << std::endl; \ - } \ - if(sstr.good()) { \ - std::cerr << "Warning: expected " << PRIM << " value, truncating remainder '"; \ - char c=sstr.get(); \ - while(sstr) { std::cerr << c; c=sstr.get(); } \ - std::cerr << "'" << std::endl; \ - } \ - fireValueChanged(); \ - } \ - PLIST_CLONE_IMP(Primitive,new Primitive(val)); - - PLIST_OBJECT_SPECIALIZATION(short,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned short,"integer"); - PLIST_OBJECT_SPECIALIZATION(int,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned int,"integer"); - PLIST_OBJECT_SPECIALIZATION(long,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned long,"integer"); - PLIST_OBJECT_SPECIALIZATION(long long,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned long long,"integer"); - PLIST_OBJECT_SPECIALIZATION(float,"real"); - PLIST_OBJECT_SPECIALIZATION(double,"real"); - -#undef PLIST_OBJECT_SPECIALIZATION - void Primitive::loadXML(xmlNode* node) { + // operator= will call fireValueChanged, so no direct calls to fire here... if(node==NULL) return; if(xNodeHasName(node,"string")) { @@ -278,7 +224,6 @@ else throw bad_format(node,"Error: plist string must be 'true', 'false', or numeric type"); std::cerr << "Warning: plist string expected, found " << (const char*)xNodeGetName(node) << " on line " << xmlGetLineNo(node) << std::endl; - fireValueChanged(); } } void Primitive::saveXML(xmlNode* node) const { @@ -287,9 +232,45 @@ xmlNodeSetName(node,(const xmlChar*)"string"); xmlNodeSetContent(node,(const xmlChar*)c_str()); } + long Primitive::toLong() const { std::stringstream s(*this); long v; s >> v; return v; } + double Primitive::toDouble() const { std::stringstream s(*this); double v; s >> v; return v; } //! implements the clone function for Primitive PLIST_CLONE_IMP(Primitive,new Primitive(get())); + + std::string NamedEnumerationBase::getDescription(bool preferredOnly/*=true*/) { + if(preferredOnly) { + std::map valsToNames; + getPreferredNames(valsToNames); + if(valsToNames.size()==0) return ""; + std::string ans="Value is one of: { "; + std::map::const_iterator it=valsToNames.begin(); + ans+=it->second; + for(++it; it!=valsToNames.end(); ++it) { + ans+=" | "; + ans+=it->second; + } + if(!strictValue) + ans+=" | "; + ans+=" } "; + return ans; + } else { + std::map namesToVals; + getAllNames(namesToVals); + if(namesToVals.size()==0) return ""; + std::string ans="Value is one of: { "; + std::map::const_iterator it=namesToVals.begin(); + ans+=it->first; + for(++it; it!=namesToVals.end(); ++it) { + ans+=" | "; + ans+=it->first; + } + if(!strictValue) + ans+=" | "; + ans+=" } "; + return ans; + } + } } //namespace plist /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plistPrimitives.h ./Shared/plistPrimitives.h --- ../Tekkotsu_3.0/Shared/plistPrimitives.h 2006-09-27 16:11:38.000000000 -0400 +++ ./Shared/plistPrimitives.h 2007-11-20 13:11:48.000000000 -0500 @@ -3,10 +3,11 @@ #define INCLUDED_plistPrimitives_h_ #include "plistBase.h" +#include -//!@name libxml2 forward declarations -//!forward declaration of the libxml2 struct of the same name extern "C" { + //!@name libxml2 forward declarations + //!forward declaration of the libxml2 struct of the same name xmlNode* xmlAddPrevSibling(xmlNode* node, xmlNode* sibling); xmlNode* xmlNewText(const xmlChar* s); xmlNode* xmlNewComment(const xmlChar* s); @@ -22,10 +23,29 @@ void xmlNodeSetName(xmlNode* node, const xmlChar* name); void xmlFreeNode(xmlNode* node); void xmlUnlinkNode(xmlNode* node); + //@} } namespace plist { - + //! returns a string indicating the plist entry type to use for the specified type + /*! some primitives (bool, char) aren't handled because they require a specialization + * of Primitive and won't use this function. If you want to use a plist Primitive of + * some custom type, you might be able to just define a new specialization of + * this function and provide iostream <> operators for your type... */ + template const char* getTypeName(); + /// @cond INTERNAL + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "integer"; } + template<> inline const char* getTypeName() { return "real"; } + template<> inline const char* getTypeName() { return "real"; } + /// @endcond + //! Implements type-specific functionality through template specialization, mainly involving value conversion and stringification formatting /*! Provides smart-pointer style functionality for transparent * access to the value storage, as well as automatic casting @@ -34,55 +54,123 @@ template class Primitive : public PrimitiveBase { public: + template struct conversion_policy { typedef typename U::template ConversionTo value_conversion; }; + //! constructor - Primitive() : ObjectBase(), val() {} - //! constructor, provides automatic casting from the value type - Primitive(const T& v) : ObjectBase(), val(v) {} + Primitive() : PrimitiveBase(), val(), prevVal() {} + //! copy constructor, automatic conversion from value type + Primitive(const T& v) : PrimitiveBase(), val(v), prevVal() {} //! assignment from value type (template specializations add in-place modiciation (e.g. +=, *=)) - Primitive& operator=(const T& v) { val=v; fireValueChanged(); return *this; } + Primitive& operator=(const T& v) { if(&v==&prevVal) std::swap(val,prevVal); else { prevVal=val; val=v; } fireValueChanged(prevVal==val); return *this; } + virtual Primitive& operator=(const PrimitiveBase& pb) { if(dynamic_cast(&pb)!=this) operator=(pb.to()); return *this; } + //! assignment from primitive of the same type (just assign value) + Primitive& operator=(const Primitive& p) { operator=(p.val); return *this; } - Primitive& operator+=(const T& v) { val+=v; fireValueChanged(); return *this; } //!< add in-place - Primitive& operator-=(const T& v) { val-=v; fireValueChanged(); return *this; } //!< subtract in-place - Primitive& operator*=(const T& v) { val*=v; fireValueChanged(); return *this; } //!< multiply in-place - Primitive& operator/=(const T& v) { val/=v; fireValueChanged(); return *this; } //!< divide in-place + Primitive& operator+=(const T& v) { prevVal=val; val+=v; fireValueChanged(prevVal==val); return *this; } //!< add in-place + Primitive& operator-=(const T& v) { prevVal=val; val-=v; fireValueChanged(prevVal==val); return *this; } //!< subtract in-place + Primitive& operator*=(const T& v) { prevVal=val; val*=v; fireValueChanged(prevVal==val); return *this; } //!< multiply in-place + Primitive& operator/=(const T& v) { prevVal=val; val/=v; fireValueChanged(prevVal==val); return *this; } //!< divide in-place - //! smart pointer access to value + //! smart pointer, dereference to access primitive storage const T& operator*() const { return val; } - //! smart pointer access to value + //! smart pointer, dereference to access primitive storage const T* operator->() const { return &val; } - //! automatic casting to the value type + //! cast operator to automatically convert to value type operator T() const { return val; } - // **** Template specializations should provide their own implementations of loadXML and saveXML **** - /*void loadXML(xmlNode* node) { - if(node==NULL) - return; - //decode base64 from xml node - //val->loadBuffer(buf,bufsize); - fireValueChanged(); + //! interprets \a node as holding the specialization type + void loadXML(xmlNode* node); + //! saves #val into \a node + void saveXML(xmlNode* node) const; + void set(const std::string& str); + using PrimitiveBase::set; + std::string get() const { + std::stringstream sstr; + sstr <::digits10)<< val; + return sstr.str(); } - void saveXML(xmlNode* node) const { - if(node==NULL) - return; - unsigned int bufsize=val->getBinSize(); - char * buf = new char[bufsize]; - val->saveBuffer(buf,bufsize); - //base64 encode into xml node - delete [] buf; - }*/ + + virtual long toLong() const { return static_cast(val); } + virtual double toDouble() const { return static_cast(val); } //! clone definition for Primitive PLIST_CLONE_DEF(Primitive,new Primitive(val)); + + const T& getPreviousValue() const { return prevVal; } //!< returns the previously assigned value protected: - T val; //!< value storage + T val; //!< storage of primitive value + T prevVal; //!< following each assignment, this is the "old" value -- very handy for PrimitiveListeners }; + + template + void Primitive::loadXML(xmlNode* node) { + if(node==NULL) + return; + prevVal=val; + bool bt=xNodeHasName(node,"true"); + bool bf=xNodeHasName(node,"false"); + if(!bt && !bf && !xNodeHasName(node,"integer") && !xNodeHasName(node,"real") && !xNodeHasName(node,"string")) { + std::stringstream errstr; + errstr << "Error: plist::Primitive<" << typeid(T).name() << "> expects " << getTypeName() << ", got unknown type " << (const char*)xNodeGetName(node); + throw bad_format(node,errstr.str()); + } + if(!xNodeHasName(node,getTypeName())) + std::cerr << "Warning: plist expected " << getTypeName() << " got " << (const char*)xNodeGetName(node) << ", trying to convert. (line " << xmlGetLineNo(node) << ")" << std::endl; + if(bt) + val = true; + else if(bf) + val = false; + else { + xmlChar * cont=xmlNodeGetContent(node); + std::stringstream str((const char*)cont); + str >> val; + xmlFree(cont); + } + fireValueChanged(prevVal==val); + } + template + void Primitive::saveXML(xmlNode* node) const { + if(node==NULL) + return; + xmlNodeSetName(node,(const xmlChar*)getTypeName()); + std::stringstream str; + str <::digits10)<< val; + xmlNodeSetContent(node,(const xmlChar*)str.str().c_str()); + } + template + void Primitive::set(const std::string& str) { + prevVal=val; + std::stringstream sstr(str); + sstr >> val; + while(sstr.good() && isspace(sstr.peek())) + sstr.get(); + if(sstr.fail()) { + if(matchTrue(str)) + val=true; + else if(matchFalse(str)) + val=false; + else { + std::string err="Expected "; err+=getTypeName(); err+=" value, got '"+str+"'"; + throw bad_format(NULL,err); + } + std::cerr << "Warning: expected " << getTypeName() << " value, interpreting '" << str << "' as boolean (value of " << val << ")" << std::endl; + } + if(sstr.good()) { + std::cerr << "Warning: expected " << getTypeName() << " value, truncating remainder '"; + char c=sstr.get(); + while(sstr) { std::cerr << c; c=sstr.get(); } + std::cerr << "'" << std::endl; + } + fireValueChanged(prevVal==val); + } + //! implements the clone function for Primitive - PLIST_CLONE_IMPT(class T,Primitive,new Primitive(val)); + PLIST_CLONE_IMPT(T,Primitive,new Primitive(val)); -/*! @cond SHOW_PLIST_OBJECT_SPECIALIZATION */ +/// @cond SHOW_PLIST_OBJECT_SPECIALIZATION //! provides a @c bool specialization of Primitive /*! A @c bool can be treated as either a string or an integer\n @@ -92,29 +180,39 @@ template<> class Primitive : public PrimitiveBase { public: - Primitive() : PrimitiveBase(), val() {} //!< constructor - Primitive(const bool& v) : PrimitiveBase(), val(v) {} //!< casting constructor - Primitive& operator=(const bool& v) { val=v; fireValueChanged(); return *this; } //!< assignment constructor + template struct conversion_policy { typedef typename U::template ConversionTo value_conversion; }; + Primitive() : PrimitiveBase(), val(), prevVal() {} //!< constructor + Primitive(const bool& v) : PrimitiveBase(), val(v), prevVal() {} //!< casting constructor + Primitive& operator=(const bool& v) { if(&v==&prevVal) std::swap(val,prevVal); else { prevVal=val; val=v; } fireValueChanged(prevVal==val); return *this; } //!< assignment constructor + virtual Primitive& operator=(const PrimitiveBase& pb) { if(dynamic_cast(&pb)!=this) operator=(pb.to()); return *this; } + Primitive& operator=(const Primitive& p) { operator=(p.val); return *this; } //bool& operator*() { return val; } const bool& operator*() const { return val; } //!< dereference will return data storage //bool* operator->() { return &val; } const bool* operator->() const { return &val; } //!< can use -> to access members of data storage operator bool() const { return val; } //!< casting operator - + void loadXML(xmlNode* node); //!< interprets @a node as a bool void saveXML(xmlNode* node) const; //!< saves #val into @a node void set(const std::string& str); + using PrimitiveBase::set; std::string get() const { return val?"true":"false"; } + virtual long toLong() const { return static_cast(val); } + virtual double toDouble() const { return static_cast(val); } + //! clone definition for Primitive PLIST_CLONE_DEF(Primitive,new Primitive(val)); + const bool& getPreviousValue() const { return prevVal; } //!< returns the previously assigned value + protected: bool val; //!< the actual data storage + bool prevVal; //!< following each assignment, this is the "old" value -- very handy for PrimitiveListeners }; -/*! @endcond */ +/// @endcond //! provides a @c char specialization of plist::Primitive, adds a unique #numeric property to the usual template implementation /*! A @c char can be treated as either a string or an integer, you can use @@ -122,13 +220,17 @@ template<> class Primitive : public PrimitiveBase { public: - Primitive() : PrimitiveBase(), val(), numeric(false) {} //!< constructor - Primitive(const char& v, bool isNum=false) : PrimitiveBase(), val(v), numeric(isNum) {} //!< casting constructor - Primitive& operator=(const char& v) { val=v; fireValueChanged(); return *this; } //!< assignment - Primitive& operator+=(const char& v) { val+=v; fireValueChanged(); return *this; } //!< add-assign - Primitive& operator-=(const char& v) { val-=v; fireValueChanged(); return *this; } //!< subtract-assign - Primitive& operator*=(const char& v) { val*=v; fireValueChanged(); return *this; } //!< multiply-assign - Primitive& operator/=(const char& v) { val/=v; fireValueChanged(); return *this; } //!< divide-assign + template struct conversion_policy { typedef typename U::template ConversionTo value_conversion; }; + Primitive() : PrimitiveBase(), val(), prevVal(), numeric(false) {} //!< constructor + Primitive(const char& v, bool isNum=false) : PrimitiveBase(), val(v), prevVal(), numeric(isNum) {} //!< casting constructor + Primitive& operator=(char v) { if(&v==&prevVal) std::swap(val,prevVal); else { prevVal=val; val=v; } fireValueChanged(prevVal==val); return *this; } //!< assignment + virtual Primitive& operator=(const PrimitiveBase& pb) { if(dynamic_cast(&pb)!=this) operator=(pb.to()); return *this; } + //! assignment from primitive of the same type (just assign value) + Primitive& operator=(const Primitive& p) { operator=(p.val); return *this; } + Primitive& operator+=(char v) { prevVal=val; val+=v; fireValueChanged(prevVal==val); return *this; } //!< add-assign + Primitive& operator-=(char v) { prevVal=val; val-=v; fireValueChanged(prevVal==val); return *this; } //!< subtract-assign + Primitive& operator*=(char v) { prevVal=val; val*=v; fireValueChanged(prevVal==val); return *this; } //!< multiply-assign + Primitive& operator/=(char v) { prevVal=val; val/=v; fireValueChanged(prevVal==val); return *this; } //!< divide-assign //char& operator*() { return val; } const char& operator*() const { return val; } //!< dereference will return data storage //char* operator->() { return &val; } @@ -141,6 +243,7 @@ void loadXML(xmlNode* node); //!< interprets @a node as a char void saveXML(xmlNode* node) const; //! saves #val into @a node void set(const std::string& str); + using PrimitiveBase::set; std::string get() const { if(numeric) { std::stringstream sstr; @@ -149,11 +252,17 @@ } else return std::string(1,val); } + virtual long toLong() const { return static_cast(val); } + virtual double toDouble() const { return static_cast(val); } + //! clone definition for Primitive PLIST_CLONE_DEF(Primitive,new Primitive(val)); + const char& getPreviousValue() const { return prevVal; } //!< returns the previously assigned value + protected: char val; //!< data storage + char prevVal; //!< following each assignment, this is the "old" value -- very handy for PrimitiveListeners bool numeric; //!< if true, requests that saves store the numeric value instead of corresponding character }; @@ -163,13 +272,17 @@ template<> class Primitive : public PrimitiveBase { public: - Primitive() : PrimitiveBase(), val(), numeric(false) {} //!< constructor - Primitive(const unsigned char& v, bool isNum=false) : PrimitiveBase(), val(v), numeric(isNum) {} //!< casting constructor - Primitive& operator=(const unsigned char& v) { val=v; fireValueChanged(); return *this; } //!< assignment - Primitive& operator+=(const unsigned char& v) { val+=v; fireValueChanged(); return *this; } //!< add-assign - Primitive& operator-=(const unsigned char& v) { val-=v; fireValueChanged(); return *this; } //!< subtract-assign - Primitive& operator*=(const unsigned char& v) { val*=v; fireValueChanged(); return *this; } //!< multiple-assign - Primitive& operator/=(const unsigned char& v) { val/=v; fireValueChanged(); return *this; } //!< divide-assign + template struct conversion_policy { typedef typename U::template ConversionTo value_conversion; }; + Primitive() : PrimitiveBase(), val(), prevVal(), numeric(false) {} //!< constructor + Primitive(const unsigned char& v, bool isNum=false) : PrimitiveBase(), val(v), prevVal(), numeric(isNum) {} //!< casting constructor + Primitive& operator=(unsigned char v) { prevVal=val; val=v; fireValueChanged(prevVal==val); return *this; } //!< assignment + virtual Primitive& operator=(const PrimitiveBase& pb) { if(dynamic_cast(&pb)!=this) operator=(pb.to()); return *this; } + //! assignment from primitive of the same type (just assign value) + Primitive& operator=(const Primitive& p) { operator=(p.val); return *this; } + Primitive& operator+=(unsigned char v) { prevVal=val; val+=v; fireValueChanged(prevVal==val); return *this; } //!< add-assign + Primitive& operator-=(unsigned char v) { prevVal=val; val-=v; fireValueChanged(prevVal==val); return *this; } //!< subtract-assign + Primitive& operator*=(unsigned char v) { prevVal=val; val*=v; fireValueChanged(prevVal==val); return *this; } //!< multiple-assign + Primitive& operator/=(unsigned char v) { prevVal=val; val/=v; fireValueChanged(prevVal==val); return *this; } //!< divide-assign //unsigned char& operator*() { return val; } const unsigned char& operator*() const { return val; } //!< dereference will return data storage //unsigned char* operator->() { return &val; } @@ -182,6 +295,7 @@ void loadXML(xmlNode* node); //!< interprets @a node as a unsigned char void saveXML(xmlNode* node) const; //! saves #val into @a node void set(const std::string& str); + using PrimitiveBase::set; std::string get() const { if(numeric) { std::stringstream sstr; @@ -190,81 +304,39 @@ } else return std::string(1,val); } + virtual long toLong() const { return static_cast(val); } + virtual double toDouble() const { return static_cast(val); } + //! clone definition for Primitive PLIST_CLONE_DEF(Primitive,new Primitive(val)); + const unsigned char& getPreviousValue() const { return prevVal; } //!< returns the previously assigned value + protected: unsigned char val; //!< data storage + unsigned char prevVal; //!< following each assignment, this is the "old" value -- very handy for PrimitiveListeners bool numeric; //!< if true, requests that saves store the numeric value instead of corresponding character }; -/*! @cond SHOW_PLIST_OBJECT_SPECIALIZATION */ - -//! a macro to provide template specializations for the numeric primitives, which only need to vary their string name -#define PLIST_OBJECT_SPECIALIZATION(T,PRIM) \ - template<> \ - class Primitive : public PrimitiveBase { \ - public: \ - /*! \brief constructor */ \ - Primitive() : PrimitiveBase(), val() {} \ - /*! \brief copy constructor, automatic conversion from value type */ \ - Primitive(const T& v) : PrimitiveBase(), val(v) {} \ - /*! \brief assignment from value type */ \ - Primitive& operator=(const T& v) { val=v; fireValueChanged(); return *this; } \ - Primitive& operator+=(const T& v) { val+=v; fireValueChanged(); return *this; } /*!< \brief in-place modification supported */ \ - Primitive& operator-=(const T& v) { val-=v; fireValueChanged(); return *this; } /*!< \brief in-place modification supported */ \ - Primitive& operator*=(const T& v) { val*=v; fireValueChanged(); return *this; } /*!< \brief in-place modification supported */ \ - Primitive& operator/=(const T& v) { val/=v; fireValueChanged(); return *this; } /*!< \brief in-place modification supported */ \ - /*! \brief dereference to access primitive storage */ \ - const T& operator*() const { return val; } \ - /*! \brief dereference to access primitive storage */ \ - const T* operator->() const { return &val; } \ - /*! \brief cast operator to automatically convert to value type */ \ - operator T() const { return val; } \ - /*! \brief interprets \a node as holding the specialization type */ \ - void loadXML(xmlNode* node); \ - /*! \brief saves #val into \a node */ \ - void saveXML(xmlNode* node) const; \ - void set(const std::string& str); \ - std::string get() const { \ - std::stringstream sstr; \ - sstr <,new Primitive(val)); \ - protected: \ - /*! \brief storage of primitve value */ \ - T val; \ - } - PLIST_OBJECT_SPECIALIZATION(short,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned short,"integer"); - PLIST_OBJECT_SPECIALIZATION(int,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned int,"integer"); - PLIST_OBJECT_SPECIALIZATION(long,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned long,"integer"); - PLIST_OBJECT_SPECIALIZATION(long long,"integer"); - PLIST_OBJECT_SPECIALIZATION(unsigned long long,"integer"); - PLIST_OBJECT_SPECIALIZATION(float,"real"); - PLIST_OBJECT_SPECIALIZATION(double,"real"); - -#undef PLIST_OBJECT_SPECIALIZATION -/*! @endcond */ - //! Provides a @c std::string specialization of Primitive /*! Doesn't need to provide a operator cast because we subclass std::string itself! */ template<> class Primitive : public PrimitiveBase, public std::string { public: - Primitive() : PrimitiveBase(), std::string() {} //!< constructor - Primitive(const std::string& v) : PrimitiveBase(), std::string(v) {} //!< casting constructor - Primitive(const std::string& v, size_type off, size_type count=npos) : PrimitiveBase(), std::string(v,off,count) {} //!< casting constructor - Primitive(const char* v, size_type count) : PrimitiveBase(), std::string(v,count) {} //!< casting constructor - Primitive(const char* v) : PrimitiveBase(), std::string(v) {} //!< casting constructor - Primitive(size_type count, char v) : PrimitiveBase(), std::string(count,v) {} //!< casting constructor - Primitive& operator=(const std::string& v) { std::string::operator=(v); fireValueChanged(); return *this; } //!< assignment - Primitive& operator=(const char* v) { std::string::operator=(v); fireValueChanged(); return *this; } //!< assignment - Primitive& operator=(char v) { std::string::operator=(v); fireValueChanged(); return *this; } //!< assignment + template struct conversion_policy { typedef typename U::template ConversionTo value_conversion; }; + Primitive() : PrimitiveBase(), std::string(), prevVal() {} //!< constructor + Primitive(const std::string& v) : PrimitiveBase(), std::string(v), prevVal() {} //!< casting constructor + Primitive(const std::string& v, size_type off, size_type count=npos) : PrimitiveBase(), std::string(v,off,count), prevVal() {} //!< casting constructor + Primitive(const char* v, size_type count) : PrimitiveBase(), std::string(v,count), prevVal() {} //!< casting constructor + Primitive(const char* v) : PrimitiveBase(), std::string(v), prevVal() {} //!< casting constructor + Primitive(size_type count, char v) : PrimitiveBase(), std::string(count,v), prevVal() {} //!< casting constructor + Primitive& operator=(const std::string& v) { if(&v==&prevVal) std::string::swap(prevVal); else { prevVal=*this; std::string::operator=(v); } fireValueChanged(prevVal==*this); return *this; } //!< assignment + Primitive& operator=(const char* v) { prevVal=*this; std::string::operator=(v); fireValueChanged(prevVal==*this); return *this; } //!< assignment + Primitive& operator=(char v) { prevVal=*this; std::string::operator=(v); fireValueChanged(prevVal==*this); return *this; } //!< assignment + virtual Primitive& operator=(const PrimitiveBase& pb) { if(dynamic_cast(&pb)!=this) operator=(pb.toString()); return *this; } + //! assignment from primitive of the same type (just assign value) + Primitive& operator=(const Primitive& p) { operator=(static_cast(p)); return *this; } //std::string& operator*() { return *this; } const std::string& operator*() const { return *this; } //!< dereference will return data storage as a string (for uniformity with the other Primitives, although unnecessary with this instantiation) //std::string* operator->() { return this; } @@ -274,53 +346,134 @@ void loadXML(xmlNode* node); //!< interprets @a node as a string void saveXML(xmlNode* node) const; //!< saves the content of the string into @a node void set(const std::string& str) { operator=(str); } // operator= will fireValueChanged + using PrimitiveBase::set; std::string get() const { return *this; } + virtual long toLong() const; + virtual double toDouble() const; + //! clone definition for Primitive PLIST_CLONE_DEF(Primitive,new Primitive(get())); + + const std::string& getPreviousValue() const { return prevVal; } //!< returns the previously assigned value + + protected: + std::string prevVal; //!< stores the previously assigned value for reference/reset by a value listener + }; + + //! provides some accessors common across NamedEnumeration types + class NamedEnumerationBase : public PrimitiveBase { + public: + NamedEnumerationBase() : PrimitiveBase(), strictValue(true) {} //!< constructor + NamedEnumerationBase(const NamedEnumerationBase& ne) : PrimitiveBase(ne), strictValue(ne.strictValue) {} //!< copy constructor + NamedEnumerationBase& operator=(const std::string& v) { set(v); return *this; } //!< assignment from string + NamedEnumerationBase& operator=(const NamedEnumerationBase& ne) { PrimitiveBase::operator=(ne); return *this; } //!< assignment (doesn't copy #strictValue) + virtual NamedEnumerationBase& operator=(const PrimitiveBase& pb)=0; + + //! fills @a names with the names and values for the enum -- needed for generic access to the names (e.g. UI generation) + virtual void getPreferredNames(std::map& names) const=0; + //! fills @a names with the names and values for the enum -- needed for generic access to the names (e.g. UI generation) + virtual void getAllNames(std::map& names) const=0; + + std::string getDescription(bool preferredOnly=true); //!< returns a string listing the available symbolic names + void setStrict(bool strict) { strictValue=strict; } //!< sets #strictValue (whether or not to allow assignment from numeric values which don't have a symbolic name) + bool getStrict() const { return strictValue; } //!< returns #strictValue (whether or not to allow assignment from numeric values which don't have a symbolic name) + + protected: + bool strictValue; //!< if true, don't allow conversion from numeric string which doesn't correspond to a named value }; //! Provides an interface for the use of enumerations in a plist -- you can specify values by either the string name or the corresponding integer value - /*! Where an array of names is required, you must order the array such that - * the enumeration value can be used as an index into the array. - * The 'maxval' parameters should be one above the maximum enumeration -- - * if your enumeration runs sequentially from 0 to n, #max should be the - * number of enumerations: n+1 */ + /*! Where an array of names is specified, you must order the array such that + * the enumeration value can be used as an index into the array. The array must be + * terminated with an empty element ("") so NamedEnumeration can tell how many + * elements there are. + * + * Binary size and symbol definition: this class contains two static STL maps + * for storing the string names of the enumeration values. The problem is that + * due to the way static members of templates are handled, you will wind up + * with extensive symbol declarations in each translation unit which references + * this header, which can lead to significant binary bloat (particularly with + * debugging symbols). The solution is to limit the instantiation of these statics. + * + * - Easy way out: define USE_GLOBAL_PLIST_STATICS, which will then declare the statics + * here in the header, and allow the duplication to occur (which is fine for small + * projects or if you don't reference this header widely) + * + * - Otherwise, you can then declare: + * @code + * template std::map plist::NamedEnumeration::namesToVals; + * template std::map plist::NamedEnumeration::valsToNames; + * @endcode + * in the translation units where you introduce new types to the template parameter. + * This will greatly limit symbol replication, although there will still be some minor + * duplication if more than just the "new" types are found in the current unit. + * You may prefer to call the macro INSTANTIATE_ALL_NAMEDENUMERATION_STATICS() to ensure + * future compatability in the unlikely event more statics are added in the future. + * + * - For the ultimate minimal binary size, explicitly declare a template + * specialization for each type you use: (note 'YOUR_T' is meant to be replaced!) + * @code + * // replace YOUR_T with the type you are using: + * template<> std::map plist::NamedEnumeration::namesToVals = std::map(); + * template<> std::map plist::NamedEnumeration::valsToNames = std::map(); + * @endcode + * You can do this only once, in a single translation unit, yielding zero replication of symbols. + * For convenience, we provide a macro INSTANTIATE_NAMEDENUMERATION_STATICS(T) which will do this for you. */ template - class NamedEnumeration : public PrimitiveBase { + class NamedEnumeration : public NamedEnumerationBase { public: - NamedEnumeration() : PrimitiveBase(), val(), names(NULL), max(0) {} //!< constructor - NamedEnumeration(const NamedEnumeration& ne) : PrimitiveBase(ne), val(ne.val), names(ne.names), max(ne.max) {} //!< copy constructor - NamedEnumeration(const T& v, const char * const* enumnames, unsigned int maxval) : PrimitiveBase(), val(v), names(enumnames), max(maxval) {} //!< constructor, pass initial value, array of strings (the names), and the one-plus-maximum enum value (i.e. the number of enumeration values if they run sequentially from 0) - NamedEnumeration(const T& v) : PrimitiveBase(), val(v), names(NULL), max(0) {} //!< automatic casting from the enumeration - NamedEnumeration& operator=(const T& v) { val=v; fireValueChanged(); return *this; } //!< assignment from enumeration value (numeric) + template struct conversion_policy { typedef typename U::template ConversionTo value_conversion; }; + NamedEnumeration() : NamedEnumerationBase(), val(), prevVal() {} //!< constructor + NamedEnumeration(const NamedEnumeration& ne) : NamedEnumerationBase(ne), val(ne.val), prevVal() {} //!< copy constructor + NamedEnumeration(const T& v, const char * const* enumnames) : NamedEnumerationBase(), val(v), prevVal() { setNames(enumnames); } //!< constructor, pass initial value, array of strings (the names); assumes enumeration is sequential starting at 0, and runs until the names entry is an empty string (i.e. @a names must be terminated with "") + NamedEnumeration(const T& v) : NamedEnumerationBase(), val(v), prevVal() {} //!< automatic casting from the enumeration + NamedEnumeration& operator=(const T& v) { if(&v==&prevVal) std::swap(val,prevVal); else { prevVal=val; val=v; } fireValueChanged(prevVal==val); return *this; } //!< assignment from enumeration value (numeric) NamedEnumeration& operator=(const std::string& v) { set(v); return *this; } //!< assignment from string - NamedEnumeration& operator=(const NamedEnumeration& ne) { val=ne.val; names=ne.names; max=ne.max; return PrimitiveBase::operator=(ne); } //!< assignment + NamedEnumeration& operator=(const NamedEnumeration& ne) { operator=(ne.val); return *this; } //!< assignment //T& operator*() { return val; } const T& operator*() const { return val; } //!< value access operator T() const { return val; } //!< automatic casting to the enumeration value - void setNames(const char * const* enumnames, unsigned int maxval) { names=enumnames; max=maxval; } //!< (re)set the array of names and one-plus-maximum enum value (i.e. the number of enumeration values if they run sequentially from 0) - const char* const* getNames() const { return names; } //!< returns the array of names previously provided from constructor or setNames() - const char* getName(unsigned int i) const { return names[i]; } //!< returns the name for a particular index - unsigned int getMax() const { return max; } //!< returns the one-past-maximum of enumeration values previously provided to constructor or setNames() + static void setNames(const char * const* enumnames); //!< calls clearNames() and then resets the array of names, @a enumnames must be terminated with an empty string (""), and the enumeration must be sequential starting at 0; these names become the "preferred" name for each value + static const std::map& getPreferredNames() { return valsToNames; } //!< returns mapping from numeric value to "preferred" name (one-to-one) + static const std::map& getAllNames() { return namesToVals; } //!< returns mapping from names to values (many-to-one allowed) + static void clearNames(); //!< removes all names, thus causing only numeric values to be accepted + static void addNameForVal(const std::string& enumname, const T& val); //!< adds an alternative name mapping to the specified numeric value; if the value doesn't already have a name, this is also the "preferred" name + static void setPreferredNameForVal(const std::string& enumname, const T& val); //!< replaces any previous "preferred" name for a specific value + //! polymorphic assignment, throws bad_format if #strictValue is requested and the value is invalid integer + virtual NamedEnumeration& operator=(const PrimitiveBase& pb) { + if(dynamic_cast(&pb)==this) + return *this; + if(const std::string* str = dynamic_cast(&pb)) + set(*str); + else { + T tv=static_cast(pb.toLong()); + if(strictValue && valsToNames.find(tv)==valsToNames.end()) + throw bad_format(NULL, "NamedEnumeration unable to assign arbitrary integer value because strict checking is requested"); + val=tv; + } + return *this; + } + //! interprets @a node as either a string holding the name, or a number corresponding to its index (name is preferred) void loadXML(xmlNode* node) { if(node==NULL) return; if(xNodeHasName(node,"true") || xNodeHasName(node,"false")) { std::string name=(const char*)xNodeGetName(node); - unsigned int i=findName(name.c_str()); - if(i==-1U) - throw bad_format(node,("Error: plist NamedEnumeration cannot be '"+name+"'").c_str()); - val=static_cast(i); std::cerr << "Warning: plist NamedEnumeration should use " << name << ", not <" << name << "/>" << std::endl; + try { + set(name); + } catch(const bad_format& err) { + throw bad_format(node,err.what()); //add current node to exception and rethrow + } } else if(xNodeHasName(node,"integer") || xNodeHasName(node,"real") || xNodeHasName(node,"string")) { xmlChar * cont=xmlNodeGetContent(node); try { - set((char*)cont); + set((const char*)cont); } catch(const bad_format& err) { xmlFree(cont); - throw bad_format(node,err.what()); + throw bad_format(node,err.what()); //add current node to exception and rethrow } catch(...) { xmlFree(cont); throw; @@ -333,54 +486,134 @@ void saveXML(xmlNode* node) const { if(node==NULL) return; - if(names!=NULL && names[val]!=NULL && val>0 && (unsigned int)val(i); - fireValueChanged(); + prevVal=val; + if(!getValForName(str,val)) + throw bad_format(NULL,"Error: plist::NamedEnumeration must be numeric or valid string (cannot be '"+str+"')"); + fireValueChanged(prevVal==val); } + using PrimitiveBase::set; std::string get() const { - if(names!=NULL && names[val]!=NULL && val>=0 && (unsigned int)val(val); } + virtual double toDouble() const { return static_cast(val); } + //! implements the clone function for NamedEnumeration PLIST_CLONE_DEF(NamedEnumeration,new NamedEnumeration(*this)); + const T& getPreviousValue() const { return prevVal; } //!< returns the previously assigned value + protected: - //! returns the enum corresponding to @a name - unsigned int findName(const char* name) { - if(name==NULL || names==NULL) - return -1U; - //prefer case sensitive match - for(unsigned int i=0; i& names) const; + //! provides the generic access to values and names from NamedEnumerationBase; protected because if you know the full type, better to use the static version of the function + virtual void getAllNames(std::map& names) const; + + //! sets @a v to the enumeration value named @a name; returns false if no such name is found + bool getValForName(std::string name, T& v) const { + std::transform(name.begin(), name.end(), name.begin(), (int(*)(int)) std::toupper); + typename std::map::const_iterator vit=namesToVals.find(name); + if(vit!=namesToVals.end()) + v=vit->second; + else { + int iv; + if(sscanf(name.c_str(),"%d",&iv)==0) + return false; + T tv=static_cast(iv); + if(strictValue && valsToNames.find(tv)==valsToNames.end()) + return false; + v=tv; + } + return true; + } + //! retrieves the "preferred" name for the enumeration value @a v; returns false if no name is registered + bool getNameForVal(const T& v, std::string& name) const { + typename std::map::const_iterator nit=valsToNames.find(v); + if(nit!=valsToNames.end()) { + name=nit->second; + return true; + } + std::stringstream str; + str << v; + name=str.str(); + return false; } T val; //!< storage of enum value - const char * const* names; //!< pointer to array of names -- enum value must be able to serve as index for lookup - unsigned int max; //!< one-plus-maximum enum value, i.e. the number of enum entries if they are ordered sequentially from 0 + T prevVal; //!< storage of enum value + + //! look up table of string names to enum values (can have multiple string names mapping to same enum -- deprecated values for example) + /*! See class notes regarding instantiation options for static values like this */ + static std::map namesToVals; + //! look up table of enum values to preferred display name (by default, first name given) + /*! See class notes regarding instantiation options for static values like this */ + static std::map valsToNames; }; //! implements the clone function for NamedEnumeration - PLIST_CLONE_IMPT(class T,NamedEnumeration,new NamedEnumeration(*this)); + PLIST_CLONE_IMPT(T,NamedEnumeration,new NamedEnumeration(*this)); +#ifdef USE_GLOBAL_PLIST_STATICS + template std::map plist::NamedEnumeration::namesToVals; + template std::map plist::NamedEnumeration::valsToNames; +#endif + + //! Unless you enable GLOBAL_PLIST_STATICS, call this macro in each translation unit which introduces new template types + /*! @see NamedEnumeration for further discussion */ +#define INSTANTIATE_ALL_NAMEDENUMERATION_STATICS() \ + template std::map plist::NamedEnumeration::namesToVals; \ + template std::map plist::NamedEnumeration::valsToNames; + + //! Unless you enable GLOBAL_PLIST_STATICS, call this macro in one of your source files to provide a definition of the statics for a specific type + /*! @see NamedEnumeration for further discussion */ +#define INSTANTIATE_NAMEDENUMERATION_STATICS(T) \ + template<> std::map plist::NamedEnumeration::namesToVals = std::map(); \ + template<> std::map plist::NamedEnumeration::valsToNames = std::map(); + + template void NamedEnumeration::setNames(const char * const* enumnames) { + clearNames(); + for(unsigned int i=0; *enumnames[i]!='\0'; ++i) { + std::string name=enumnames[i]; + valsToNames[static_cast(i)]=name; + std::transform(name.begin(), name.end(), name.begin(), (int(*)(int)) std::toupper); + namesToVals[name]=static_cast(i); + } + } + template void NamedEnumeration::clearNames() { + namesToVals.clear(); + valsToNames.clear(); + } + template void NamedEnumeration::addNameForVal(const std::string& enumname, const T& val) { + if(valsToNames.find(val)==valsToNames.end()) + valsToNames[val]=enumname; + std::string name=enumname; + std::transform(name.begin(), name.end(), name.begin(), (int(*)(int)) std::toupper); + namesToVals[name]=val; + } + template void NamedEnumeration::setPreferredNameForVal(const std::string& enumname, const T& val) { + valsToNames[val]=enumname; + } + + template void NamedEnumeration::getPreferredNames(std::map& names) const { + names.clear(); + for(typename std::map::const_iterator it=valsToNames.begin(); it!=valsToNames.end(); ++it) + names.insert(std::pair(it->first,it->second)); + } + template void NamedEnumeration::getAllNames(std::map& names) const { + names.clear(); + for(typename std::map::const_iterator it=namesToVals.begin(); it!=namesToVals.end(); ++it) + names.insert(std::pair(it->first,it->second)); + } + } //namespace plist diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/string_util.cc ./Shared/string_util.cc --- ../Tekkotsu_3.0/Shared/string_util.cc 2006-03-16 17:07:28.000000000 -0500 +++ ./Shared/string_util.cc 2007-11-09 14:01:14.000000000 -0500 @@ -1,25 +1,34 @@ #include "string_util.h" -#include +#include +#include #include #include +#include using namespace std; namespace string_util { - string makeLower(const string& s) { - string ans(s.size(),'#'); - unsigned int i=s.size(); - while(i--!=0) - ans[i]=::tolower(s[i]); - return ans; + //! reference to the current standard library 'locale' + static const std::locale& curLocale=std::locale::classic(); + + char localeToUpper(char c) { + return std::toupper(c,curLocale); } + char localeToLower(char c) { + return std::tolower(c,curLocale); + } + string makeUpper(const string& s) { - string ans(s.size(),'#'); - unsigned int i=s.size(); - while(i--!=0) - ans[i]=::toupper(s[i]); + string ans(s); // yes, I actually checked if it's faster to copy and then overwrite or reserve and use std::back_inserter(ans) + std::transform(ans.begin(), ans.end(), ans.begin(), (int(*)(int)) std::toupper); + return ans; + } + + string makeLower(const string& s) { + string ans(s); + std::transform(ans.begin(), ans.end(), ans.begin(), (int(*)(int)) std::tolower); return ans; } @@ -124,6 +133,35 @@ return !isDoubleQuote && !isSingleQuote; } + bool reMatch(const std::string& str, const std::string& regex) { + return reMatch(str,regex,REG_EXTENDED); + } + + bool reMatch(const std::string& str, const std::string& regex, int flags) { + regex_t re; + if(int err=regcomp(&re,regex.c_str(),flags | REG_NOSUB)) { + char msg[128]; + regerror(err,&re,msg,128); + string errmsg; + errmsg.append("Bad filter '").append(regex).append("': ").append(msg); + regfree(&re); + throw errmsg; + } + int match=regexec(&re,str.c_str(),0,NULL,0); + regfree(&re); + if(match==0) { + return true; + } else if(match==REG_NOMATCH) { + return false; + } else { + char msg[128]; + regerror(match,&re,msg,128); + string errmsg; + errmsg.append("Regex error on reMatch('").append(str).append("', '").append(regex).append("'): ").append(msg); + throw errmsg; + } + } + } /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/string_util.h ./Shared/string_util.h --- ../Tekkotsu_3.0/Shared/string_util.h 2006-03-16 17:24:30.000000000 -0500 +++ ./Shared/string_util.h 2007-11-09 14:01:14.000000000 -0500 @@ -8,6 +8,12 @@ //! some common string processing functions, for std::string namespace string_util { + //! uses the standard library's "locale" to convert case of a single character + char localeToUpper(char c); + + //! uses the standard library's "locale" to convert case of a single character + char localeToLower(char c); + //! returns lower case version of @a s std::string makeLower(const std::string& s) ATTR_must_check; @@ -25,6 +31,24 @@ //! replaces ~USER prefix with specified user's home directory, or ~ prefix with current HOME environment setting; returns str if no valid expansion is found std::string tildeExpansion(const std::string& str) ATTR_must_check; + + //! returns true if @a str matches @a re (assumes 'extended' regular expression, not 'basic'), false otherwise and throws std::string message on error + /*! @param str The string to match + * @param regex The (extended) regular expression which should be parsed and executed + * + * This compiles the @a regex and then executes it... for repeated usage of the same + * regular expression, you could be better off compiling it yourself and using the regex library directly. */ + bool reMatch(const std::string& str, const std::string& regex); + + //! returns true if @a str matches @a re (with optional @a flags to control interpretation), false otherwise and throws std::string message on error + /*! @param str The string to match + * @param regex The regular expression which should be parsed and executed + * @param flags pass flags for regex (e.g. REG_EXTENDED) + * + * This compiles the @a regex and then executes it... for repeated usage of the same + * regular expression, you could be better off compiling it yourself and using the regex library directly. */ + bool reMatch(const std::string& str, const std::string& regex, int flags); + }; /*! @file diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/zignor.cc ./Shared/zignor.cc --- ../Tekkotsu_3.0/Shared/zignor.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/zignor.cc 2007-01-25 15:54:13.000000000 -0500 @@ -0,0 +1,288 @@ +/*! @file +*========================================================================== +* This code is Copyright (C) 2005, Jurgen A. Doornik. +* Permission to use this code for non-commercial purposes +* is hereby given, provided proper reference is made to: +* Doornik, J.A. (2005), "An Improved Ziggurat Method to Generate Normal +* Random Samples", mimeo, Nuffield College, University of Oxford, +* and www.doornik.com/research. +* or the published version when available. +* This reference is still required when using modified versions of the code. +* This notice should be maintained in modified versions of the code. +* No warranty is given regarding the correctness of this code. +*========================================================================== +* +* @author Jurgen A. Doornik (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.1 $ +* $State: Exp $ +* $Date: 2007/01/25 20:54:13 $ +*/ + +#include +#include +#include +#include +#include + +#include "zigrandom.h" +#include "zignor.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*------------------------------ General Ziggurat --------------------------*/ +static double DRanNormalTail(double dMin, int iNegative) +{ + double x, y; + do + { x = log(DRanU()) / dMin; + y = log(DRanU()); + } while (-2 * y < x * x); + return iNegative ? x - dMin : dMin - x; +} + +#define ZIGNOR_C 128 /* number of blocks */ +#define ZIGNOR_R 3.442619855899 /* start of the right tail */ + /* (R * phi(R) + Pr(X>=R)) * sqrt(2\pi) */ +#define ZIGNOR_V 9.91256303526217e-3 + +/* s_adZigX holds coordinates, such that each rectangle has*/ +/* same area; s_adZigR holds s_adZigX[i + 1] / s_adZigX[i] */ +static double s_adZigX[ZIGNOR_C + 1], s_adZigR[ZIGNOR_C]; + +static void zigNorInit(int iC, double dR, double dV) +{ + int i; double f; + + f = exp(-0.5 * dR * dR); + s_adZigX[0] = dV / f; /* [0] is bottom block: V / f(R) */ + s_adZigX[1] = dR; + s_adZigX[iC] = 0; + + for (i = 2; i < iC; ++i) + { + s_adZigX[i] = sqrt(-2 * log(dV / s_adZigX[i - 1] + f)); + f = exp(-0.5 * s_adZigX[i] * s_adZigX[i]); + } + for (i = 0; i < iC; ++i) + s_adZigR[i] = s_adZigX[i + 1] / s_adZigX[i]; +} +double DRanNormalZig(void) +{ + unsigned int i; + double x, u, f0, f1; + + for (;;) + { + u = 2 * DRanU() - 1; + i = IRanU() & 0x7F; + /* first try the rectangular boxes */ + if (fabs(u) < s_adZigR[i]) + return u * s_adZigX[i]; + /* bottom box: sample from the tail */ + if (i == 0) + return DRanNormalTail(ZIGNOR_R, u < 0); + /* is this a sample from the wedges? */ + x = u * s_adZigX[i]; + f0 = exp(-0.5 * (s_adZigX[i] * s_adZigX[i] - x * x) ); + f1 = exp(-0.5 * (s_adZigX[i+1] * s_adZigX[i+1] - x * x) ); + if (f1 + DRanU() * (f0 - f1) < 1.0) + return x; + } +} + +#define ZIGNOR_STORE 64 * 4 +static unsigned int s_auiZigTmp[ZIGNOR_STORE / 4]; +static unsigned int s_auiZigBox[ZIGNOR_STORE]; +static double s_adZigRan[ZIGNOR_STORE + ZIGNOR_STORE / 4]; +static int s_cZigStored = 0; + +double DRanNormalZigVec(void) +{ + unsigned int i, j, k; + double x, u, f0, f1; + + for (;;) + { + if (s_cZigStored == 0) + { + RanVecIntU(s_auiZigTmp, ZIGNOR_STORE / 4); + RanVecU(s_adZigRan, ZIGNOR_STORE); + for (j = k = 0; j < ZIGNOR_STORE; j += 4, ++k) + { + i = s_auiZigTmp[k]; s_auiZigBox[j + 0] = i & 0x7F; + i >>= 8; s_auiZigBox[j + 1] = i & 0x7F; + i >>= 8; s_auiZigBox[j + 2] = i & 0x7F; + i >>= 8; s_auiZigBox[j + 3] = i & 0x7F; + s_adZigRan[j + 0] = 2 * s_adZigRan[j + 0] - 1; + s_adZigRan[j + 1] = 2 * s_adZigRan[j + 1] - 1; + s_adZigRan[j + 2] = 2 * s_adZigRan[j + 2] - 1; + s_adZigRan[j + 3] = 2 * s_adZigRan[j + 3] - 1; + } + s_cZigStored = j; + } + --s_cZigStored; + + u = s_adZigRan[s_cZigStored]; + i = s_auiZigBox[s_cZigStored]; + + if (fabs(u) < s_adZigR[i]) /* first try the rectangular boxes */ + return u * s_adZigX[i]; + + if (i == 0) /* bottom box: sample from the tail */ + return DRanNormalTail(ZIGNOR_R, u < 0); + + x = u * s_adZigX[i]; /* is this a sample from the wedges? */ + f0 = exp(-0.5 * (s_adZigX[i] * s_adZigX[i] - x * x) ); + f1 = exp(-0.5 * (s_adZigX[i + 1] * s_adZigX[i + 1] - x * x) ); + if (f1 + DRanU() * (f0 - f1) < 1.0) + return x; + } +} + +void RanNormalSetSeedZig(int *piSeed, int cSeed) +{ + zigNorInit(ZIGNOR_C, ZIGNOR_R, ZIGNOR_V); + RanSetSeed(piSeed, cSeed); +} +void RanNormalSetSeedZigVec(int *piSeed, int cSeed) +{ + s_cZigStored = 0; + RanNormalSetSeedZig(piSeed, cSeed); +} +/*--------------------------- END General Ziggurat -------------------------*/ + +/*------------------------------ Integer Ziggurat --------------------------*/ +#define ZIGNOR_INVM M_RAN_INVM32 + +static unsigned int s_aiZigRm[ZIGNOR_C]; +static double s_adZigXm[ZIGNOR_C + 1]; + +static void zig32NorInit(int iC, double dR, double dV) +{ + int i; double f, m31 = ZIGNOR_INVM * 2; + + f = exp(-0.5 * dR * dR); + s_adZigXm[0] = dV / f; /* [0] is bottom block: V / f(R) */ + s_adZigXm[1] = dR; + s_adZigXm[iC] = 0; + + for (i = 2; i < iC; ++i) + { + s_adZigXm[i] = sqrt(-2 * log(dV / s_adZigXm[i - 1] + f)); + f = exp(-0.5 * s_adZigXm[i] * s_adZigXm[i]); + } + /* compute ratio and implement scaling */ + for (i = 0; i < iC; ++i) + s_aiZigRm[i] = (unsigned int) + ( (s_adZigXm[i + 1] / s_adZigXm[i]) / m31 ); + for (i = 0; i <= iC; ++i) + s_adZigXm[i] *= m31; +} +double DRanNormalZig32(void) +{ + unsigned int i; + int u; + double x, y, f0, f1; + + for (;;) + { + u = (int)IRanU(); + i = IRanU() & 0x7F; + if ((unsigned int)abs(u) < s_aiZigRm[i])/* first try the rectangles */ + return u * s_adZigXm[i]; + + if (i == 0) /* sample from the tail */ + return DRanNormalTail(ZIGNOR_R, u < 0); + + x = u * s_adZigXm[i]; /* is this a sample from the wedges? */ + y = 0.5 * s_adZigXm[i] / ZIGNOR_INVM; f0 = exp(-0.5 * (y * y - x * x) ); + y = 0.5 * s_adZigXm[i + 1] / ZIGNOR_INVM; f1 = exp(-0.5 * (y * y - x * x) ); + if (f1 + IRanU() * ZIGNOR_INVM * (f0 - f1) < 1.0) + return x; + } +} +#define ZIGNOR32_STORE 64 * 4 +static unsigned int s_auiZig32Ran[ZIGNOR32_STORE]; +static unsigned int s_auiZig32Box[ZIGNOR32_STORE]; +static int s_cZig32Stored = 0; + +double DRanNormalZig32Vec(void) +{ + unsigned int i, j, k; + int u; + double x, y, f0, f1; + + for (;;) + { + if (s_cZig32Stored == 0) + { + RanVecIntU(s_auiZig32Ran, ZIGNOR32_STORE / 4); + for (j = k = 0; j < ZIGNOR32_STORE; j += 4, ++k) + { + i = s_auiZig32Ran[k]; s_auiZig32Box[j+0] = i & 0x7F; + i >>= 8; s_auiZig32Box[j+1] = i & 0x7F; + i >>= 8; s_auiZig32Box[j+2] = i & 0x7F; + i >>= 8; s_auiZig32Box[j+3] = i & 0x7F; + } + RanVecIntU(s_auiZig32Ran, ZIGNOR32_STORE); + s_cZig32Stored = j; + } + --s_cZig32Stored; + + u = (int)s_auiZig32Ran[s_cZig32Stored]; + i = s_auiZig32Box[s_cZig32Stored]; + /* first try the rectangles */ + if ((unsigned int)abs(u) < s_aiZigRm[i]) + return u * s_adZigXm[i]; + /* bottom box: sample from the tail */ + if (i == 0) + return DRanNormalTail(ZIGNOR_R, u < 0); + /* is this a sample from the wedges? */ + x = u * s_adZigXm[i]; + y = 0.5 * s_adZigXm[i] / ZIGNOR_INVM; + f0 = exp(-0.5 * (y * y - x * x) ); + y = 0.5 * s_adZigXm[i + 1] / ZIGNOR_INVM; + f1 = exp(-0.5 * (y * y - x * x) ); + if (f1 + IRanU() * ZIGNOR_INVM * (f0 - f1) < 1.0) + return x; + } +} +void RanNormalSetSeedZig32(int *piSeed, int cSeed) +{ + zig32NorInit(ZIGNOR_C, ZIGNOR_R, ZIGNOR_V); + RanSetSeed(piSeed, cSeed); +} +void RanNormalSetSeedZig32Vec(int *piSeed, int cSeed) +{ + s_cZig32Stored = 0; + RanNormalSetSeedZig32(piSeed, cSeed); +} +/*--------------------------- END Integer Ziggurat -------------------------*/ + +/*--------------------------- functions for testing ------------------------*/ +double DRanQuanNormalZig(void) +{ + return DProbNormal(DRanNormalZig()); +} +double DRanQuanNormalZigVec(void) +{ + return DProbNormal(DRanNormalZigVec()); +} +double DRanQuanNormalZig32(void) +{ + return DProbNormal(DRanNormalZig32()); +} +double DRanQuanNormalZig32Vec(void) +{ + return DProbNormal(DRanNormalZig32Vec()); +} +/*------------------------- END functions for testing ----------------------*/ + +#ifdef __cplusplus +} //extern "C" +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/zignor.h ./Shared/zignor.h --- ../Tekkotsu_3.0/Shared/zignor.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/zignor.h 2007-01-25 15:54:13.000000000 -0500 @@ -0,0 +1,49 @@ +#ifndef INCLUDED_ZIGNOR_H +#define INCLUDED_ZIGNOR_H + +/*! @file +*========================================================================== +* This code is Copyright (C) 2005, Jurgen A. Doornik. +* Permission to use this code for non-commercial purposes +* is hereby given, provided proper reference is made to: +* Doornik, J.A. (2005), "An Improved Ziggurat Method to Generate Normal +* Random Samples", mimeo, Nuffield College, University of Oxford, +* and www.doornik.com/research. +* or the published version when available. +* This reference is still required when using modified versions of the code. +* This notice should be maintained in modified versions of the code. +* No warranty is given regarding the correctness of this code. +*========================================================================== +* +* @author Jurgen A. Doornik (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.1 $ +* $State: Exp $ +* $Date: 2007/01/25 20:54:13 $ +*/ + +#ifdef __cplusplus +extern "C" { +#endif + +void RanNormalSetSeedZig(int *piSeed, int cSeed); +double DRanNormalZig(void); +void RanNormalSetSeedZigVec(int *piSeed, int cSeed); +double DRanNormalZigVec(void); +void RanNormalSetSeedZig32(int *piSeed, int cSeed); +double DRanNormalZig32(void); +void RanNormalSetSeedZig32Vec(int *piSeed, int cSeed); +double DRanNormalZig32Vec(void); + +double DRanQuanNormalZig(void); +double DRanQuanNormalZigVec(void); +double DRanQuanNormalZig32(void); +double DRanQuanNormalZig32Vec(void); + +#ifdef __cplusplus +} //extern "C" +#endif + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/zigrandom.cc ./Shared/zigrandom.cc --- ../Tekkotsu_3.0/Shared/zigrandom.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/zigrandom.cc 2007-01-30 18:17:12.000000000 -0500 @@ -0,0 +1,318 @@ +/*! @file +*========================================================================== +* This code is Copyright (C) 2005, Jurgen A. Doornik. +* Permission to use this code for non-commercial purposes +* is hereby given, provided proper reference is made to: +* Doornik, J.A. (2005), "An Improved Ziggurat Method to Generate Normal +* Random Samples", mimeo, Nuffield College, University of Oxford, +* and www.doornik.com/research. +* or the published version when available. +* This reference is still required when using modified versions of the code. +* This notice should be maintained in modified versions of the code. +* No warranty is given regarding the correctness of this code. +*========================================================================== +* +* @author Jurgen A. Doornik (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.2 $ +* $State: Exp $ +* $Date: 2007/01/30 23:17:12 $ +*/ + +#include +#include +#include +#include + +#include "zigrandom.h" + +#ifdef __cplusplus +extern "C" { +#endif + +/*---------------------------- GetInitialSeeds -----------------------------*/ +void GetInitialSeeds(unsigned int auiSeed[], int cSeed, + unsigned int uiSeed, unsigned int uiMin) +{ + int i; + unsigned int s = uiSeed; /* may be 0 */ + + for (i = 0; i < cSeed; ) + { /* see Knuth p.106, Table 1(16) and Numerical Recipes p.284 (ranqd1)*/ + s = 1664525 * s + 1013904223; + if (s <= uiMin) + continue; + auiSeed[i] = s; + ++i; + } +} +/*-------------------------- END GetInitialSeeds ---------------------------*/ + + +/*------------------------ George Marsaglia MWC ----------------------------*/ +#define MWC_R 256 +#define MWC_A LIT_UINT64(809430660) +#define MWC_AI 809430660 +#define MWC_C 362436 +static unsigned int s_uiStateMWC = MWC_R - 1; +static unsigned int s_uiCarryMWC = MWC_C; +static unsigned int s_auiStateMWC[MWC_R]; + +void RanSetSeed_MWC8222(int *piSeed, int cSeed) +{ + s_uiStateMWC = MWC_R - 1; + s_uiCarryMWC = MWC_C; + + if (cSeed == MWC_R) + { + int i; + for (i = 0; i < MWC_R; ++i) + { + s_auiStateMWC[i] = (unsigned int)piSeed[i]; + } + } + else + { + GetInitialSeeds(s_auiStateMWC, MWC_R, piSeed && cSeed ? piSeed[0] : 0, 0); + } +} +unsigned int IRan_MWC8222(void) +{ + UINT64 t; + + s_uiStateMWC = (s_uiStateMWC + 1) & (MWC_R - 1); + t = MWC_A * s_auiStateMWC[s_uiStateMWC] + s_uiCarryMWC; + s_uiCarryMWC = (unsigned int)(t >> 32); + s_auiStateMWC[s_uiStateMWC] = (unsigned int)t; + return (unsigned int)t; +} +double DRan_MWC8222(void) +{ + UINT64 t; + + s_uiStateMWC = (s_uiStateMWC + 1) & (MWC_R - 1); + t = MWC_A * s_auiStateMWC[s_uiStateMWC] + s_uiCarryMWC; + s_uiCarryMWC = (unsigned int)(t >> 32); + s_auiStateMWC[s_uiStateMWC] = (unsigned int)t; + return RANDBL_32new(t); +} +void VecIRan_MWC8222(unsigned int *auiRan, int cRan) +{ + UINT64 t; + unsigned int carry = s_uiCarryMWC, status = s_uiStateMWC; + + for (; cRan > 0; --cRan, ++auiRan) + { + status = (status + 1) & (MWC_R - 1); + t = MWC_A * s_auiStateMWC[status] + carry; + *auiRan = s_auiStateMWC[status] = (unsigned int)t; + carry = (unsigned int)(t >> 32); + } + s_uiCarryMWC = carry; + s_uiStateMWC = status; +} +void VecDRan_MWC8222(double *adRan, int cRan) +{ + UINT64 t; + unsigned int carry = s_uiCarryMWC, status = s_uiStateMWC; + + for (; cRan > 0; --cRan, ++adRan) + { + status = (status + 1) & (MWC_R - 1); + t = MWC_A * s_auiStateMWC[status] + carry; + s_auiStateMWC[status] = (unsigned int)t; + *adRan = RANDBL_32new(t); + carry = (unsigned int)(t >> 32); + } + s_uiCarryMWC = carry; + s_uiStateMWC = status; +} +/*----------------------- END George Marsaglia MWC -------------------------*/ + + +/*------------------- normal random number generators ----------------------*/ +static int s_cNormalInStore = 0; /* > 0 if a normal is in store */ + +static DRANFUN s_fnDRanu = DRan_MWC8222; +static IRANFUN s_fnIRanu = IRan_MWC8222; +static IVECRANFUN s_fnVecIRanu = VecIRan_MWC8222; +static DVECRANFUN s_fnVecDRanu = VecDRan_MWC8222; +static RANSETSEEDFUN s_fnRanSetSeed = RanSetSeed_MWC8222; + +double DRanU(void) +{ + return (*s_fnDRanu)(); +} +unsigned int IRanU(void) +{ + return (*s_fnIRanu)(); +} +void RanVecIntU(unsigned int *auiRan, int cRan) +{ + (*s_fnVecIRanu)(auiRan, cRan); +} +void RanVecU(double *adRan, int cRan) +{ + (*s_fnVecDRanu)(adRan, cRan); +} +//void RanVecU(double *adRan, int cRan) +//{ +// int i, j, c, airan[256]; +// +// for (; cRan > 0; cRan -= 256) +// { +// c = min(cRan, 256); +// (*s_fnVecIRanu)(airan, c); +// for (j = 0; j < c; ++j) +// *adRan = RANDBL_32new(airan[j]); +// } +//} +void RanSetSeed(int *piSeed, int cSeed) +{ + s_cNormalInStore = 0; + (*s_fnRanSetSeed)(piSeed, cSeed); +} +void RanSetRan(const char *sRan) +{ + s_cNormalInStore = 0; + if (strcmp(sRan, "MWC8222") == 0) + { + s_fnDRanu = DRan_MWC8222; + s_fnIRanu = IRan_MWC8222; + s_fnVecIRanu = VecIRan_MWC8222; + s_fnRanSetSeed = RanSetSeed_MWC8222; + } + else + { + s_fnDRanu = NULL; + s_fnIRanu = NULL; + s_fnVecIRanu = NULL; + s_fnRanSetSeed = NULL; + } +} +static unsigned int IRanUfromDRanU(void) +{ + return (unsigned int)(UINT_MAX * (*s_fnDRanu)()); +} +static double DRanUfromIRanU(void) +{ + return RANDBL_32new( (*s_fnIRanu)() ); +} +void RanSetRanExt(DRANFUN DRanFun, IRANFUN IRanFun, IVECRANFUN IVecRanFun, + DVECRANFUN DVecRanFun, RANSETSEEDFUN RanSetSeedFun) +{ + s_fnDRanu = DRanFun ? DRanFun : DRanUfromIRanU; + s_fnIRanu = IRanFun ? IRanFun : IRanUfromDRanU; + s_fnVecIRanu = IVecRanFun; + s_fnVecDRanu = DVecRanFun; + s_fnRanSetSeed = RanSetSeedFun; +} +/*---------------- END uniform random number generators --------------------*/ + + +/*----------------------------- Polar normal RNG ---------------------------*/ +#define POLARBLOCK(u1, u2, d) \ + do \ + { u1 = (*s_fnDRanu)(); u1 = 2 * u1 - 1;\ + u2 = (*s_fnDRanu)(); u2 = 2 * u2 - 1;\ + d = u1 * u1 + u2 * u2; \ + } while (d >= 1); \ + d = sqrt( (-2.0 / d) * log(d) ); \ + u1 *= d; u2 *= d + +static double s_dNormalInStore; + +double DRanNormalPolar(void) /* Polar Marsaglia */ +{ + double d, u1; + + if (s_cNormalInStore) + u1 = s_dNormalInStore, s_cNormalInStore = 0; + else + { + POLARBLOCK(u1, s_dNormalInStore, d); + s_cNormalInStore = 1; + } + +return u1; +} + +#define FPOLARBLOCK(u1, u2, d) \ + do \ + { u1 = (float)((*s_fnDRanu)()); u1 = 2 * u1 - 1;\ + u2 = (float)((*s_fnDRanu)()); u2 = 2 * u2 - 1;\ + d = u1 * u1 + u2 * u2; \ + } while (d >= 1); \ + d = sqrt( (-2.0 / d) * log(d) ); \ + u1 *= d; u2 *= d + +static float s_fNormalInStore; +double FRanNormalPolar(void) /* Polar Marsaglia */ +{ + float d, u1; + + if (s_cNormalInStore) + u1 = s_fNormalInStore, s_cNormalInStore = 0; + else + { + POLARBLOCK(u1, s_fNormalInStore, d); + s_cNormalInStore = 1; + } + +return (double)u1; +} +/*--------------------------- END Polar normal RNG -------------------------*/ + +/*------------------------------ DRanQuanNormal -----------------------------*/ +static double dProbN(double x, int fUpper) +{ + double p; double y; int fnegative = 0; + + if (x < 0) + x = -x, fnegative = 1, fUpper = !fUpper; + else if (x == 0) + return 0.5; + + if ( !(x <= 8 || (fUpper && x <= 37) ) ) + return (fUpper) ? 0 : 1; + + y = x * x / 2; + + if (x <= 1.28) + { + p = 0.5 - x * (0.398942280444 - 0.399903438504 * y / + (y + 5.75885480458 - 29.8213557808 / + (y + 2.62433121679 + 48.6959930692 / + (y + 5.92885724438)))); + } + else + { + p = 0.398942280385 * exp(-y) / + (x - 3.8052e-8 + 1.00000615302 / + (x + 3.98064794e-4 + 1.98615381364 / + (x - 0.151679116635 + 5.29330324926 / + (x + 4.8385912808 - 15.1508972451 / + (x + 0.742380924027 + 30.789933034 / + (x + 3.99019417011)))))); + } + return (fUpper) ? p : 1 - p; +} +double DProbNormal(double x) +{ + return dProbN(x, 0); +} +double DRanQuanNormal(void) +{ + return DProbNormal(DRanNormalPolar()); +} +double FRanQuanNormal(void) +{ + return DProbNormal(FRanNormalPolar()); +} +/*----------------------------- END DRanQuanNormal -------------------------*/ + +#ifdef __cplusplus +} //extern "C" +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/zigrandom.h ./Shared/zigrandom.h --- ../Tekkotsu_3.0/Shared/zigrandom.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Shared/zigrandom.h 2007-01-25 15:54:13.000000000 -0500 @@ -0,0 +1,111 @@ +#ifndef INCLUDED_ZIGRANDOM_H +#define INCLUDED_ZIGRANDOM_H + +/*! @file +*========================================================================== +* This code is Copyright (C) 2005, Jurgen A. Doornik. +* Permission to use this code for non-commercial purposes +* is hereby given, provided proper reference is made to: +* Doornik, J.A. (2005), "An Improved Ziggurat Method to Generate Normal +* Random Samples", mimeo, Nuffield College, University of Oxford, +* and www.doornik.com/research. +* or the published version when available. +* This reference is still required when using modified versions of the code. +* This notice should be maintained in modified versions of the code. +* No warranty is given regarding the correctness of this code. +*========================================================================== +* +* @author Jurgen A. Doornik (Creator) +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.1 $ +* $State: Exp $ +* $Date: 2007/01/25 20:54:13 $ +*/ + +#ifdef __cplusplus +extern "C" { +#endif + +#ifdef __LP64__ + typedef unsigned long UINT64; + typedef long INT64; + #define LIT_UINT64(c) (c##ul) + #define LIT_INT64(c) (c##l) +#elif defined(_MSC_VER) + typedef unsigned __int64 UINT64; + typedef __int64 INT64; + #define LIT_UINT64(c) (c##ui64) + #define LIT_INT64(c) (c##i64) +#else + typedef unsigned long long UINT64; + typedef long long INT64; + #define LIT_UINT64(c) (c##ull) + #define LIT_INT64(c) (c##ll) +#endif + +#define M_RAN_INVM30 9.31322574615478515625e-010 /* 1.0 / 2^30 */ +#define M_RAN_INVM32 2.32830643653869628906e-010 /* 1.0 / 2^32 */ +#define M_RAN_INVM48 3.55271367880050092936e-015 /* 1.0 / 2^48 */ +#define M_RAN_INVM52 2.22044604925031308085e-016 /* 1.0 / 2^52 */ +#define M_RAN_INVM64 5.42101086242752217004e-020 /* 1.0 / 2^64 */ + +#define RANDBL_32old(iRan1) \ + ((unsigned int)(iRan1) * M_RAN_INVM32) +#define RANDBL_48old(iRan1, iRan2) \ + ((unsigned int)(iRan1) + (unsigned int)((iRan2) << 16) \ + * M_RAN_INVM32) * M_RAN_INVM32 +#define RANDBL_52old(iRan1, iRan2) \ + ((unsigned int)(iRan1) + (unsigned int)((iRan2) << 12) \ + * M_RAN_INVM32) * M_RAN_INVM32 + +#define RANDBL_32new(iRan1) \ + ((int)(iRan1) * M_RAN_INVM32 + (0.5 + M_RAN_INVM32 / 2)) +#define RANDBL_48new(iRan1, iRan2) \ + ((int)(iRan1) * M_RAN_INVM32 + (0.5 + M_RAN_INVM48 / 2) + \ + (int)((iRan2) & 0x0000FFFF) * M_RAN_INVM48) +#define RANDBL_52new(iRan1, iRan2) \ + ((int)(iRan1) * M_RAN_INVM32 + (0.5 + M_RAN_INVM52 / 2) + \ + (int)((iRan2) & 0x000FFFFF) * M_RAN_INVM52) + +void GetInitialSeeds(unsigned int auiSeed[], int cSeed, + unsigned int uiSeed, unsigned int uiMin); + +/* MWC8222 George Marsaglia */ +void RanSetSeed_MWC8222(int *piSeed, int cSeed); +unsigned int IRan_MWC8222(void); +double DRan_MWC8222(void); +void VecIRan_MWC8222(unsigned int *auiRan, int cRan); +void VecDRan_MWC8222(double *adRan, int cRan); + +/* plug-in RNG */ +typedef double ( * DRANFUN)(void); +typedef unsigned int( * IRANFUN)(void); +typedef void ( * IVECRANFUN)(unsigned int *, int); +typedef void ( * DVECRANFUN)(double *, int); +typedef void ( * RANSETSEEDFUN)(int *, int); + +void RanSetRan(const char *sRan); +void RanSetRanExt(DRANFUN DRanFun, IRANFUN IRanFun, IVECRANFUN IVecRanFun, + DVECRANFUN DVecRanFun, RANSETSEEDFUN RanSetSeedFun); +double DRanU(void); +unsigned int IRanU(void); +void RanVecIntU(unsigned int *auiRan, int cRan); +void RanVecU(double *adRan, int cRan); +void RanSetSeed(int *piSeed, int cSeed); + +/* normal probabilities */ +double DProbNormal(double x); + +/* polar standard normal RNG */ +double FRanNormalPolar(void); +double DRanNormalPolar(void); +double FRanQuanNormal(void); +double DRanQuanNormal(void); + +#ifdef __cplusplus +} //extern "C" +#endif + +#endif /* INCLUDED_ZIGRANDOM_H */ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Sound/PitchDetector.cc ./Sound/PitchDetector.cc --- ../Tekkotsu_3.0/Sound/PitchDetector.cc 2006-09-22 12:16:55.000000000 -0400 +++ ./Sound/PitchDetector.cc 2007-11-12 23:16:04.000000000 -0500 @@ -15,11 +15,11 @@ //better to put this here instead of the header using namespace std; -const unsigned int PitchDetector::fft_frames = 4; //!< number frames to use for fft -const unsigned int PitchDetector::num_pitches = 60; //!< 5 octaves -const float PitchDetector::base_pitch = 110.0f; //!< two octaves below tuning A (440) -const float PitchDetector::half_step = 1.0594630943593f; //!< twelfth root of two -const float PitchDetector::sqrt_2_pi = 2.506628274631f; //!< \sqrt{2\pi} +const unsigned int PitchDetector::fft_frames = 4; // number frames to use for fft +const unsigned int PitchDetector::num_pitches = 60; // 5 octaves +const float PitchDetector::base_pitch = 110.0f; // two octaves below tuning A (440) +const float PitchDetector::half_step = 1.0594630943593f; // twelfth root of two +const float PitchDetector::sqrt_2_pi = 2.506628274631f; // \sqrt{2\pi} PitchDetector::~PitchDetector() { ASSERT(pitch_info==NULL,"pitch_info wasn't deleted before destructor"); @@ -192,11 +192,11 @@ EventBase::EventTypeID_t type = ( ! pitch_info[i].duration ) ? EventBase::activateETID : EventBase::statusETID; pitch_info[i].amplitude = (pitch_info[i].amplitude*pitch_info[i].duration + pitch_bin[i]) / (pitch_info[i].duration + 1); ++pitch_info[i].duration; - erouter->postEvent(PitchEvent((unsigned int) this, type, pitch_info[i].freq, pitch_name(i), pitch_bin[i], pitch_info[i].duration*win_sz*1000/rate, c)); + erouter->postEvent(PitchEvent(reinterpret_cast(this), type, pitch_info[i].freq, pitch_name(i), pitch_bin[i], pitch_info[i].duration*win_sz*1000/rate, c)); } else { if (pitch_info[i].duration) { //printf("pitch number %u, frequency %f, name %s, confidence %f, duration %u went off \n",i, pitch_info[i].freq, pitch_name(i), c, pitch_info[i].duration); - erouter->postEvent(PitchEvent((unsigned int) this,EventBase::deactivateETID,pitch_info[i].freq, pitch_name(i),pitch_info[i].amplitude,pitch_info[i].duration*win_sz*1000/rate,c)); + erouter->postEvent(PitchEvent(reinterpret_cast(this), EventBase::deactivateETID,pitch_info[i].freq, pitch_name(i),pitch_info[i].amplitude,pitch_info[i].duration*win_sz*1000/rate,c)); pitch_info[i].duration = 0; pitch_info[i].amplitude = 0; } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Sound/PitchDetector.h ./Sound/PitchDetector.h --- ../Tekkotsu_3.0/Sound/PitchDetector.h 2006-09-28 17:00:28.000000000 -0400 +++ ./Sound/PitchDetector.h 2007-11-12 23:16:04.000000000 -0500 @@ -16,7 +16,7 @@ static const float sqrt_2_pi; //!< set to @f$ \sqrt{2\pi} @f$ //! constructor - PitchDetector() : EventGeneratorBase("PitchDetector","PitchDetector",EventBase::micPitchEGID,(unsigned int)this,EventBase::micOSndEGID), + PitchDetector() : EventGeneratorBase("PitchDetector","PitchDetector",EventBase::micPitchEGID,reinterpret_cast(this),EventBase::micOSndEGID), left(), right(), iml(), imr(), rel(), rer(), pol(), por(), po(), frame_sz(0), win_sz(0), rate(0), cur_frame(0), local_maxes(0), pitch_info(NULL), pitch_bin(NULL), have_fft(false) //,fft_file(0) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Sound/SoundManager.h ./Sound/SoundManager.h --- ../Tekkotsu_3.0/Sound/SoundManager.h 2006-09-29 12:56:10.000000000 -0400 +++ ./Sound/SoundManager.h 2006-10-03 18:52:24.000000000 -0400 @@ -30,9 +30,9 @@ * at a time and chain them so it seamlessly moves from one to the * other. * - * You can also preload sounds (loadFile()) before playing them so - * there's no delay while loading after you request a sound to be - * played. Just be sure to release the file (releaseFile()) again + * You can also preload sounds (loadFile()) before playing them (play() / playFile()) so + * there's no delay between requesting a sound and having it start playing while it is loaded from disk/memory stick. + * Just be sure to release the file (releaseFile()) again * when you're done with it ;) * * All functions will attempt to lock the SoundManager. Remember, @@ -52,6 +52,8 @@ * * @todo Add functions to hand out regions to be filled out to avoid * copying into the buffer. + * + * @see David Touretzky's "Playing Sounds" Chapter */ class SoundManager { public: diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/BufferedImageGenerator.cc ./Vision/BufferedImageGenerator.cc --- ../Tekkotsu_3.0/Vision/BufferedImageGenerator.cc 2006-09-11 19:05:19.000000000 -0400 +++ ./Vision/BufferedImageGenerator.cc 2007-08-20 17:21:27.000000000 -0400 @@ -46,9 +46,13 @@ if(imgsrc.width!=getWidth(imgsrc.layer) || imgsrc.height!=getHeight(imgsrc.layer)) { freeCaches(); setDimensions(); - serr->printf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, \"full\" layer now %dx%d\n",widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); - } else if(strides[numLayers-1]==0) { - // first frame, set it anyway + if(framesProcessed==0) + serr->printf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, \"full\" layer now %dx%d\n",widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); + else + serr->printf("WARNING: the image dimensions have changed since last frame, \"full\" layer now %dx%d\n",widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); + erouter->postEvent(EventBase::cameraResolutionEGID,event.getSourceID(),EventBase::statusETID); + } else if(framesProcessed==0) { + // first frame, always set it anyway setDimensions(); } } @@ -119,7 +123,7 @@ } unsigned char* img=images[selectedSaveLayer][selectedSaveChannel]; unsigned int used=widths[selectedSaveLayer]*heights[selectedSaveLayer]; - ASSERTRETVAL(used<=len,"buffer too small",0); + ASSERTRETVAL(used<=len,"buffer too small " << len << ' ' << widths[selectedSaveLayer] << ' ' << heights[selectedSaveLayer],0); unsigned int inc=getIncrement(selectedSaveLayer); if(inc==1) { //special case, straight copy @@ -280,19 +284,25 @@ void BufferedImageGenerator::setDimensions() { if(imgsrc.img==NULL) //don't have an image to set from return; - // set dimensions of layers below and including the input layer + // set dimensions of layers below the input layer for(unsigned int i=0; i<=imgsrc.layer; i++) { //s is the scaling factor -- 2 means *half* size unsigned int s=(1<<(imgsrc.layer-i)); //width and height are scaled down (divide by s) - widths[i]=imgsrc.width/s; + widths[i]=strides[i]=imgsrc.width/s; heights[i]=imgsrc.height/s; - //need to skip rows to make good on promised height (multiply by s) - strides[i]=imgsrc.width*imgsrc.channels*s; - skips[i]=strides[i]-imgsrc.width*imgsrc.channels; + //stride is same as width (set above) -- we allocate these layers, don't skip rows + skips[i]=0; + increments[i]=1; //cout << "setDimensions() " << widths[i] << ' ' << skips[i] << ' ' << strides[i] << endl; } - //set dimensions for layers above the input layer, these are not interleaved + // set dimensions of the input layer (interleaved -- note increment and stride) + increments[imgsrc.layer] = imgsrc.channels; + widths[imgsrc.layer]=imgsrc.width; + heights[imgsrc.layer]=imgsrc.height; + strides[imgsrc.layer]=imgsrc.width*imgsrc.channels; + skips[imgsrc.layer]=0; + //set dimensions for layers above the input layer for(unsigned int i=imgsrc.layer+1; iprintf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, now %dx%d\n",widths[numLayers-1],heights[numLayers-1]); + serr->printf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, \"full\" layer now %dx%d\n",widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); dimchange=true; } else if(strides[0]==0) { dimchange=true; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/FilterBankGenerator.cc ./Vision/FilterBankGenerator.cc --- ../Tekkotsu_3.0/Vision/FilterBankGenerator.cc 2006-09-09 00:33:04.000000000 -0400 +++ ./Vision/FilterBankGenerator.cc 2007-08-20 17:21:27.000000000 -0400 @@ -3,6 +3,7 @@ #include "Events/EventRouter.h" #include "Wireless/Socket.h" #include "Shared/RobotInfo.h" +#include "Shared/ProjectInterface.h" using namespace std; @@ -130,6 +131,7 @@ widths[i]=src->getWidth(i); heights[i]=src->getHeight(i); } + freeCaches(); } void @@ -177,8 +179,11 @@ return false; } if(src->getWidth(numLayers-1)!=getWidth(numLayers-1) || src->getHeight(numLayers-1)!=getHeight(numLayers-1)) { - serr->printf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, now %dx%d",widths[numLayers-1],heights[numLayers-1]); setDimensions(); + if(framesProcessed==0) + serr->printf("WARNING: %s image dimensions don't match values predicted by RobotInfo consts, \"full\" layer now %dx%d\n",getName().c_str(),widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); + else + serr->printf("WARNING: %s image dimensions have changed since last frame, \"full\" layer now %dx%d\n",getName().c_str(),widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); } else if(framesProcessed==0) { setDimensions(); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/JPEGGenerator.cc ./Vision/JPEGGenerator.cc --- ../Tekkotsu_3.0/Vision/JPEGGenerator.cc 2006-09-11 19:05:20.000000000 -0400 +++ ./Vision/JPEGGenerator.cc 2007-06-22 14:33:52.000000000 -0400 @@ -6,10 +6,7 @@ #include "Wireless/Wireless.h" #include "Shared/Config.h" #include "Shared/Profiler.h" - -#include "Shared/jpeg-6b/jpeg_mem_dest.h" - -#include "Shared/debuget.h" +#include "Shared/ImageUtil.h" JPEGGenerator::JPEGGenerator(unsigned int mysid, FilterBankGenerator* fbg, EventBase::EventTypeID_t tid) : FilterBankGenerator("JPEGGenerator","JPEGGenerator",EventBase::visJPEGEGID,mysid,fbg,tid), srcMode(SRC_AUTO), curMode(SRC_AUTO), bytesUsed(NULL), cinfo(), jerr(), quality(-1U) @@ -194,97 +191,35 @@ return new unsigned char[widths[layer]*heights[layer]*3+JPEG_HEADER_PAD]; } -/*! This function is taken pretty directly from the write_jpeg_mem() - * function from Sony's W3AIBO sample code. - * - * I have adapted it for this object, and added the ability to - * process greyscale images as well as color. - */ void JPEGGenerator::calcImage(unsigned int layer, unsigned int chan) { PROFSECTION("JPEGGenerator::calcImage(...)",*mainProfiler); -try { - //pass the destination buffer and buffer size here - jpeg_mem_dest(&cinfo, images[layer][chan], widths[layer]*heights[layer]*3+JPEG_HEADER_PAD); - - // mode setup - cinfo.image_width = widths[layer]; - cinfo.image_height = heights[layer]; + + // input configuration + char* inbuf = reinterpret_cast(src->getImage(layer,chan)); + size_t inbufSize = src->getWidth(layer)*src->getIncrement(layer)*src->getHeight(layer); + size_t srcChans = src->getIncrement(layer); + + // output configuration + ASSERT(images[layer][chan]!=NULL,"image was not allocated"); + char*& outbuf = reinterpret_cast(images[layer][chan]); + size_t outbufSize = widths[layer]*heights[layer]*3+JPEG_HEADER_PAD; + size_t dstChans; if(getCurrentSourceFormat()==SRC_COLOR ) { - cinfo.input_components = 3; /* # of color components per pixel */ - cinfo.in_color_space = JCS_YCbCr; /* colorspace of input image */ + dstChans=3; } else if(getCurrentSourceFormat()==SRC_GRAYSCALE) { - cinfo.input_components = 1; /* # of color components per pixel */ - cinfo.in_color_space = JCS_GRAYSCALE; /* colorspace of input image */ + dstChans=1; } else { serr->printf("%s %s Compression failed - unsuitable or unknown mode/generator pair",getClassName().c_str(),getName().c_str()); - jpeg_destroy_compress(&cinfo); return; } - - // parameter setup - jpeg_set_defaults(&cinfo); - unsigned int qual=(quality==-1U?config->vision.rawcam_compress_quality:quality); - jpeg_set_quality(&cinfo, qual, false); /* limit to baseline-JPEG values */ - cinfo.dct_method=config->vision.jpeg_dct_method; - if(cinfo.in_color_space==JCS_GRAYSCALE && src->getIncrement(layer)!=1) { - //special case, need to remove interleaved channels as we compress (single channel, grayscale) - jpeg_start_compress(&cinfo, TRUE); - unsigned int row_stride = src->getStride(layer); /* JSAMPLEs per row in image_buffer */ - JSAMPROW row_pointer[1] = { new JSAMPLE[src->getWidth(layer)] }; - unsigned char * curpos=src->getImage(layer,chan); - const unsigned int inc=src->getIncrement(layer); - while (cinfo.next_scanline < cinfo.image_height) { - for(unsigned int x=0; xgetWidth(layer); x++) - row_pointer[0][x] = curpos[x*inc]; - jpeg_write_scanlines(&cinfo, row_pointer, 1); - curpos+=row_stride; - } - jpeg_finish_compress(&cinfo); - - } else { - if(cinfo.in_color_space==JCS_YCbCr) { - unsigned int ysamp=1; - unsigned int uvsamp=1; - const unsigned int maxsamp=2; // according to jpeg docs, this should be able to go up to 4, but I get error: "Sampling factors too large for interleaved scan" - if(config->vision.rawcam_y_skip>config->vision.rawcam_uv_skip) { - uvsamp=config->vision.rawcam_y_skip-config->vision.rawcam_uv_skip+1; - if(uvsamp>maxsamp) - uvsamp=maxsamp; - } else { - ysamp=config->vision.rawcam_uv_skip-config->vision.rawcam_y_skip+1; - if(ysamp>maxsamp) - ysamp=maxsamp; - } - cinfo.comp_info[0].h_samp_factor=ysamp; - cinfo.comp_info[0].v_samp_factor=ysamp; - cinfo.comp_info[1].h_samp_factor=uvsamp; - cinfo.comp_info[1].v_samp_factor=uvsamp; - cinfo.comp_info[2].h_samp_factor=uvsamp; - cinfo.comp_info[2].v_samp_factor=uvsamp; - } - - // compression - jpeg_start_compress(&cinfo, TRUE); - unsigned int row_stride = src->getStride(layer); /* JSAMPLEs per row in image_buffer */ - JSAMPROW row_pointer[1] = { const_cast(src->getImage(layer,chan)) }; - while (cinfo.next_scanline < cinfo.image_height) { - jpeg_write_scanlines(&cinfo, row_pointer, 1); - row_pointer[0]+=row_stride; - } - jpeg_finish_compress(&cinfo); - } - - // results - bytesUsed[layer][chan]=jpeg_mem_size(&cinfo); - imageValids[layer][chan]=true; -} catch(const std::exception& ex) { - std::cerr << "Exception while compressing JPEG: " << ex.what() << std::endl; //really, can only be bad_alloc - std::cerr << "layer==" << layer << " channel==" << chan << " image==" << (void*)images[layer][chan] << std::endl; - std::cerr << "width==" << widths[layer] << " height==" << heights[layer] << std::endl; - std::cerr << "row_stride==" << src->getStride(layer) << " next_scanline==" << reinterpret_cast(cinfo.next_scanline) << " image_height==" << cinfo.image_height << std::endl; - jpeg_destroy_compress(&cinfo); -} + unsigned int qual = (quality==-1U?*config->vision.rawcam.compress_quality:quality); + unsigned int yskip = config->vision.rawcam.y_skip; + unsigned int uvskip = config->vision.rawcam.uv_skip; + + // do it! + bytesUsed[layer][chan] = image_util::encodeJPEG(inbuf,inbufSize,widths[layer],heights[layer],srcChans,outbuf,outbufSize,dstChans,qual,yskip,uvskip,cinfo); + imageValids[layer][chan] = (bytesUsed[layer][chan]!=0); } void diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/JPEGGenerator.h ./Vision/JPEGGenerator.h --- ../Tekkotsu_3.0/Vision/JPEGGenerator.h 2006-09-16 13:32:40.000000000 -0400 +++ ./Vision/JPEGGenerator.h 2007-04-09 18:22:04.000000000 -0400 @@ -3,7 +3,6 @@ #define INCLUDED_JPEGGenerator_h_ #include "Vision/FilterBankGenerator.h" - extern "C" { #include } @@ -102,7 +101,7 @@ struct jpeg_compress_struct cinfo; //!< used to interface with libjpeg - holds compression parameters and state struct jpeg_error_mgr jerr; //!< used to interface with libjpeg - gives us access to error information - unsigned int quality; //!< quality level to pass to libjpeg; -1U causes Config::vision_config::rawcam_compress_quality to be used + unsigned int quality; //!< quality level to pass to libjpeg; -1U causes Config::vision_config::RawCamBehavior::compress_quality to be used private: JPEGGenerator(const JPEGGenerator& fbk); //!< don't call diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/PNGGenerator.cc ./Vision/PNGGenerator.cc --- ../Tekkotsu_3.0/Vision/PNGGenerator.cc 2006-09-16 02:01:41.000000000 -0400 +++ ./Vision/PNGGenerator.cc 2007-06-22 14:33:52.000000000 -0400 @@ -5,33 +5,10 @@ #include "Events/FilterBankEvent.h" #include "Shared/Profiler.h" #include "Wireless/Socket.h" +#include "Shared/ImageUtil.h" -//better to put this here instead of the header using namespace std; -extern "C" { - //! stores progress of user_write_png_data() between calls - struct png_write_mem_status { - png_bytep buf; //!< beginning of buffer being writen into (doesn't move with progress) - size_t bufsize; //!< total size of buffer - size_t offset; //!< position within buffer, i.e. amount of buffer written so far - }; - //! user callback function for writing a png at @a data into user parameters stored in @a png_ptr - void user_write_png_data(png_structp png_ptr, png_bytep data, png_size_t length) { - png_write_mem_status* status=(png_write_mem_status*)(png_get_io_ptr(png_ptr)); - size_t endoff=status->offset+length; - if(endoff<=status->bufsize) { - memcpy(status->buf+status->offset,data,length); - status->offset=endoff; - } else { - png_error(png_ptr, "Write Error - ran out of file"); - } - } - //! user callback function for flushing results of user_write_png_data() (this is a no-op) - void user_flush_png_data(png_structp /*png_ptr*/) {} -} - - PNGGenerator::PNGGenerator(unsigned int mysid, FilterBankGenerator* fbg, EventBase::EventTypeID_t tid) : FilterBankGenerator("PNGGenerator","PNGGenerator",EventBase::visPNGEGID,mysid,fbg,tid), srcMode(SRC_AUTO), curMode(SRC_AUTO), bytesUsed(NULL) { @@ -206,64 +183,28 @@ PNGGenerator::calcImage(unsigned int layer, unsigned int chan) { PROFSECTION("PNGGenerator::calcImage(...)",*mainProfiler); - png_structp png_ptr = png_create_write_struct(PNG_LIBPNG_VER_STRING, NULL, NULL, NULL); - if (!png_ptr) { - serr->printf("png_create_info_struct failed, %s unavailable.\n",getName().c_str()); - return; - } - png_infop info_ptr = png_create_info_struct(png_ptr); - if (!info_ptr) { - png_destroy_write_struct(&png_ptr, NULL); - serr->printf("png_create_info_struct failed, %s unavailable.\n",getName().c_str()); - return; - } - - png_write_mem_status write_status; - write_status.buf=images[layer][chan]; - write_status.bufsize=widths[layer]*heights[layer]*3+PNG_HEADER_PAD; - write_status.offset=0; - png_set_write_fn(png_ptr, &write_status, user_write_png_data, user_flush_png_data); + // input configuration + char* inbuf = reinterpret_cast(src->getImage(layer,chan)); + size_t inbufSize = src->getWidth(layer)*src->getIncrement(layer)*src->getHeight(layer); + size_t srcChans = src->getIncrement(layer); - if(setjmp(png_jmpbuf(png_ptr))) { - serr->printf("An error occurred during PNG compression\n"); - png_destroy_write_struct(&png_ptr, &info_ptr); - return; - } - int bit_depth=8; - int color_type; - if(getCurrentSourceFormat()==SRC_COLOR) - color_type=PNG_COLOR_TYPE_RGB; - else if(getCurrentSourceFormat()==SRC_GRAYSCALE) - color_type=PNG_COLOR_TYPE_GRAY; - else { - serr->printf("calcImage failed - unsuitable or unknown mode/generator pair\n"); - return; - } - png_set_IHDR(png_ptr, info_ptr, widths[layer], heights[layer], bit_depth, color_type, PNG_INTERLACE_NONE, PNG_COMPRESSION_TYPE_DEFAULT, PNG_FILTER_TYPE_DEFAULT); - png_write_info(png_ptr, info_ptr); - png_bytep row=reinterpret_cast(src->getImage(layer,chan)); - const unsigned int inc=src->getIncrement(layer); -#ifdef DEBUG - if(getCurrentSourceFormat()==SRC_COLOR && inc!=3 || getCurrentSourceFormat()==SRC_GRAYSCALE && inc!=1) { - serr->printf("PNGGenerator only supports color mode from sources with interleaving of 3 samples (increment==3), or grayscale from \"pure\" sources (increment==1)\n"); - png_write_end(png_ptr, NULL); + // output configuration + ASSERT(images[layer][chan]!=NULL,"image was not allocated"); + char*& outbuf = reinterpret_cast(images[layer][chan]); + size_t outbufSize = widths[layer]*heights[layer]*3+PNG_HEADER_PAD; + size_t dstChans; + if(getCurrentSourceFormat()==SRC_COLOR ) { + dstChans=3; + } else if(getCurrentSourceFormat()==SRC_GRAYSCALE) { + dstChans=1; + } else { + serr->printf("%s %s Compression failed - unsuitable or unknown mode/generator pair",getClassName().c_str(),getName().c_str()); return; } -#endif - unsigned int row_stride = src->getStride(layer); - png_bytep endp=reinterpret_cast(row+row_stride*heights[layer]); - for(unsigned int h=0; hendp) { - serr->printf("Ran out of src image -- bad height?\n"); - break; - } - png_write_row(png_ptr, row); - row+=row_stride; - } - png_write_end(png_ptr, NULL); - png_destroy_write_struct(&png_ptr, &info_ptr); - bytesUsed[layer][chan]=write_status.offset; - imageValids[layer][chan]=true; + + // do it! + bytesUsed[layer][chan] = image_util::encodePNG(inbuf,inbufSize,widths[layer],heights[layer],srcChans,outbuf,outbufSize,dstChans); + imageValids[layer][chan] = (bytesUsed[layer][chan]!=0); } void diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/PNGGenerator.h ./Vision/PNGGenerator.h --- ../Tekkotsu_3.0/Vision/PNGGenerator.h 2006-09-16 13:32:40.000000000 -0400 +++ ./Vision/PNGGenerator.h 2007-04-09 18:22:05.000000000 -0400 @@ -3,11 +3,6 @@ #define INCLUDED_PNGGenerator_h_ #include "Vision/FilterBankGenerator.h" -#include - -extern "C" { - void user_write_png_data(png_structp png_ptr, png_bytep data, png_size_t length); -} //! Generates FilterBankEvents containing PNG compressed images /*! diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/RawCameraGenerator.cc ./Vision/RawCameraGenerator.cc --- ../Tekkotsu_3.0/Vision/RawCameraGenerator.cc 2006-09-11 19:05:22.000000000 -0400 +++ ./Vision/RawCameraGenerator.cc 2007-06-05 17:56:00.000000000 -0400 @@ -5,6 +5,7 @@ #include "Wireless/Wireless.h" #include "Shared/Config.h" #include "Shared/Profiler.h" +#include "Shared/ProjectInterface.h" #include "Shared/ODataFormats.h" #include "OFbkImage.h" @@ -69,7 +70,7 @@ //|| widths[numLayers-2-numRealLayers]*2!=widths[numNotRealLayers] //|| heights[numLayers-2-numRealLayers]*2!=heights[numNotRealLayers]) { //set the width and height of non-real layers (since they don't match what they should be) - serr->printf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, now %dx%d\n",widths[numLayers-1],heights[numLayers-1]); + serr->printf("WARNING: the image dimensions don't match values predicted by RobotInfo consts, \"full\" layer now %dx%d\n",widths[ProjectInterface::fullLayer],heights[ProjectInterface::fullLayer]); freeCaches(); dimchange=true; } else if(strides[numLayers-1]==0) { @@ -80,7 +81,7 @@ setDimensions(); float testaspect=widths[numLayers-2]/(float)heights[numLayers-2]; if(fabs(testaspect-config->vision.aspectRatio)>FLT_EPSILON) { - serr->printf("WARNING: the image aspect ratio changed, was %g, now %g (diff %g)\n",config->vision.aspectRatio,testaspect,testaspect-config->vision.aspectRatio); + serr->printf("WARNING: the image aspect ratio changed, was %g, now %g (diff %g)\n",*config->vision.aspectRatio,testaspect,testaspect-*config->vision.aspectRatio); config->vision.aspectRatio=testaspect; if(testaspect>1) { config->vision.x_range=1; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/SegmentedColorGenerator.h ./Vision/SegmentedColorGenerator.h --- ../Tekkotsu_3.0/Vision/SegmentedColorGenerator.h 2006-09-22 18:31:44.000000000 -0400 +++ ./Vision/SegmentedColorGenerator.h 2006-11-12 04:08:05.000000000 -0500 @@ -117,6 +117,10 @@ return getColorRGB(name.c_str()); } + //! returns the name of a color given its index + const char* getColorName(const unsigned int index) const { + return (index>=numColors ? NULL : getColors()[index].name); + } virtual unsigned int getBinSize() const; virtual unsigned int loadBuffer(const char buf[], unsigned int len); diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/cmv_region.h ./Vision/cmv_region.h --- ../Tekkotsu_3.0/Vision/cmv_region.h 2005-06-01 01:47:58.000000000 -0400 +++ ./Vision/cmv_region.h 2007-11-11 18:57:27.000000000 -0500 @@ -1,20 +1,19 @@ -/*======================================================================== - cmv_region.h : Region and connected component support for CMVision2 - ------------------------------------------------------------------------ - Copyright (C) 1999-2002 James R. Bruce - School of Computer Science, Carnegie Mellon University - ------------------------------------------------------------------------ - This software is distributed under the GNU General Public License, - version 2. If you do not have a copy of this licence, visit - www.gnu.org, or write: Free Software Foundation, 59 Temple Place, - Suite 330 Boston, MA 02111-1307 USA. This program is distributed - in the hope that it will be useful, but WITHOUT ANY WARRANTY, - including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - ========================================================================*/ - #ifndef __CMV_REGION_H__ #define __CMV_REGION_H__ +/*! @file +* @brief Region and connected component support for #CMVision +* @author James R. Bruce, School of Computer Science, Carnegie Mellon University +* +* Licensed under the GNU GPL version 2 +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.11 $ +* $State: Exp $ +* $Date: 2007/11/11 23:57:27 $ +*/ + //@todo this should go away - ET const unsigned int MAX_COLORS=20; @@ -1062,10 +1061,8 @@ return(end); } -using namespace __gnu_cxx; - template -int LoadColorInformation(color_class_state_t *color,int max,const char *filename, hash_map, hashcmp_eqstr> &color_names) +int LoadColorInformation(color_class_state_t *color,int max,const char *filename, __gnu_cxx::hash_map, hashcmp_eqstr> &color_names) { char buf[512]; FILE *in; diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/cmv_threshold.h ./Vision/cmv_threshold.h --- ../Tekkotsu_3.0/Vision/cmv_threshold.h 2006-07-02 14:50:56.000000000 -0400 +++ ./Vision/cmv_threshold.h 2007-08-14 14:24:07.000000000 -0400 @@ -1,20 +1,19 @@ -/*======================================================================== - cmv_threshold.h : Color threshold support for CMVision2 - ------------------------------------------------------------------------ - Copyright (C) 1999-2002 James R. Bruce - School of Computer Science, Carnegie Mellon University - ------------------------------------------------------------------------ - This software is distributed under the GNU General Public License, - version 2. If you do not have a copy of this licence, visit - www.gnu.org, or write: Free Software Foundation, 59 Temple Place, - Suite 330 Boston, MA 02111-1307 USA. This program is distributed - in the hope that it will be useful, but WITHOUT ANY WARRANTY, - including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - ========================================================================*/ - #ifndef __CMV_THRESHOLD_H__ #define __CMV_THRESHOLD_H__ +/*! @file +* @brief Color threshold support for #CMVision +* @author James R. Bruce, School of Computer Science, Carnegie Mellon University +* +* Licensed under the GNU GPL version 2 +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.9 $ +* $State: Exp $ +* $Date: 2007/08/14 18:24:07 $ +*/ + #include #include "cmv_types.h" diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/cmv_types.h ./Vision/cmv_types.h --- ../Tekkotsu_3.0/Vision/cmv_types.h 2006-01-17 15:10:03.000000000 -0500 +++ ./Vision/cmv_types.h 2007-08-14 14:24:07.000000000 -0400 @@ -1,20 +1,19 @@ -/*======================================================================== - cmv_types.h : Base types for CMVision2 - ------------------------------------------------------------------------ - Copyright (C) 1999-2002 James R. Bruce - School of Computer Science, Carnegie Mellon University - ------------------------------------------------------------------------ - This software is distributed under the GNU General Public License, - version 2. If you do not have a copy of this licence, visit - www.gnu.org, or write: Free Software Foundation, 59 Temple Place, - Suite 330 Boston, MA 02111-1307 USA. This program is distributed - in the hope that it will be useful, but WITHOUT ANY WARRANTY, - including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - ========================================================================*/ - #ifndef __CMVISION_TYPES_H__ #define __CMVISION_TYPES_H__ +/*! @file +* @brief Base types for #CMVision +* @author James R. Bruce, School of Computer Science, Carnegie Mellon University +* +* Licensed under the GNU GPL version 2 +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.7 $ +* $State: Exp $ +* $Date: 2007/08/14 18:24:07 $ +*/ + #include "colors.h" namespace CMVision{ diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/cmvision.h ./Vision/cmvision.h --- ../Tekkotsu_3.0/Vision/cmvision.h 2003-01-23 13:14:11.000000000 -0500 +++ ./Vision/cmvision.h 2007-08-14 14:24:07.000000000 -0400 @@ -1,29 +1,43 @@ -/*======================================================================== - cmvision.h : Main user include file for CMVision2 - ------------------------------------------------------------------------ - Copyright (C) 1999-2002 James R. Bruce - School of Computer Science, Carnegie Mellon University - ------------------------------------------------------------------------ - This software is distributed under the GNU General Public License, - version 2. If you do not have a copy of this licence, visit - www.gnu.org, or write: Free Software Foundation, 59 Temple Place, - Suite 330 Boston, MA 02111-1307 USA. This program is distributed - in the hope that it will be useful, but WITHOUT ANY WARRANTY, - including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - ========================================================================*/ - #ifndef __CMVISION_H__ #define __CMVISION_H__ +//! For more information on the CMVision package, visit http://www.cs.cmu.edu/~jbruce/cmvision/ +/*! + ======================================================================== + Copyright (C) 1999-2002 James R. Bruce + School of Computer Science, Carnegie Mellon University + ------------------------------------------------------------------------ + This software is distributed under the GNU General Public License, + version 2. If you do not have a copy of this licence, visit + www.gnu.org, or write: Free Software Foundation, 59 Temple Place, + Suite 330 Boston, MA 02111-1307 USA. This program is distributed + in the hope that it will be useful, but WITHOUT ANY WARRANTY, + including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. + ======================================================================== +*/ +namespace CMVision {} + #include #include #include -//#include "Shared/Util.h" #include "colors.h" #include "cmv_types.h" #include "cmv_threshold.h" #include "cmv_region.h" +/*! @file +* @brief Main user include file for #CMVision +* @author James R. Bruce, School of Computer Science, Carnegie Mellon University +* +* Licensed under the GNU GPL version 2 +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.4 $ +* $State: Exp $ +* $Date: 2007/08/14 18:24:07 $ +*/ + #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/colors.cc ./Vision/colors.cc --- ../Tekkotsu_3.0/Vision/colors.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Vision/colors.cc 2006-11-03 04:20:46.000000000 -0500 @@ -0,0 +1,19 @@ +#include "Vision/colors.h" + +//! displays an rgb value in the form '[r,g,b]' +std::ostream& operator<<(std::ostream &os, const rgb &rgbval) { + os << "[" << (unsigned int)rgbval.red + << "," << (unsigned int)rgbval.green + << "," << (unsigned int)rgbval.blue + << "]"; + return os; +} + +//! returns @a rgbval in the form 'r g b' +std::string toString(const rgb &rgbval) { + char buff[15]; + snprintf(buff,15,"%d %d %d",rgbval.red,rgbval.green,rgbval.blue); + return buff; +} + + diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/colors.h ./Vision/colors.h --- ../Tekkotsu_3.0/Vision/colors.h 2006-01-17 15:10:03.000000000 -0500 +++ ./Vision/colors.h 2007-08-14 14:24:07.000000000 -0400 @@ -1,21 +1,20 @@ -/*======================================================================== - colors.h : Color definitions for CMVision2 and the Simple Image class - ------------------------------------------------------------------------ - Copyright (C) 1999-2002 James R. Bruce - School of Computer Science, Carnegie Mellon University - ------------------------------------------------------------------------ - This software is distributed under the GNU General Public License, - version 2. If you do not have a copy of this licence, visit - www.gnu.org, or write: Free Software Foundation, 59 Temple Place, - Suite 330 Boston, MA 02111-1307 USA. This program is distributed - in the hope that it will be useful, but WITHOUT ANY WARRANTY, - including MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - ========================================================================*/ - #ifndef __COLORS_H__ #define __COLORS_H__ -#define RGB_COLOR_NAMES +/*! @file +* @brief Color definitions for #CMVision +* @author James R. Bruce, School of Computer Science, Carnegie Mellon University +* +* Licensed under the GNU GPL version 2 +* +* $Author: ejt $ +* $Name: tekkotsu-4_0 $ +* $Revision: 1.13 $ +* $State: Exp $ +* $Date: 2007/08/14 18:24:07 $ +*/ + +typedef unsigned int color_index; //==== Color Classes =================================================// namespace CMVision{ @@ -128,35 +127,10 @@ }; #endif +//==== converting rgb to string +#include +#include +std::ostream& operator<<(std::ostream &os, const rgb &rgbval); +std::string toString(const rgb &rgbval); -//==== Color Names ===================================================// - -#ifdef RGB_COLOR_NAMES -namespace Rgb{ -/* const rgb Black = { 0, 0, 0}; */ -/* const rgb Blue = { 0,128,255}; */ -/* const rgb Green = { 0,128, 0}; */ -/* const rgb Orange = {255,128, 0}; */ -/* const rgb Bgreen = { 0,255, 0}; */ -/* const rgb Purple = {128, 0,255}; */ -/* const rgb Red = {255, 0, 0}; */ -/* const rgb Pink = {255,128,224}; */ -/* const rgb Yellow = {255,255, 0}; */ -/* const rgb Gray = {200,200,200}; */ -/* const rgb Skin = {150,100, 0}; */ - -/* const rgb Black(0, 0, 0); */ -/* const rgb Blue(0,128,255); */ -/* const rgb Green( 0,128, 0); */ -/* const rgb Orange(255,128, 0); */ -/* const rgb Bgreen(0,255, 0); */ -/* const rgb Purple(128, 0,255); */ -/* const rgb Red(255, 0, 0); */ -/* const rgb Pink(255,128,224); */ -/* const rgb Yellow(255,255, 0); */ -/* const rgb Gray(200,200,200); */ -/* const rgb Skin(150,100, 0); */ -} - -#endif #endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/LGmixin.cc ./Wireless/LGmixin.cc --- ../Tekkotsu_3.0/Wireless/LGmixin.cc 2006-04-26 17:46:59.000000000 -0400 +++ ./Wireless/LGmixin.cc 2007-11-09 11:30:07.000000000 -0500 @@ -1,15 +1,13 @@ +#include "LGmixin.h" +#include "Shared/ProjectInterface.h" +#include "Vision/JPEGGenerator.h" + #include #include #include #include #include -#include "DualCoding/Sketch.h" -#include "Shared/ProjectInterface.h" -#include "Vision/JPEGGenerator.h" - -#include "LGmixin.h" - using namespace std; unsigned int LGmixin::instanceCount = 0; @@ -25,7 +23,7 @@ } theOne=this; - LGsock = wireless->socket(SocketNS::SOCK_STREAM, 1024, LGbufferSize); + LGsock = wireless->socket(Socket::SOCK_STREAM, 1024, LGbufferSize); wireless->setDaemon(LGsock, false); wireless->listen(LGsock, LGport); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/LGmixin.h ./Wireless/LGmixin.h --- ../Tekkotsu_3.0/Wireless/LGmixin.h 2006-09-22 12:59:26.000000000 -0400 +++ ./Wireless/LGmixin.h 2007-11-09 11:30:08.000000000 -0500 @@ -3,11 +3,7 @@ #define INCLUDED_LGmixin_h_ #include "Wireless/Wireless.h" - -namespace DualCoding { - typedef unsigned char uchar; - template class Sketch; -} +#include "DualCoding/Sketch.h" //! Mix-in for the BehaviorBase or StateNode class to give access to Looking Glass variables. class LGmixin { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/Socket.cc ./Wireless/Socket.cc --- ../Tekkotsu_3.0/Wireless/Socket.cc 2006-07-03 21:36:46.000000000 -0400 +++ ./Wireless/Socket.cc 2007-05-21 16:51:21.000000000 -0400 @@ -129,7 +129,7 @@ if ( ::setsockopt ( endpoint, SOL_SOCKET, SO_REUSEADDR, ( const char* ) &on, sizeof ( on ) ) == -1 ) { perror("Socket::init(): SO_REUSEADDR setsockopt"); } - if(trType==SocketNS::SOCK_DGRAM) { + if(trType==Socket::SOCK_DGRAM) { if ( ::setsockopt ( endpoint, SOL_SOCKET, SO_BROADCAST, ( const char* ) &on, sizeof ( on ) ) == -1 ) { perror("Socket::init(): SO_BROADCAST setsockopt"); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/Socket.h ./Wireless/Socket.h --- ../Tekkotsu_3.0/Wireless/Socket.h 2006-10-03 18:32:49.000000000 -0400 +++ ./Wireless/Socket.h 2007-11-10 17:58:11.000000000 -0500 @@ -6,57 +6,53 @@ # include # include #else +# include # include +typedef unsigned char byte; #endif #include #include #include -//! holds socket enumerations and constants -namespace SocketNS { - +class SocketListener; + +// Sigh... I hate when people define constants via macros... #ifdef PLATFORM_APERIOS - const int _SYS_SOCK_STREAM=1; //!< aperios doesn't provide SOCK_STREAM, so we will initialize them to these values - const int _SYS_SOCK_DGRAM=2; //!< aperios doesn't provide SOCK_DGRAM, so we will initialize them to these values -#else - //this is why you shouldn't use #define to declare constant values... grrr - const int _SYS_SOCK_STREAM=SOCK_STREAM; - const int _SYS_SOCK_DGRAM=SOCK_DGRAM; -# ifdef SOCK_STREAM -# undef SOCK_STREAM -# endif -# ifdef SOCK_DGRAM -# undef SOCK_DGRAM -# endif -#endif - //! Specifies transport type. TCP is usually a good idea - enum TransportType_t { - SOCK_STREAM=_SYS_SOCK_STREAM, //!< TCP: guaranteed delivery, higher overhead - SOCK_DGRAM=_SYS_SOCK_DGRAM //!< UDP: no guarantees, low overhead - }; +// no socket stuff at all, define it ourselves! +enum { + SOCK_STREAM, //!< aperios doesn't provide SOCK_STREAM, so we will initialize them to these values + SOCK_DGRAM //!< aperios doesn't provide SOCK_DGRAM, so we will initialize them to these values +}; - //! Internal TCP/UDP Connection State - enum ConnectionState { - CONNECTION_CLOSED, - CONNECTION_CONNECTING, - CONNECTION_CONNECTED, - CONNECTION_LISTENING, - CONNECTION_CLOSING, - CONNECTION_ERROR - }; +#elif !defined(__DOXYGEN__) - //! Chooses between blocking and non-blocking Wireless Input, Output. Blocking wireless output from the main process will affect the performance of the Aibo, and should only be used for debugging purposes - enum FlushType_t { - FLUSH_NONBLOCKING=0, //!< Writes and Reads return immediately, and are processed by another process, so Main can continue to run. Non-blocking reads require specifying a callback function to handle data received - FLUSH_BLOCKING //!< Blocking writes are a good idea for debugging - a blocking write will be transmitted before execution continues to the next statement. Blocking reads should be avoided, since they'll cause a significant slow down in the main process - }; +// some platforms give both a 'real' definition and a macro of the same name... need to detect that +#define doTestSelfRef(foo) defined(x##foo) +#define testSelfRef(foo) doTestSelfRef(foo) -}; +#define xSOCK_STREAM +#if defined(SOCK_STREAM) && !testSelfRef(SOCK_STREAM) +// looks like a macro-only definition, reset it +enum { _SYS_SOCK_STREAM=SOCK_STREAM }; +#undef SOCK_STREAM +enum { SOCK_STREAM=_SYS_SOCK_STREAM }; +#define SOCK_STREAM SOCK_STREAM +#endif +#undef xSOCK_STREAM -using namespace SocketNS; +#define xSOCK_DGRAM +#if defined(SOCK_DGRAM) && !testSelfRef(SOCK_DGRAM) +// looks like a macro-only definition, reset it +enum { _SYS_SOCK_DGRAM=SOCK_DGRAM }; +#undef SOCK_DGRAM +enum { SOCK_DGRAM=_SYS_SOCK_DGRAM }; +#define SOCK_DGRAM SOCK_DGRAM +#endif +#undef xSOCK_DGRAM + +#undef testSelfRef +#undef doTestSelfRef -#ifndef PLATFORM_APERIOS - typedef unsigned char byte; #endif //! Tekkotsu wireless Socket class @@ -79,6 +75,28 @@ public: int sock; //!< unique non-negative integer representing socket. Serves as index into socket Objects array + //! Specifies transport type. TCP is usually a good idea + enum TransportType_t { + SOCK_STREAM=::SOCK_STREAM, //!< TCP: guaranteed delivery, higher overhead + SOCK_DGRAM=::SOCK_DGRAM //!< UDP: no guarantees, low overhead + }; + + //! Internal TCP/UDP Connection State + enum ConnectionState { + CONNECTION_CLOSED, + CONNECTION_CONNECTING, + CONNECTION_CONNECTED, + CONNECTION_LISTENING, + CONNECTION_CLOSING, + CONNECTION_ERROR + }; + + //! Chooses between blocking and non-blocking Wireless Input, Output. Blocking wireless output from the main process will affect the performance of the Aibo, and should only be used for debugging purposes + enum FlushType_t { + FLUSH_NONBLOCKING=0, //!< Writes and Reads return immediately, and are processed by another process, so Main can continue to run. Non-blocking reads require specifying a callback function to handle data received + FLUSH_BLOCKING //!< Blocking writes are a good idea for debugging - a blocking write will be transmitted before execution continues to the next statement. Blocking reads should be avoided, since they'll cause a significant slow down in the main process + }; + public: //! constructor explicit Socket(int sockn) @@ -88,7 +106,7 @@ tx(false), rx(false), sendBuffer(), sendData(NULL), writeData(NULL), recvBuffer(), recvData(NULL), readData(NULL), server_port(0), rcvcbckfn(NULL), peer_addr(-1), peer_port(-1), textForward(false), textForwardBuf(NULL), - forwardSock(NULL), daemon(false) + forwardSock(NULL), daemon(false), sckListener(NULL) { #ifndef PLATFORM_APERIOS endpoint=-1; @@ -267,7 +285,8 @@ Socket * forwardSock; //!< if non-NULL, output will be sent to this socket if the current socket is not otherwise connected (overrides #textForward) bool daemon; //!< if true, the socket will automatically be reopened after any closure (manual or otherwise) - + + SocketListener *sckListener; //!< if non-null, class based callback interface to provide notification when new data is available for reading protected: Socket(const Socket&); //!< copy constructor, don't call Socket& operator= (const Socket&); //!< assignment operator, don't call diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/SocketListener.h ./Wireless/SocketListener.h --- ../Tekkotsu_3.0/Wireless/SocketListener.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Wireless/SocketListener.h 2007-11-10 17:58:11.000000000 -0500 @@ -0,0 +1,15 @@ +#ifndef SOCKETLISTENER_H_ +#define SOCKETLISTENER_H_ + +//! interface for notifications from Wireless +class SocketListener { +public: + //! destructor (just to satisfy compiler warning that we do indeed intend to use this as a base class) + virtual ~SocketListener() {} + + //! called by wireless whenever new data is available on the Socket this was registered with + /*! @see Wireless::setReceiver() */ + virtual int processData(char *data, int bytes) = 0; +}; + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/Wireless.cc ./Wireless/Wireless.cc --- ../Tekkotsu_3.0/Wireless/Wireless.cc 2006-06-26 12:24:17.000000000 -0400 +++ ./Wireless/Wireless.cc 2007-10-16 13:37:22.000000000 -0400 @@ -3,6 +3,8 @@ #include #include "Shared/ProjectInterface.h" +#include "SocketListener.h" + Wireless *wireless=NULL; #ifdef PLATFORM_APERIOS @@ -14,7 +16,6 @@ # include # include "aperios/MMCombo/entry.h" -using namespace SocketNS; using namespace std; Wireless::Wireless () @@ -43,12 +44,12 @@ } } -Socket* Wireless::socket(TransportType_t ttype) +Socket* Wireless::socket(Socket::TransportType_t ttype) { return socket(ttype, WIRELESS_DEF_RECV_SIZE, WIRELESS_DEF_SEND_SIZE); } -Socket* Wireless::socket(TransportType_t ttype, int recvsize, int sendsize) +Socket* Wireless::socket(Socket::TransportType_t ttype, int recvsize, int sendsize) { if (freeSockets.empty() || (recvsize + sendsize) <= 256) return sockets[0]; @@ -88,12 +89,12 @@ int Wireless::listen(int sock, int port) { if ( port <= 0 || port >= 65535 || sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL - || sockets[sock]->state != CONNECTION_CLOSED )return -1; + || sockets[sock]->state != Socket::CONNECTION_CLOSED )return -1; sockets[sock]->server_port = port; sockets[sock]->init(); - if (sockets[sock]->trType==SocketNS::SOCK_STREAM) { + if (sockets[sock]->trType==Socket::SOCK_STREAM) { // create endpoint antEnvCreateEndpointMsg tcpCreateMsg( EndpointType_TCP, ( sockets[sock]->recvBufSize + sockets[sock]->sendBufSize ) * 3 ); tcpCreateMsg.Call( ipstackRef, sizeof( tcpCreateMsg ) ); @@ -106,9 +107,9 @@ listenMsg.Send( ipstackRef, myOID, Extra_Entry[entryListenCont], sizeof( listenMsg ) ); - sockets[sock]->state = CONNECTION_LISTENING; + sockets[sock]->state = Socket::CONNECTION_LISTENING; return 0; - } else if (sockets[sock]->trType==SOCK_DGRAM) { + } else if (sockets[sock]->trType==Socket::SOCK_DGRAM) { // create endpoint antEnvCreateEndpointMsg udpCreateMsg( EndpointType_UDP, ( sockets[sock]->recvBufSize + sockets[sock]->sendBufSize ) * 3 ); udpCreateMsg.Call( ipstackRef, sizeof( udpCreateMsg ) ); @@ -120,7 +121,7 @@ bindMsg.Call( ipstackRef, sizeof( bindMsg ) ); bindMsg.continuation = ( void * ) sock; - sockets[sock]->state = CONNECTION_CONNECTING; + sockets[sock]->state = Socket::CONNECTION_CONNECTING; receive( sock ); @@ -137,10 +138,10 @@ int Wireless::connect( int sock, const char * ipaddr, int port ) { if ( port <= 0 || port >= 65535 || sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL - || ( sockets[sock]->trType == SOCK_STREAM && sockets[sock]->state != CONNECTION_CLOSED ) ) return -1; + || ( sockets[sock]->trType == Socket::SOCK_STREAM && sockets[sock]->state != Socket::CONNECTION_CLOSED ) ) return -1; sockets[sock]->init(); - if (sockets[sock]->trType==SOCK_STREAM) { + if (sockets[sock]->trType==Socket::SOCK_STREAM) { // create endpoint antEnvCreateEndpointMsg tcpCreateMsg( EndpointType_TCP, ( sockets[sock]->recvBufSize + sockets[sock]->sendBufSize ) * 3 ); tcpCreateMsg.Call( ipstackRef, sizeof( tcpCreateMsg ) ); @@ -155,11 +156,11 @@ sockets[sock]->peer_addr=connectMsg.fAddress.Address(); sockets[sock]->peer_port=connectMsg.fPort; - sockets[sock]->state = CONNECTION_CONNECTING; + sockets[sock]->state = Socket::CONNECTION_CONNECTING; return 0; } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { // connect UDPEndpointConnectMsg connectMsg( sockets[sock]->endpoint, ipaddr, port ); @@ -170,7 +171,7 @@ sockets[sock]->peer_addr=connectMsg.address.Address(); sockets[sock]->peer_port=connectMsg.port; - sockets[sock]->state = CONNECTION_CONNECTED; + sockets[sock]->state = Socket::CONNECTION_CONNECTED; //std::cout << "Sock " << sock << " connected via UDP to IP " << ipaddr << " port " << port << std::flush << std::endl; return 0; @@ -189,13 +190,13 @@ antEnvMsg * Msg = ( antEnvMsg * ) msg; int sock = ( int )( Msg->continuation ); - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointListenMsg * listenMsg = ( TCPEndpointListenMsg * ) antEnvMsg::Receive( msg ); if ( listenMsg->error != TCP_SUCCESS ) { - sockets[sock]->state = CONNECTION_ERROR; + sockets[sock]->state = Socket::CONNECTION_ERROR; // no use recycling since its a resource issue return; @@ -203,7 +204,7 @@ sockets[sock]->peer_addr=listenMsg->fAddress.Address(); sockets[sock]->peer_port=listenMsg->fPort; - sockets[sock]->state = CONNECTION_CONNECTED; + sockets[sock]->state = Socket::CONNECTION_CONNECTED; //sockets[sock]->local_ipaddr = listenMsg->lAddress.Address(); //cout << "Listen set lip: " << local_ipaddr << endl; receive( sock ); @@ -225,16 +226,16 @@ antEnvMsg * Msg = ( antEnvMsg * ) msg; int sock = ( int )( Msg->continuation ); - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointConnectMsg * connectMsg = ( TCPEndpointConnectMsg * ) antEnvMsg::Receive( msg ); if ( connectMsg->error != TCP_SUCCESS ) { - sockets[sock]->state = CONNECTION_ERROR; + sockets[sock]->state = Socket::CONNECTION_ERROR; return; } - sockets[sock]->state = CONNECTION_CONNECTED; + sockets[sock]->state = Socket::CONNECTION_CONNECTED; //sockets[sock]->local_ipaddr = connectMsg->lAddress.Address(); //cout << "Connect set lip: " << local_ipaddr << endl; receive( sock ); @@ -257,11 +258,11 @@ int sock = (int)bindMsg->continuation; if (bindMsg->error != UDP_SUCCESS) { - sockets[sock]->state = CONNECTION_ERROR; + sockets[sock]->state = Socket::CONNECTION_ERROR; return; } - sockets[sock]->state = CONNECTION_CONNECTED; + sockets[sock]->state = Socket::CONNECTION_CONNECTED; /* if(bindMsg->address.Address()!=0) { //sockets[sock]->local_ipaddr = bindMsg->address.Address(); //cout << "Bind set lip: " << local_ipaddr << endl; @@ -281,10 +282,10 @@ void Wireless::send(int sock) { - if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL || sockets[sock]->state != CONNECTION_CONNECTED + if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL || sockets[sock]->state != Socket::CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 ) return; - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointSendMsg sendMsg( sockets[sock]->endpoint, sockets[sock]->sendData, sockets[sock]->sendSize ); sendMsg.continuation = ( void * ) sock; @@ -294,7 +295,7 @@ sockets[sock]->sendSize = 0; } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { UDPEndpointSendMsg sendMsg( sockets[sock]->endpoint, sockets[sock]->sendData, sockets[sock]->sendSize ); @@ -314,25 +315,25 @@ antEnvMsg * Msg = ( antEnvMsg * ) msg; int sock = ( int )( Msg->continuation ); - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointSendMsg * sendMsg = ( TCPEndpointSendMsg * ) antEnvMsg::Receive( msg ); sockets[sock]->tx = false; if ( sendMsg->error != TCP_SUCCESS ) { - sockets[sock]->state = CONNECTION_ERROR; + sockets[sock]->state = Socket::CONNECTION_ERROR; close( sock ); return; } } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { UDPEndpointSendMsg * sendMsg = ( UDPEndpointSendMsg * ) antEnvMsg::Receive( msg ); sockets[sock]->tx = false; if ( sendMsg->error != UDP_SUCCESS ) { - sockets[sock]->state = CONNECTION_ERROR; + sockets[sock]->state = Socket::CONNECTION_ERROR; close( sock ); return; } @@ -357,10 +358,10 @@ void Wireless::blockingSend(int sock) { - if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL || sockets[sock]->state != CONNECTION_CONNECTED + if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL || sockets[sock]->state != Socket::CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 ) return; - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointSendMsg sendMsg( sockets[sock]->endpoint, sockets[sock]->sendData, sockets[sock]->sendSize ); sendMsg.continuation = ( void * ) sock; @@ -382,21 +383,28 @@ sockets[sock]->rcvcbckfn=rcvcbckfn; } +void Wireless::setReceiver(int sock, SocketListener *listener) { + if (sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL) + return; + + sockets[sock]->sckListener = listener; +} + void Wireless::receive(int sock) { if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL - || ( sockets[sock]->trType == SOCK_STREAM && sockets[sock]->state != CONNECTION_CONNECTED ) ) + || ( sockets[sock]->trType == Socket::SOCK_STREAM && sockets[sock]->state != Socket::CONNECTION_CONNECTED ) ) return; - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointReceiveMsg receiveMsg( sockets[sock]->endpoint, sockets[sock]->recvData, 1, sockets[sock]->recvBufSize ); receiveMsg.continuation = ( void * ) sock; receiveMsg.Send( ipstackRef, myOID, Extra_Entry[entryReceiveCont], sizeof( receiveMsg ) ); } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { UDPEndpointReceiveMsg receiveMsg( sockets[sock]->endpoint, sockets[sock]->recvData, sockets[sock]->recvBufSize ); receiveMsg.continuation = ( void * ) sock; @@ -410,18 +418,18 @@ Wireless::receive(int sock, int (*rcvcbckfn) (char*, int) ) { if (sock<=0 || sock>=WIRELESS_MAX_SOCKETS || sockets[sock]==NULL - || sockets[sock]->state != CONNECTION_CONNECTED) return; + || sockets[sock]->state != Socket::CONNECTION_CONNECTED) return; sockets[sock]->rcvcbckfn = rcvcbckfn; - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointReceiveMsg receiveMsg( sockets[sock]->endpoint, sockets[sock]->recvData, 1, sockets[sock]->recvBufSize ); receiveMsg.continuation = ( void * ) sock; receiveMsg.Send( ipstackRef, myOID, Extra_Entry[entryReceiveCont], sizeof( receiveMsg ) ); } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { UDPEndpointReceiveMsg receiveMsg( sockets[sock]->endpoint, sockets[sock]->recvData, sockets[sock]->recvBufSize ); receiveMsg.continuation = ( void * ) sock; @@ -440,27 +448,34 @@ int sock = ( int )( Msg->continuation ); if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL - || ( sockets[sock]->state != CONNECTION_CONNECTED && sockets[sock]->state != CONNECTION_CONNECTING ) ) + || ( sockets[sock]->state != Socket::CONNECTION_CONNECTED && sockets[sock]->state != Socket::CONNECTION_CONNECTING ) ) return; - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointReceiveMsg * receiveMsg = ( TCPEndpointReceiveMsg * ) antEnvMsg::Receive( msg ); if ( receiveMsg->error != TCP_SUCCESS ) { - sockets[sock]->state = CONNECTION_ERROR; + sockets[sock]->state = Socket::CONNECTION_ERROR; close( sock ); return; } sockets[sock]->recvSize = receiveMsg->sizeMin; - if ( sockets[sock]->rcvcbckfn != NULL ) - sockets[sock]->rcvcbckfn( ( char * ) sockets[sock]->recvData, sockets[sock]->recvSize ); + + if (sockets[sock]->sckListener != NULL) { + sockets[sock]->sckListener->processData((char *)sockets[sock]->recvData, + sockets[sock]->recvSize); + + } else if (sockets[sock]->rcvcbckfn != NULL) { + sockets[sock]->rcvcbckfn((char *)sockets[sock]->recvData, + sockets[sock]->recvSize); + } sockets[sock]->recvSize = 0; } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { UDPEndpointReceiveMsg * receiveMsg; receiveMsg = ( UDPEndpointReceiveMsg * ) antEnvMsg::Receive( msg ); @@ -475,22 +490,22 @@ sockets[sock]->peer_addr=receiveMsg->address.Address(); sockets[sock]->peer_port=receiveMsg->port; - if ( !strncmp( "connection request", ( char * ) sockets[sock]->recvData, 18 ) ) - { - // clear this message from the receiving buffer - sockets[sock]->recvData += sockets[sock]->recvSize; - - if ( sockets[sock]->state != CONNECTION_CONNECTED ) - { - char caller[14]; - receiveMsg->address.GetAsString( caller ); - connect( sock, caller, receiveMsg->port ); - } + if ( !strncmp( "connection request", ( char * ) sockets[sock]->recvData, 18 ) ) { + // clear this message from the receiving buffer + sockets[sock]->recvData += sockets[sock]->recvSize; + + if ( sockets[sock]->state != Socket::CONNECTION_CONNECTED ) { + char caller[14]; + receiveMsg->address.GetAsString( caller ); + connect( sock, caller, receiveMsg->port ); } - - else if ( sockets[sock]->rcvcbckfn != NULL ) + + } else if (sockets[sock]->sckListener != NULL) { + sockets[sock]->sckListener->processData((char *)sockets[sock]->recvData, sockets[sock]->recvSize); + + } else if ( sockets[sock]->rcvcbckfn != NULL ) sockets[sock]->rcvcbckfn( ( char * ) sockets[sock]->recvData, sockets[sock]->recvSize ); - + } sockets[sock]->recvSize = 0; @@ -511,8 +526,8 @@ void Wireless::close(int sock) { - if (sockets[sock]->state == CONNECTION_CLOSED || - sockets[sock]->state == CONNECTION_CLOSING) return; + if (sockets[sock]->state == Socket::CONNECTION_CLOSED || + sockets[sock]->state == Socket::CONNECTION_CLOSING) return; if (!(sockets[sock]->server_port>0 && sockets[sock]->daemon)) { sockets[sock]->recvBuffer.UnMap(); @@ -523,14 +538,14 @@ sendBufferMsg.Call(ipstackRef, sizeof(antEnvDestroySharedBufferMsg)); } - if ( sockets[sock]->trType == SOCK_STREAM ) + if ( sockets[sock]->trType == Socket::SOCK_STREAM ) { TCPEndpointCloseMsg closeMsg( sockets[sock]->endpoint ); closeMsg.continuation = ( void * ) sock; closeMsg.Send( ipstackRef, myOID, Extra_Entry[entryCloseCont], sizeof( closeMsg ) ); } - else if ( sockets[sock]->trType == SOCK_DGRAM ) + else if ( sockets[sock]->trType == Socket::SOCK_DGRAM ) { UDPEndpointCloseMsg closeMsg( sockets[sock]->endpoint ); closeMsg.continuation = ( void * ) sock; @@ -539,7 +554,7 @@ sockets[sock]->peer_addr=sockets[sock]->peer_port=-1; - sockets[sock]->state = CONNECTION_CLOSING; + sockets[sock]->state = Socket::CONNECTION_CLOSING; } uint32 @@ -574,7 +589,7 @@ if ( sockets[sock] == NULL ) return; - sockets[sock]->state = CONNECTION_CLOSED; + sockets[sock]->state = Socket::CONNECTION_CLOSED; sockets[sock]->peer_addr=sockets[sock]->peer_port=-1; if ( sockets[sock]->server_port > 0 && sockets[sock]->daemon ) { @@ -663,6 +678,10 @@ sockets[sock]->rcvcbckfn=rcvcbckfn; } +void Wireless::setReceiver(int sock, SocketListener *listener) { + sockets[sock]->sckListener = listener; +} + void Wireless::close(int sock) { MarkScope l(getLock()); if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL) @@ -695,7 +714,7 @@ int Wireless::connect(int sock, const char* ipaddr, int port) { MarkScope l(getLock()); if ( port <= 0 || port >= 65535 || sock <= 0 || sock >= WIRELESS_MAX_SOCKETS - || sockets[sock] == NULL || sockets[sock]->state != CONNECTION_CLOSED && sockets[sock]->trType!=SocketNS::SOCK_DGRAM ) + || sockets[sock] == NULL || sockets[sock]->state != Socket::CONNECTION_CLOSED && sockets[sock]->trType!=Socket::SOCK_DGRAM ) return -1; if(sockets[sock]->endpoint==-1) @@ -722,9 +741,9 @@ int status = ::connect ( endpoint, ( sockaddr * ) &m_addr, sizeof ( m_addr ) ); if ( status == 0 ) - sockets[sock]->state=CONNECTION_CONNECTED; + sockets[sock]->state=Socket::CONNECTION_CONNECTED; else if(errno==EINPROGRESS) - sockets[sock]->state=CONNECTION_CONNECTING; + sockets[sock]->state=Socket::CONNECTION_CONNECTING; else { perror("Wireless::connect(): connect"); return -1; @@ -740,7 +759,7 @@ int Wireless::listen(int sock, int port) { MarkScope l(getLock()); if ( port <= 0 || port >= 65535 || sock <= 0 || sock >= WIRELESS_MAX_SOCKETS - || sockets[sock] == NULL || sockets[sock]->state != CONNECTION_CLOSED ) + || sockets[sock] == NULL || sockets[sock]->state != Socket::CONNECTION_CLOSED ) return -1; sockets[sock]->server_port = port; sockets[sock]->init(); @@ -757,23 +776,23 @@ perror("Wireless::listen: bind"); return -1; } - if(sockets[sock]->trType==SocketNS::SOCK_STREAM) { + if(sockets[sock]->trType==Socket::SOCK_STREAM) { int listen_return = ::listen ( endpoint, MAXCONNECTIONS ); if ( listen_return == -1 ) { perror("Wireless::listen: listen"); return -1; } } - sockets[sock]->state = CONNECTION_LISTENING; + sockets[sock]->state = Socket::CONNECTION_LISTENING; //this will allow sock to be added to rfds so we can tell when a connection is available wakeup(); return 0; } -Socket* Wireless::socket(TransportType_t ttype) { +Socket* Wireless::socket(Socket::TransportType_t ttype) { return socket(ttype, WIRELESS_DEF_RECV_SIZE, WIRELESS_DEF_SEND_SIZE); } -Socket* Wireless::socket(TransportType_t ttype, int recvsize, int sendsize) { +Socket* Wireless::socket(Socket::TransportType_t ttype, int recvsize, int sendsize) { MarkScope l(getLock()); if (freeSockets.empty() || (recvsize + sendsize) <= 256) return sockets[0]; @@ -824,7 +843,7 @@ { MarkScope l(getLock()); if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL - || sockets[sock]->state != CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 ) + || sockets[sock]->state != Socket::CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 ) return; //we could defer all sending to the poll, but let's give a shot at sending it out right away to reduce latency @@ -859,7 +878,7 @@ { MarkScope l(getLock()); if ( sock <= 0 || sock >= WIRELESS_MAX_SOCKETS || sockets[sock] == NULL - || sockets[sock]->state != CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 ) + || sockets[sock]->state != Socket::CONNECTION_CONNECTED || sockets[sock]->sendSize <= 0 ) return; while(sockets[sock]->sentSizesendSize) { @@ -909,9 +928,9 @@ cerr << "ERROR Wireless::pollSetup() encountered bad endpoint " << *it << endl; continue; } - if(sockets[*it]->state!=CONNECTION_CLOSED && sockets[*it]->state!=CONNECTION_ERROR) + if(sockets[*it]->state!=Socket::CONNECTION_CLOSED && sockets[*it]->state!=Socket::CONNECTION_ERROR) FD_SET(sockets[*it]->endpoint, &rfds); - if(sockets[*it]->state==CONNECTION_CONNECTING || sockets[*it]->tx) + if(sockets[*it]->state==Socket::CONNECTION_CONNECTING || sockets[*it]->tx) FD_SET(sockets[*it]->endpoint, &wfds); FD_SET(sockets[*it]->endpoint, &efds); if(sockets[*it]->endpoint>fdsMax) @@ -956,12 +975,12 @@ int s=sockets[*it]->endpoint; if(FD_ISSET(s,&rfds)) { //cout << *it << " set in read" << endl; - if(sockets[*it]->state==CONNECTION_CONNECTING) { + if(sockets[*it]->state==Socket::CONNECTION_CONNECTING) { //cout << "Wireless::pollProcess(): read set on connecting" << endl; - sockets[*it]->state=CONNECTION_CONNECTED; + sockets[*it]->state=Socket::CONNECTION_CONNECTED; } - if(sockets[*it]->state==CONNECTION_LISTENING) { - if(sockets[*it]->trType==SocketNS::SOCK_STREAM) { + if(sockets[*it]->state==Socket::CONNECTION_LISTENING) { + if(sockets[*it]->trType==Socket::SOCK_STREAM) { sockaddr_in m_addr; socklen_t addrlen=sizeof(m_addr); int n=accept(s,(sockaddr*)&m_addr,&addrlen); @@ -976,7 +995,7 @@ if(::close(s)==-1) perror("Wireless::pollProcess(): close"); s=sockets[*it]->endpoint=n; - sockets[*it]->state=CONNECTION_CONNECTED; + sockets[*it]->state=Socket::CONNECTION_CONNECTED; //cout << "Accepted connection" << endl; } else { //cout << "UDP accept" << endl; @@ -1003,8 +1022,19 @@ //cout << "Read " << sockets[*it]->recvSize << " bytes " << sockets[*it]->rcvcbckfn << endl; if ( !strncmp( "connection request", ( char * ) sockets[*it]->recvData, 18 ) ) { // clear this message from the receiving buffer - if ( sockets[*it]->state != CONNECTION_CONNECTED ) + if ( sockets[*it]->state != Socket::CONNECTION_CONNECTED ) connect( *it, sockets[*it]->getPeerAddressAsString().c_str(), sockets[*it]->getPeerPort() ); + } else if (sockets[*it]->sckListener != NULL) { + try { + sockets[*it]->sckListener->processData((char *)sockets[*it]->recvData, + sockets[*it]->recvSize); + } catch(const std::exception& ex) { + if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during networking received data callback",&ex)) + throw; + } catch(...) { + if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during networking received data callback",NULL)) + throw; + } } else if ( sockets[*it]->rcvcbckfn != NULL ) { try { sockets[*it]->rcvcbckfn( ( char * ) sockets[*it]->recvData, sockets[*it]->recvSize ); @@ -1019,7 +1049,7 @@ sockets[*it]->recvSize = 0; } } - } else if(sockets[*it]->state==CONNECTION_CONNECTED || sockets[*it]->state==CONNECTION_CLOSING) { + } else if(sockets[*it]->state==Socket::CONNECTION_CONNECTED || sockets[*it]->state==Socket::CONNECTION_CLOSING) { sockets[*it]->recvSize = recvfrom(s,sockets[*it]->recvData,sockets[*it]->recvBufSize,0,NULL,NULL); if(sockets[*it]->recvSize==-1) { if(errno!=EAGAIN) { //may have just completed connection, not a problem @@ -1041,7 +1071,18 @@ continue; } else { //cout << "Read " << sockets[*it]->recvSize << " bytes " << sockets[*it]->rcvcbckfn << endl; - if ( sockets[*it]->rcvcbckfn != NULL ) { + if (sockets[*it]->sckListener != NULL) { + try { + sockets[*it]->sckListener->processData((char *)sockets[*it]->recvData, + sockets[*it]->recvSize); + } catch(const std::exception& ex) { + if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during networking received data callback",&ex)) + throw; + } catch(...) { + if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during networking received data callback",NULL)) + throw; + } + } else if ( sockets[*it]->rcvcbckfn != NULL ) { try { sockets[*it]->rcvcbckfn( ( char * ) sockets[*it]->recvData, sockets[*it]->recvSize ); } catch(const std::exception& ex) { @@ -1070,9 +1111,9 @@ } if(FD_ISSET(s,&wfds)) { //cout << *it << " set in write" << endl; - if(sockets[*it]->state==CONNECTION_CONNECTING) { - sockets[*it]->state=CONNECTION_CONNECTED; - } else if(sockets[*it]->state==CONNECTION_CONNECTED) { + if(sockets[*it]->state==Socket::CONNECTION_CONNECTING) { + sockets[*it]->state=Socket::CONNECTION_CONNECTED; + } else if(sockets[*it]->state==Socket::CONNECTION_CONNECTED) { if(!sockets[*it]->tx) { //cerr << "Wireless::pollProcess(): write available on non-tx socket??" << endl; //can happen on a refused connection diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/Wireless.h ./Wireless/Wireless.h --- ../Tekkotsu_3.0/Wireless/Wireless.h 2006-09-22 12:59:26.000000000 -0400 +++ ./Wireless/Wireless.h 2007-11-11 18:57:28.000000000 -0500 @@ -10,14 +10,14 @@ #else # include "IPC/Thread.h" # include "Shared/Resource.h" -typedef unsigned long uint32; +# include +typedef uint32_t uint32; #endif #include "Socket.h" #include "DummySocket.h" #include -using namespace SocketNS; -using namespace __gnu_cxx; +class SocketListener; //! Tekkotsu wireless class /*! @@ -56,12 +56,12 @@ /*! @return pointer to Socket object created * @param ttype selects between TCP and UDP * @see WIRELESS_DEF_RECV_SIZE, WIRELESS_DEF_SEND_SIZE */ - Socket* socket(TransportType_t ttype); + Socket* socket(Socket::TransportType_t ttype); /*!@param ttype selects between TCP and UDP * @param recvsize size of input buffer * @param sendsize size of output buffer */ - Socket* socket(TransportType_t ttype, int recvsize, int sendsize); + Socket* socket(Socket::TransportType_t ttype, int recvsize, int sendsize); //@} //! The socket waits for incoming connections. @@ -73,8 +73,13 @@ //! The socket tries to connect to a specific int connect(int sock, const char* ipaddr, int port); + //! sets receiver callback for a socket - void setReceiver(int sock, int (*rcvcbckfn) (char*, int) ); + void setReceiver(int sock, int (*rcvcbckfn) (char*, int) ); + + //! sets receiver callback for a socket, this version requiring the SocketListener interface (more powerful, as this lets us tell connections apart) + void setReceiver(int sock, SocketListener *listener); + //! sets the socket to be a daemon (recycles on close) void setDaemon(int sock, bool val=true) { sockets[sock]->daemon=val; } //! sets the socket to be a daemon (recycles on close) @@ -88,10 +93,10 @@ * and read buffers does the necessary sanity checks */ bool isConnected(int sock) { - return sockets[sock]==NULL ? false : sockets[sock]->state==CONNECTION_CONNECTED; + return sockets[sock]==NULL ? false : sockets[sock]->state==Socket::CONNECTION_CONNECTED; } bool isError(int sock) { - return sockets[sock]==NULL ? false : sockets[sock]->state==CONNECTION_ERROR; + return sockets[sock]==NULL ? false : sockets[sock]->state==Socket::CONNECTION_ERROR; } bool isReady(int sock) { return !sockets[sock]->tx; } @@ -104,6 +109,10 @@ { setReceiver(sobj.sock, rcvcbckfn); } void setReceiver(Socket *sobj, int (*rcvcbckfn) (char*, int) ) { setReceiver(sobj->sock, rcvcbckfn); } + void setReceiver(Socket &sobj, SocketListener *listener) + { setReceiver(sobj.sock, listener); } + void setReceiver(Socket *sobj, SocketListener *listener) + { setReceiver(sobj->sock, listener); } void setDaemon(Socket &sobj, bool val=true) { setDaemon(sobj.sock, val); } void setDaemon(Socket *sobj, bool val=true) { setDaemon(sobj->sock, val); } bool getDaemon(Socket &sobj) { return getDaemon(sobj.sock); } diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/netstream.cc ./Wireless/netstream.cc --- ../Tekkotsu_3.0/Wireless/netstream.cc 1969-12-31 19:00:00.000000000 -0500 +++ ./Wireless/netstream.cc 2007-11-11 18:57:28.000000000 -0500 @@ -0,0 +1,84 @@ +#ifndef PLATFORM_APERIOS +#include "netstream.h" +#include + +using namespace std; + +const unsigned int IPaddr::maxHostNameLen = 256; + +IPaddr::IPaddr() : server(), ipname(), ipport(0) { Init(); } + +IPaddr::IPaddr(const ipnum_t& num) : server(), ipname(), ipport(0) { Init(); set_num(num); } + +IPaddr::IPaddr(const ipname_t& name) : server(), ipname(), ipport(0) { Init(); set_name(name); } + +IPaddr::IPaddr(const ipnum_t& num, const ipport_t& port) : server(), ipname(), ipport(0) { Init(); set_addr(num,port); } + +IPaddr::IPaddr(const ipname_t& name, const ipport_t& port) : server(), ipname(), ipport(0) { Init(); set_addr(name,port); } + +bool IPaddr::set_num(const ipnum_t& num) { + if(get_num()!=num) { + Init(); + server.sin_family = AF_INET; + server.sin_addr.s_addr = htonl(num); + server.sin_port = htons(ipport); + struct in_addr a; + a.s_addr = server.sin_addr.s_addr; + char addrname[maxHostNameLen]; + inet_ntop(AF_INET,&a,addrname,maxHostNameLen); + ipname=addrname; + } + return true; +} + +bool IPaddr::set_name(const ipname_t& name) { + Init(); + if(!isalpha(name[0])) { + // in case the string holds a dotted decimal we can convert directly + struct in_addr a; + if(inet_pton(AF_INET,name.c_str(),&a)<=0) { + cerr << "IPaddr error: inet_pton failed: " << name << endl; + return false; + } + return set_num(ntohl(a.s_addr)); + } else { + Init(); + struct hostent * data = gethostbyname(name.c_str()); + if(data == NULL) { + cerr << "IPaddr error: gethostbyname failed: " << name << endl; + return false; + } + ipname=name; + + memcpy((char *) &server.sin_addr, data->h_addr_list[0], data->h_length); + server.sin_family = data->h_addrtype; + server.sin_port = htons(ipport); + } + return true; +} + +IPaddr::ipname_t IPaddr::get_display_num() const { + struct in_addr a; + a.s_addr = server.sin_addr.s_addr; + char addrname[maxHostNameLen]; + inet_ntop(AF_INET,&a,addrname,maxHostNameLen); + return addrname; +} + +IPaddr::ipname_t IPaddr::get_rname() const { + struct in_addr a; + a.s_addr = server.sin_addr.s_addr; + struct hostent * data = gethostbyaddr((char*)&a,sizeof(a),AF_INET); + if(data==NULL) { + cerr << "IPaddr error: gethostbyaddr failed: " << ipname << endl; + return ""; + } + return data->h_name; +} + +void IPaddr::Init() { + ipname=""; + memset((char *) &server, sizeof(server), 0); +} + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Wireless/netstream.h ./Wireless/netstream.h --- ../Tekkotsu_3.0/Wireless/netstream.h 1969-12-31 19:00:00.000000000 -0500 +++ ./Wireless/netstream.h 2007-11-11 18:57:28.000000000 -0500 @@ -0,0 +1,755 @@ +#ifndef INCLUDED_netstream_h_ +#define INCLUDED_netstream_h_ + +#ifdef PLATFORM_APERIOS +#error netstream not yet supported on AIBO/Aperios +#endif + +#include +#include +#include +#include +#include +#include +#include +#include +#include + +#include +#include +//#include +#include +#include +#include +#include +#include +#include +#include +#include + +#define OTAssert(str, b) if(!b) std::cerr << "ERR " << __FILE__ << '(' << __LINE__ << "): " << str << std::endl; + +class IPaddr { +public: + typedef std::string ipname_t; + typedef unsigned int ipnum_t; + typedef unsigned short ipport_t; + const static unsigned int maxHostNameLen; + + IPaddr(); + explicit IPaddr(const ipnum_t& num); + explicit IPaddr(const ipname_t& name); + IPaddr(const ipnum_t& num, const ipport_t& port); + IPaddr(const ipname_t& name, const ipport_t& port); + virtual ~IPaddr() {} + + virtual bool set_num(const ipnum_t& num); + virtual bool set_name(const ipname_t& name); + virtual bool set_addr(const ipnum_t& num, const ipport_t& port) { return set_num(num) && set_port(port); } + virtual bool set_addr(const ipname_t& name, const ipport_t& port) { return set_name(name) && set_port(port); } + virtual bool set_port(const ipport_t& port) { ipport=port; server.sin_port=htons(port); return true; } + virtual ipnum_t get_num() const { return ntohl(server.sin_addr.s_addr); } + virtual const ipname_t& get_name() const { return ipname; } + virtual ipname_t get_display_num() const; + virtual ipname_t get_rname() const; + virtual ipport_t get_port() const { return ipport; } + + virtual const sockaddr_in& get_addr() const { return server; } +protected: + void Init(); + + struct sockaddr_in server; + ipname_t ipname; + ipport_t ipport; +}; + + +template > +class basic_netbuf : public std::basic_streambuf { +public: + // Types: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + + //Constructors/Destructors: + basic_netbuf(); + basic_netbuf(const IPaddr& addr, bool datagram=false); + basic_netbuf(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false); + basic_netbuf(size_t buf_in_size, size_t buf_out_size); + virtual ~basic_netbuf(); + + + + //basic_netbuf Functions: +public: + virtual bool open(const IPaddr& addr, bool datagram=false); + virtual bool open(const IPaddr::ipname_t& str, bool datagram=false); + virtual bool open(const IPaddr::ipname_t& ahost, unsigned int aPort, bool datagram=false) { return open(IPaddr(ahost,aPort),datagram); } + virtual bool listen(unsigned int aPort, bool datagram=false) { return listen(IPaddr(ntohl(INADDR_ANY),aPort),datagram); } + virtual bool listen(const IPaddr& addr, bool datagram=false); + virtual bool is_open() const { return (sock!=INVALID_SOCKET); } + virtual void update_status(); + virtual void close(); + virtual void reset() { close(); reconnect(); } + + virtual int adoptFD(int fd) { int old=sock; sock=fd; update_status(); return old; } + + virtual void setReconnect(bool doReconnect) { autoReconnect = doReconnect; } + virtual bool getReconnect() const { return autoReconnect; } + + virtual void setEcho(bool val = true) { is_echoing = val; } + virtual bool getEcho() { return is_echoing; } + + virtual const IPaddr& getPeerAddress() const { return peerAddress; } + virtual const IPaddr& getLocalAddress() const { return localAddress; } + +protected: + virtual void reconnect(); + static void printBuffer(const char* buf, int buflen, const char* header, const char* prefix); + void Init() { Init(def_buf_in_size, def_buf_out_size); } + void Init(size_t insize, size_t outsize); + + + +//Inherited Functions: +public: + virtual void in_sync(); //users shouldn't need to call this directly... but can if want to + virtual void out_flush(); + +protected: + using std::basic_streambuf::eback; + using std::basic_streambuf::gptr; + using std::basic_streambuf::egptr; + using std::basic_streambuf::gbump; + using std::basic_streambuf::pbase; + using std::basic_streambuf::pptr; + using std::basic_streambuf::epptr; + using std::basic_streambuf::pbump; + + // lib.streambuf.virt.get Get area: + virtual std::streamsize showmanyc(); + // virtual streamsize xsgetn(char_type* s, streamsize n); + virtual int_type underflow(); + virtual int_type uflow(); + + // lib.streambuf.virt.pback Putback: + // virtual int_type pbackfail(int_type c = traits::eof() ); + // lib.streambuf.virt.put Put area: + // virtual streamsize xsputn(const char_type* s, streamsize n); + virtual int_type overflow(int_type c = traits::eof()); + + // lib.streambuf.virt.buffer Buffer management and positioning: + // virtual _Myt basic_netbuf* setbuf(char_type* s, streamsize n); + virtual pos_type seekoff(off_type off, std::ios_base::seekdir way, std::ios_base::openmode which = std::ios_base::in | std::ios_base::out); + virtual pos_type seekpos(pos_type sp, std::ios_base::openmode which = std::ios_base::in | std::ios_base::out) { return seekoff(sp,std::ios_base::beg,which); } + virtual int sync(); + // lib.streambuf.virt.locales Locales: + // virtual void imbue(const locale &loc); + +//Data: +protected: + static const int INVALID_SOCKET=-1; + charT *buf_in, *buf_out; + bool using_buf_in, using_buf_out; + static const size_t def_buf_in_size; + static const size_t def_buf_out_size; + int sock; + bool canRead; + bool canWrite; + bool is_echoing; + bool autoReconnect; + bool sockFromServer; + + IPaddr peerAddress; + IPaddr localAddress; + IPaddr tgtAddress; + bool isDatagram; + +private: + basic_netbuf(const basic_netbuf&); // copy constructor, don't call + basic_netbuf& operator=(const basic_netbuf&); //!< assignment, don't call +}; +template +const size_t basic_netbuf::def_buf_in_size=(1<<14)-28; +template +const size_t basic_netbuf::def_buf_out_size=(1<<14)-28; + + +template > +class basic_netbuf_interface { +public: + basic_netbuf_interface() : nb() {} + basic_netbuf_interface(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram) : nb(host,port,datagram) {} + basic_netbuf_interface(const IPaddr& addr, bool datagram) : nb(addr,datagram) {} + basic_netbuf_interface(size_t buf_in_size, size_t buf_out_size) : nb(buf_in_size,buf_out_size) {} + + inline bool open(const IPaddr& addr, bool datagram=false) { return nb.open(addr,datagram); } + inline bool open(const IPaddr::ipname_t& str, bool datagram=false) { return nb.open(str,datagram); } + inline bool open(const IPaddr::ipname_t& ahost, unsigned int aPort, bool datagram=false) { return nb.open(ahost,aPort,datagram); } + inline bool listen(unsigned int aPort, bool datagram=false) { return nb.listen(aPort,datagram); } + inline bool listen(const IPaddr& addr, bool datagram=false) { return nb.listen(addr,datagram); } + + inline bool is_open() const { return nb.is_open(); } + inline void update_status() { nb.update_status(); } + + inline void close() { nb.close(); } + inline void reset() { nb.close(); nb.reconnect(); } + + inline void setReconnect(bool reconnect) { nb.setReconnect(reconnect); } + inline bool getReconnect() const { return nb.getReconnect(); } + + inline void setEcho(bool val=true) { nb.setEcho(val); } + inline bool getEcho() { return nb.getEcho(); } + + inline const IPaddr& getPeerAddress() const { return nb.getPeerAddress(); } + inline const IPaddr& getLocalAddress() const { return nb.getLocalAddress(); } + + inline basic_netbuf* rdbuf() const { return const_cast*>(&nb); } + +protected: + ~basic_netbuf_interface() {} + basic_netbuf nb; +}; + +template > +class basic_inetstream : public virtual basic_netbuf_interface, public std::basic_istream +{ +public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + // lib.ifstream.cons Constructors: + basic_inetstream() : basic_netbuf_interface(), std::basic_istream(basic_netbuf_interface::rdbuf()) {} + basic_inetstream(const IPaddr& addr, bool datagram=false) : basic_netbuf_interface(addr,datagram), std::basic_istream(basic_netbuf_interface::rdbuf()) {} + basic_inetstream(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false) : basic_netbuf_interface(host,port,datagram), std::basic_istream(basic_netbuf_interface::rdbuf()) {} + basic_inetstream(size_t buf_in_size, size_t buf_out_size) : basic_netbuf_interface(buf_in_size,buf_out_size), std::basic_istream(basic_netbuf_interface::rdbuf()) {} + using basic_netbuf_interface::rdbuf; +}; + + +template > +class basic_onetstream : public virtual basic_netbuf_interface, public std::basic_ostream +{ +public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + // lib.ifstream.cons Constructors: + basic_onetstream() : basic_netbuf_interface(), std::basic_ostream(basic_netbuf_interface::rdbuf()) {} + basic_onetstream(const IPaddr& addr, bool datagram=false) : basic_netbuf_interface(addr,datagram), std::basic_ostream(basic_netbuf_interface::rdbuf()) {} + basic_onetstream(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false) : basic_netbuf_interface(host,port,datagram), std::basic_ostream(basic_netbuf_interface::rdbuf()) {} + basic_onetstream(size_t buf_in_size, size_t buf_out_size) : basic_netbuf_interface(buf_in_size,buf_out_size) , std::basic_ostream(basic_netbuf_interface::rdbuf()){} + using basic_netbuf_interface::rdbuf; +}; + + +template > +class basic_ionetstream : public virtual basic_netbuf_interface, public std::basic_iostream +{ +public: + typedef charT char_type; + typedef typename traits::int_type int_type; + typedef typename traits::pos_type pos_type; + typedef typename traits::off_type off_type; + typedef traits traits_type; + // lib.ifstream.cons Constructors: + basic_ionetstream() : basic_netbuf_interface(), std::basic_iostream(basic_netbuf_interface::rdbuf()) {} + basic_ionetstream(const IPaddr& addr, bool datagram=false) : basic_netbuf_interface(addr,datagram), std::basic_iostream(basic_netbuf_interface::rdbuf()) {} + basic_ionetstream(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false) : basic_netbuf_interface(host,port,datagram), std::basic_iostream(basic_netbuf_interface::rdbuf()) {} + basic_ionetstream(size_t buf_in_size, size_t buf_out_size) : basic_netbuf_interface(buf_in_size,buf_out_size) , std::basic_iostream(basic_netbuf_interface::rdbuf()){} + using basic_netbuf_interface::rdbuf; +}; + +/* +template +class char_traits { +public: + typedef T char_type; + typedef int int_type; + typedef T* pos_type; + typedef unsigned int off_type; + static void copy(pos_type dst, pos_type src, off_type size) { + memcpy(dst,src,size); + } + static void move(pos_type dst, pos_type src, off_type size) { + memmove(dst,src,size); + } + static int to_int_type(T c) { return c; } + static int eof() { return EOF; } +};*/ + +typedef basic_netbuf > netbuf; +typedef basic_inetstream > inetstream; +typedef basic_onetstream > onetstream; +typedef basic_ionetstream > ionetstream; + + + + +template +basic_netbuf::basic_netbuf() + : std::basic_streambuf(), buf_in(NULL), buf_out(NULL), using_buf_in(false), using_buf_out(false), + sock(INVALID_SOCKET), canRead(false), canWrite(false), is_echoing(false), autoReconnect(false), sockFromServer(), + peerAddress(), localAddress(), tgtAddress(), isDatagram() { + Init(); +} +template +basic_netbuf::basic_netbuf(const IPaddr& addr, bool datagram) + : std::basic_streambuf(), buf_in(NULL), buf_out(NULL), using_buf_in(false), using_buf_out(false), + sock(INVALID_SOCKET), canRead(false), canWrite(false), is_echoing(false), autoReconnect(false), sockFromServer(), + peerAddress(), localAddress(), tgtAddress(), isDatagram() { + Init(); + open(addr,datagram); +} + +template +basic_netbuf::basic_netbuf(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram) + : std::basic_streambuf(), buf_in(NULL), buf_out(NULL), using_buf_in(false), using_buf_out(false), + sock(INVALID_SOCKET), canRead(false), canWrite(false), is_echoing(false), autoReconnect(false), sockFromServer(), + peerAddress(), localAddress(), tgtAddress(), isDatagram() { + Init(); + open(host,port,datagram); +} + +template +basic_netbuf::basic_netbuf(size_t buf_in_size, size_t buf_out_size) + : std::basic_streambuf(), buf_in(NULL), buf_out(NULL), using_buf_in(false), using_buf_out(false), + sock(INVALID_SOCKET), canRead(false), canWrite(false), is_echoing(false), autoReconnect(false), sockFromServer(), + peerAddress(), localAddress(), tgtAddress(), isDatagram() { + Init(); +} + +template +basic_netbuf::~basic_netbuf() { + autoReconnect=false; + if(is_open()) { + out_flush(); + close(); + } + if(using_buf_in) + delete [] buf_in; + if(using_buf_out) + delete [] buf_out; +} + +template +void +basic_netbuf::Init(size_t insize, size_t outsize) { + buf_in = new charT[insize]; + buf_out = new charT[outsize]; + using_buf_in = using_buf_out = true; + setg(buf_in,buf_in+insize,buf_in+insize); + setp(buf_out,buf_out+outsize); + // cout << "Buffer is:" << endl; + // cout << "Input buffer: " << egptr() << " to " << egptr() << " at " << gptr() << endl; + // cout << "Output buffer: " << pbase() << " to " << epptr() << " at " << pptr() << endl; +} + +template +void +basic_netbuf::update_status() { + pollfd pfd; + pfd.fd=sock; + pfd.events = POLLIN | POLLOUT; + if(poll(&pfd,1,0)==-1) + perror("basic_netbuf poll"); + if(pfd.revents&(POLLERR|POLLHUP|POLLNVAL)) { + close(); + if(autoReconnect) + reconnect(); + if(is_open()) + update_status(); + } else { + canRead = (pfd.revents&POLLIN); + canWrite = (pfd.revents&POLLOUT); + } +} + +template +bool +basic_netbuf::open(const IPaddr& addr, bool datagram) { + if(is_open()) + close(); + tgtAddress=addr; + + while(!is_open()) { + //cout << "netstream opening " << addr.get_display_num() << ":" << addr.get_port() << endl; + // create socket + int opsock = ::socket(AF_INET, datagram ? (int)SOCK_DGRAM : (int)SOCK_STREAM, 0); + if(opsock < 1) { + perror("netstream socket()"); + //std::cerr << "netstream error: socket failed to create stream socket" << std::endl; + return false; + } + int on=1; + if ( ::setsockopt ( opsock, SOL_SOCKET, SO_REUSEADDR, ( const char* ) &on, sizeof ( on ) ) == -1 ) { + perror("netstream SO_REUSEADDR setsockopt"); + } + if(datagram) { + if ( ::setsockopt ( opsock, SOL_SOCKET, SO_BROADCAST, ( const char* ) &on, sizeof ( on ) ) == -1 ) { + perror("netstream SO_BROADCAST setsockopt"); + } + const int sndbuf=(epptr()-pbase()); + if ( ::setsockopt ( opsock, SOL_SOCKET, SO_SNDBUF, ( const char* ) &sndbuf, sizeof ( sndbuf ) ) == -1 ) { + perror("netstream SO_SNDBUF setsockopt"); + } + } + + // connect to server. + sockaddr_in server = addr.get_addr(); + int err = ::connect(opsock, (const sockaddr *) &server, sizeof(server)); + if(err < 0) { + //perror("netstream connect()"); + //cout << "netstream error: connect failed to connect to requested address" << endl; + ::close(opsock); + if(!autoReconnect) + return false; + usleep(750000); // don't try to reconnect too fast + } else { + sock=opsock; + sockFromServer=false; + isDatagram=datagram; + socklen_t server_size=sizeof(server); + err = ::getpeername(sock, reinterpret_cast(&server), &server_size); + if(err<0) + perror("netstream getpeername"); + else { + peerAddress.set_addr(ntohl(server.sin_addr.s_addr), ntohs(server.sin_port)); + } + err = ::getsockname(sock, reinterpret_cast(&server), &server_size); + if(err<0) + perror("netstream getsockname"); + else { + localAddress.set_addr(ntohl(server.sin_addr.s_addr), ntohs(server.sin_port)); + } + //cout << " netstream connected to " << getPeerAddress().get_display_num() << ":" << getPeerAddress().get_port() + // << " from " << getLocalAddress().get_display_num() << ":" << getLocalAddress().get_port() << endl; + } + } + + return true; +} + +template +bool +basic_netbuf::listen(const IPaddr& addr, bool datagram) { + if(is_open()) + close(); + tgtAddress=addr; + + // create socket + int opsock = ::socket(AF_INET, datagram ? (int)SOCK_DGRAM : (int)SOCK_STREAM, 0); + if(opsock < 1) { + perror("netstream socket"); + //cout << "netstream error: socket failed to create stream socket" << endl; + return false; + } + int on=1; + if ( ::setsockopt ( opsock, SOL_SOCKET, SO_REUSEADDR, ( const char* ) &on, sizeof ( on ) ) == -1 ) { + perror("netstream SO_REUSEADDR setsockopt"); + } + if(datagram) { + if ( ::setsockopt ( opsock, SOL_SOCKET, SO_BROADCAST, ( const char* ) &on, sizeof ( on ) ) == -1 ) { + perror("netstream SO_BROADCAST setsockopt"); + } + const int sndbuf=(epptr()-pbase()); + if ( ::setsockopt ( opsock, SOL_SOCKET, SO_SNDBUF, ( const char* ) &sndbuf, sizeof ( sndbuf ) ) == -1 ) { + perror("netstream SO_SNDBUF setsockopt"); + } + } + + sockaddr_in server = addr.get_addr(); + + // bind socket to specified address + if(::bind(opsock, (const sockaddr *) &server, sizeof(server)) != 0) { + //perror("netstream bind"); + ::close(opsock); + return false; + } + + // tell OS to start listening + if(::listen(opsock, 1) != 0) { + perror("netstream listen"); + ::close(opsock); + return false; + } + + while(!is_open()) { + // block until connection + sockaddr tmp; + socklen_t tmplen; + int sock2 = ::accept(opsock, &tmp, &tmplen); + if(sock2 < 0) { + perror("netstream accept"); + if(!autoReconnect) { + ::close(opsock); + return false; + } + } else { + // close server socket + ::close(opsock); + //replace with accepted socket + sock=sock2; + sockFromServer=true; + isDatagram=datagram; + socklen_t server_size=sizeof(server); + int err = ::getpeername(sock, reinterpret_cast(&server), &server_size); + if(err<0) + perror("netstream getpeername"); + else { + peerAddress.set_addr(ntohl(server.sin_addr.s_addr), ntohs(server.sin_port)); + } + err = ::getsockname(sock, reinterpret_cast(&server), &server_size); + if(err<0) + perror("netstream getsockname"); + else { + localAddress.set_addr(ntohl(server.sin_addr.s_addr), ntohs(server.sin_port)); + } + //cout << " netstream connected to " << getPeerAddress().get_display_num() << ":" << getPeerAddress().get_port() + // << " from " << getLocalAddress().get_display_num() << ":" << getLocalAddress().get_port() << endl; + } + } + + return true; +} + +template +bool +basic_netbuf::open(const IPaddr::ipname_t& str, bool datagram) { + std::string::size_type colon = str.rfind(':'); + if(colon==std::string::npos) + return false; + IPaddr::ipport_t port = atoi(str.substr(colon+1).c_str()); + bool res = open(str.substr(0,colon),port,datagram); + return res; +} + +template +void +basic_netbuf::close() { + //cout << "close called" << endl; + if(!is_open()) + return; + //cout << "closing" << endl; + ::close(sock); + //cout << "closed" << endl; + sock = INVALID_SOCKET; +} + +template +void +basic_netbuf::reconnect() { + if(sockFromServer) { + listen(tgtAddress,isDatagram); + } else { + open(tgtAddress,isDatagram); + } +} + +template +void +basic_netbuf::printBuffer(const char *buf, int buflen, const char *header, const char *prefix) { + fputs(header, stderr); + int line_begin = 0; + for(int i = 0; i < buflen; i++) { + if(buf[i] == '\n') { + line_begin = 1; + fputc('\n', stderr); + } else { + if(line_begin) fputs(prefix, stderr); + line_begin = 0; + fputc(buf[i], stderr); + } + } +} + +template +void +basic_netbuf::in_sync() { + if(!is_open()) { + //cout << "netstream error: must open connection before reading from it" << endl; + return; + } + update_status(); + if(!is_open()) + return; // just discovered close, don't complain + if(gptr()>egptr()) + gbump( egptr()-gptr() ); + if(gptr()==eback()) { + //cout << "netstream error: in_sync without room in input buffer" << endl; + return; + } + unsigned long n = gptr()-eback()-1; + charT * temp_buf = new char[n*sizeof(charT)]; + ssize_t used = read(sock, temp_buf, n*sizeof(charT)); + while(used==0 || used==(ssize_t)-1) { + //cout << "netstream error: connection dropped" << endl; + close(); + if(autoReconnect) + reconnect(); + if(!is_open()) { + delete [] temp_buf; + return; + } + used = read(sock, temp_buf, n*sizeof(charT)); + } + if(is_echoing) + printBuffer(temp_buf, used, "netstream receiving: ", "< "); + //TODO - what if sizeof(charT)>1? We might need to worry about getting/storing partial char + OTAssert("Partial char was dropped!",(ssize_t)((used/sizeof(charT))*sizeof(charT))==used); + used/=sizeof(charT); + size_t remain = egptr()-eback()-used; + traits::move(eback(),egptr()-remain,remain); + traits::copy(egptr()-used,temp_buf,used); + delete [] temp_buf; + gbump( -used ); +} + +template +void +basic_netbuf::out_flush() { + if(!is_open()) { + //cout << "netstream error: must open connection before writing to it" << endl; + return; + } + update_status(); + if(!is_open()) + return; // just discovered close, don't complain + size_t n = (pptr()-pbase())*sizeof(charT); + if(n==0) + return; + size_t total = 0; + while(total "); + total += sent; + } + total/=sizeof(charT); + n/=sizeof(charT); + if(total!=n) + traits::move(pbase(),pbase()+total,n-total); + pbump( -total ); +} + + +template +inline std::streamsize +basic_netbuf::showmanyc() { + update_status(); + return (is_open() && canRead) ? 1 : 0; + //return (gptr() +inline typename basic_netbuf::int_type +basic_netbuf::underflow() { + in_sync(); + if(gptr() +inline typename basic_netbuf::int_type +basic_netbuf::uflow() { + in_sync(); + if(gptr() +inline typename basic_netbuf::int_type +basic_netbuf::overflow(int_type c) { + out_flush(); + if(!is_open()) + return traits::eof(); + if(!traits::eq_int_type(c, traits::eof())) { + *pptr() = c; + pbump(1); + } + return traits::not_eof(c); +} + +//template +//inline basic_netbuf::_Myt //not supported - don't know details of expected implementation +//basic_netbuf::setbuf(char_type* /*s*/, streamsize /*n*/) { +// return this; +//} + +template +typename basic_netbuf::pos_type +basic_netbuf::seekoff(off_type off, std::ios_base::seekdir way, std::ios_base::openmode which /*= ios_base::in | ios_base::out*/) { + bool dog = (which & std::ios_base::in); + bool dop = (which & std::ios_base::out); + charT* newg, *newp; + int gb,pb; + switch(way) { + case std::ios_base::beg: { + newg = eback()+off; + gb = newg-gptr(); + newp = pbase()+off; + pb = newp-pptr(); + } break; + case std::ios_base::cur: { + newg = gptr()+off; + newp = pptr()+off; + gb=pb=off; + } break; + case std::ios_base::end: { + newg = egptr()+off; + gb = newg-gptr(); + newp = epptr()+off; + pb = newp-pptr(); + } break; + default: + return pos_type(off_type(-1)); + } + if(dog && (newg +inline int +basic_netbuf::sync() { + out_flush(); + //in_sync(); + return is_open()?0:-1; +} + +#undef OTAssert + +#endif diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/aperios/MMCombo/MMCombo.cc ./aperios/MMCombo/MMCombo.cc --- ../Tekkotsu_3.0/aperios/MMCombo/MMCombo.cc 2006-09-19 16:10:33.000000000 -0400 +++ ./aperios/MMCombo/MMCombo.cc 2007-11-21 16:15:07.000000000 -0500 @@ -3,6 +3,7 @@ #include "Shared/Profiler.h" #include "Shared/debuget.h" #include "Shared/Config.h" +#include "Shared/zignor.h" #include "IPC/SharedObject.h" #include "Events/EventRouter.h" #include "Events/EventTranslator.h" @@ -33,22 +34,23 @@ using namespace std; +//#define NO_PROFILING +#ifdef NO_PROFILING +#undef PROFSECTION +#define PROFSECTION(...) {} +#endif + MMCombo::MMCombo() : OObject(), motmanMemRgn(NULL), motionProfilerMemRgn(NULL), soundProfilerMemRgn(NULL), worldStatePoolMemRgn(NULL), soundManagerMemRgn(NULL), processMapMemRgn(NULL), - runLevel(0), num_open(0), etrans(NULL), wspool(NULL), entryPt(), isStopped(true) + runLevel(0), num_open(0), etrans(NULL), wspool(NULL), entryPt(), isStopped(true), + gainListener(), shutterListener(), wbListener() { try { for(unsigned int i=0; i(); - EventTranslator::registerPrototype(); - EventTranslator::registerPrototype(); - EventTranslator::registerPrototype(); } catch(const std::exception& ex) { if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MMCombo construction",&ex)) throw; @@ -58,7 +60,6 @@ } } - OStatus MMCombo::DoInit(const OSystemEvent&) { @@ -117,10 +118,20 @@ //Read config file - config=new Config("/ms/config/tekkotsu.cfg"); - + ::config = new Config(); + ::config->setFileSystemRoot("/ms"); + ::config->vision.gain.addPrimitiveListener(&gainListener); + ::config->vision.shutter_speed.addPrimitiveListener(&shutterListener); + ::config->vision.white_balance.addPrimitiveListener(&wbListener); + if(::config->loadFile("config/tekkotsu.xml")==0) { + if(::config->loadFile("config/tekkotsu.cfg")==0) + std::cerr << std::endl << " *** ERROR: Could not load configuration file config/tekkotsu.xml *** " << std::endl << std::endl; + else + std::cerr << "Successfully imported settings from old-format tekkotsu.cfg" << std::endl; + } + erouter = new EventRouter; - + if(strcmp(objectName,"MainObj")==0) { bool isSlowOutput[NumOutputs]; for(unsigned int i=0; isocket(SocketNS::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*12); - serr=wireless->socket(SocketNS::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*4); + sout=wireless->socket(Socket::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*12); + serr=wireless->socket(Socket::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*4); wireless->setDaemon(sout); wireless->setDaemon(serr); - serr->setFlushType(SocketNS::FLUSH_BLOCKING); + serr->setFlushType(Socket::FLUSH_BLOCKING); sout->setTextForward(); serr->setForward(sout); + //Have erouter listen for incoming stuff + cout << "Telling erouter to serve remote event requests" << endl; + erouter->serveRemoteEventRequests(); + //worldStatePoolMemRgn -> state setup worldStatePoolMemRgn = InitRegion(sizeof(WorldStatePool)); wspool=new ((WorldStatePool*)worldStatePoolMemRgn->Base()) WorldStatePool; @@ -166,11 +181,11 @@ //Setup wireless wireless = new Wireless(); - sout=wireless->socket(SocketNS::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*6); - serr=wireless->socket(SocketNS::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*2); + sout=wireless->socket(Socket::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*6); + serr=wireless->socket(Socket::SOCK_STREAM,Wireless::WIRELESS_DEF_RECV_SIZE,Wireless::WIRELESS_DEF_SEND_SIZE*2); wireless->setDaemon(sout); wireless->setDaemon(serr); - serr->setFlushType(SocketNS::FLUSH_BLOCKING); + serr->setFlushType(Socket::FLUSH_BLOCKING); sout->setTextForward(); serr->setForward(sout); @@ -454,7 +469,7 @@ // there's new sensor info, but we didn't get the event //(Motion drops event if there's anything else already in the queue, might not have been a sensor event in the queue though) unsigned int t=get_time(); - erouter->postEvent(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,t-lastSensorTime,"SensorSouceID::UpdatedSID",1); + erouter->postEvent(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,t-lastSensorTime,"SensorSouceID::UpdatedSID",1); lastSensorTime=t; //if(state->frameNumber-lastSensorFrame!=NumFrames && lastSensorFrame!=-1U) //cout << ProcessID::getIDStr() << " dropped " << (state->frameNumber-lastSensorFrame-NumFrames)/NumFrames << " sensor frames" << endl; @@ -537,6 +552,7 @@ return; } +#ifndef NO_PROFILING static unsigned int id=-1U; Profiler::Timer timer; if(ProcessID::getID()==ProcessID::MotionProcess) { @@ -548,6 +564,7 @@ id=mainProfiler->getNewID("ReadySendJoints()"); timer.setID(id,&mainProfiler->prof); } +#endif if(num_open==0) //If we don't have any joints to open, leave now. (i.e. MainObj on a 220, has no ears) return; @@ -572,24 +589,31 @@ // Update the outputs (note that Main is doing the ears) //I'm using an id compare instead of the slightly more readable strcmp for a tiny bit of speed - bool isERS7; - if(state!=NULL) - isERS7=state->robotDesign&WorldState::ERS7Mask; - else { - char robotDesignStr[orobotdesignNAME_MAX + 1]; - memset(robotDesignStr, 0, sizeof(robotDesignStr)); - if (OPENR::GetRobotDesign(robotDesignStr) != oSUCCESS) { - cout << objectName << "::SetupOutputs - OPENR::GetRobotDesign() failed." << endl; - return; - } - isERS7=(strcmp(robotDesignStr,"ERS-7")==0); - } + bool isERS7=(RobotName == ERS7Info::TargetName); if(ProcessID::getID()==ProcessID::MotionProcess) { float outputs[NumFrames][NumOutputs]; if(state!=NULL) { + static bool seededRNG=false; + if(!seededRNG) { + seededRNG=true; + initRNG(); + } motman->getOutputs(outputs); motman->updatePIDs(primIDs); - motman->updateWorldState(); + + //cout << "updateWorldState" << endl; + for(uint output=LEDOffset; outputoutputs[output]=motman->getOutputCmd(output).value; + for(uint output=BinJointOffset; outputoutputs[output]=motman->getOutputCmd(output).value; + + // these parts check to see if there are "fake" joints, and sets their "sensed" values + // to be the current target value, just in case a behavior is waiting for a non-existant + // non-existant joint to move to a certain position. + const std::set& fakes = RobotInfo::capabilities.getFakeOutputs(); + for(std::set::const_iterator it=fakes.begin(); it!=fakes.end(); ++it) + state->outputs[*it]=motman->getOutputCmd(*it).value; + } else { for(unsigned int f=0; fmotion.calibration[i-PIDJointOffset]; OJointCommandValue2* jval = reinterpret_cast(cmdVecData->GetData(used)->value); for(unsigned int frame=0; framegetNewID("GotSensorFrame()"); timer.setID(id,&mainProfiler->prof); } - TimeET t; +#endif + //TimeET t; OSensorFrameVectorData* rawsensor = reinterpret_cast(event.RCData(0)->Base()); static unsigned int lastFrameNumber=-1U; @@ -768,30 +793,10 @@ //if(wsw.frame-lastFrameNumber!=NumFrames) // cout << objectName << " dropped " << (wsw.frame-lastFrameNumber-NumFrames)/NumFrames << " sensor frame(s)" << endl; lastFrameNumber=wsw.frame; - //seed the random number generator with time value and sensor noise - if(wasLastThrowAway && config->main.seed_rng) { - double tv=TimeET().Value(); //current time with nanosecond resolution - unsigned int * tm=reinterpret_cast(&tv); - unsigned int seed=tm[0]+tm[1]; - for(unsigned int i=0; i(&state->outputs[i]); - seed+=(*x)<<((i%sizeof(unsigned int))*8); - } - for(unsigned int i=0; i(&state->pidduties[i]); - seed+=(*x)<<((i%sizeof(unsigned int))*8); - } - for(unsigned int i=0; i(&state->sensors[i]); - seed+=(*x)<<((i%sizeof(unsigned int))*8); //sensor values - } - cout << "RNG seed=" << seed << endl;; - srand(seed); - } //cout << objectName << " done updating sensors " << info->frameNumber << " at " << TimeET() << " (" << (t.Age()*1000) << "ms)" << endl; } if(info!=NULL) { // notify main of update, but only if there's no backlog - etrans->encodeEvent(EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,0,"SensorSouceID::UpdatedSID",1),true); + etrans->encodeEvent(EventBase(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,0,"SensorSouceID::UpdatedSID",1),true); } observer[obsSensorFrame]->AssertReady(); @@ -927,7 +932,7 @@ // i'm leaving this low-level because there's not much else you can do anyway... // the hardware kills power to the motors, and as far as we can tell, you can't // turn them back on. - if(state->powerFlags[PowerSourceID::PauseSID]) { + if(state->powerFlags[PowerSrcID::PauseSID]) { cout << "%%%%%%% Pause button was pushed! %%%%%%%" << endl; OBootCondition bc(0); OPENR::Shutdown(bc); @@ -1033,26 +1038,9 @@ void MMCombo::SetupOutputs(const bool to_open[NumOutputs]) { - char robotDesignStr[orobotdesignNAME_MAX + 1]; - memset(robotDesignStr, 0, sizeof(robotDesignStr)); - if (OPENR::GetRobotDesign(robotDesignStr) != oSUCCESS) { - cout << objectName << "::SetupOutputs - OPENR::GetRobotDesign() failed." << endl; - return; - } else { - if(strcmp(robotDesignStr,"ERS-210")==0) { - for(unsigned int j=0; j& fakes = RobotInfo::capabilities.getFakeOutputs(); + for(unsigned int j=0; jGetInfo(used++); info->Set(odataJOINT_COMMAND2, primIDs[j], NumFrames); } - if(strcmp(robotDesignStr,"ERS-7")==0) { + if(RobotName == ERS7Info::TargetName) { // this part's the same as usual, except stop when we get to face leds for(unsigned int j=LEDOffset; jmain.seed_rng) { + double tv=TimeET().Value(); //current time with nanosecond resolution + unsigned int * tm=reinterpret_cast(&tv); + unsigned int seed=tm[0]+tm[1]; + for(unsigned int i=0; i(&state->outputs[i]); + seed+=(*x)<<((i%sizeof(unsigned int))*8); + } + for(unsigned int i=0; i(&state->pidduties[i]); + seed+=(*x)<<((i%sizeof(unsigned int))*8); + } + for(unsigned int i=0; i(&state->sensors[i]); + seed+=(*x)<<((i%sizeof(unsigned int))*8); //sensor values + } + cout << ProcessID::getIDStr() << " RNG seed=" << seed << ", zignor seeds: " << *tm << ',' << seed << endl; + srand(seed); + RanNormalSetSeedZig32((int*)&seed,1); + RanNormalSetSeedZig((int*)&seed,1); + } else { + int s=12345; + RanNormalSetSeedZig32(&s,1); + RanNormalSetSeedZig(&s,1); + } +} + +void MMCombo::addRunLevel() { runLevel++; if(runLevel==readyLevel) { try { + initRNG(); cout << "START UP BEHAVIOR..." << flush; ProjectInterface::startupBehavior().DoStart(); cout << "START UP BEHAVIOR-DONE" << endl; @@ -1162,6 +1181,51 @@ } } +void MMCombo::GainSettingListener::plistValueChanged(const plist::PrimitiveBase& pl) { + typedef plist::NamedEnumeration GainSetting; + OPrimitiveID fbkID = 0; + if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){ + std::cout << "Open FbkImageSensor failure." << std::endl; + } else if(const GainSetting* v=dynamic_cast(&pl)) { + OPrimitiveControl_CameraParam ogain(*v); + if(OPENR::ControlPrimitive(fbkID, oprmreqCAM_SET_GAIN, &ogain, sizeof(ogain), 0, 0) != oSUCCESS) + std::cout << "CAM_SET_GAIN : Failed!" << std::endl; + OPENR::ClosePrimitive(fbkID); + } else { + std::cerr << "GainSettingListener got a value changed notification for a non-gain_levels primitive, ignoring..." << std::endl; + } +} + +void MMCombo::ShutterSettingListener::plistValueChanged(const plist::PrimitiveBase& pl) { + typedef plist::NamedEnumeration SpeedSetting; + OPrimitiveID fbkID = 0; + if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){ + std::cout << "Open FbkImageSensor failure." << std::endl; + } else if(const SpeedSetting* v=dynamic_cast(&pl)) { + OPrimitiveControl_CameraParam oshutter(*v); + if(OPENR::ControlPrimitive(fbkID,oprmreqCAM_SET_SHUTTER_SPEED, &oshutter, sizeof(oshutter), 0, 0) != oSUCCESS) + std::cout << "CAM_SET_SHUTTER_SPEED : Failed!" << std::endl; + OPENR::ClosePrimitive(fbkID); + } else { + std::cerr << "ShutterSettingListener got a value changed notification for a non-shutter_speeds primitive, ignoring..." << std::endl; + } +} + +void MMCombo::WhiteBalanceSettingListener::plistValueChanged(const plist::PrimitiveBase& pl) { + typedef plist::NamedEnumeration WBSetting; + OPrimitiveID fbkID = 0; + if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){ + std::cerr << "Open FbkImageSensor failure." << std::endl; + } else if(const WBSetting* v=dynamic_cast(&pl)) { + OPrimitiveControl_CameraParam owb(*v); + if(OPENR::ControlPrimitive(fbkID, oprmreqCAM_SET_WHITE_BALANCE, &owb, sizeof(owb), 0, 0) != oSUCCESS) + std::cerr << "CAM_SET_WHITE_BALANCE : Failed!" << std::endl; + OPENR::ClosePrimitive(fbkID); + } else { + std::cerr << "WhiteBalanceSettingListener got a value changed notification for a non-white_balance_levels primitive, ignoring..." << std::endl; + } +} + /*! @file * @brief Implements MMCombo, the OObject which "forks" (sort of) into Main and Motion processes diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/aperios/MMCombo/MMCombo.h ./aperios/MMCombo/MMCombo.h --- ../Tekkotsu_3.0/aperios/MMCombo/MMCombo.h 2006-08-22 18:23:06.000000000 -0400 +++ ./aperios/MMCombo/MMCombo.h 2007-02-19 17:27:05.000000000 -0500 @@ -5,6 +5,7 @@ #include "Shared/debuget.h" #include "Shared/MarkScope.h" #include "Shared/RobotInfo.h" +#include "Shared/plistBase.h" #include "Wireless/Wireless.h" #include "IPC/ProcessID.h" #include "aperios/EntryPoint.h" @@ -78,6 +79,7 @@ void OpenPrimitives(); //!< both, called from SetupOutputs() (mostly for motion, but main does ears), uses #open to tell which to open void SetupOutputs(const bool to_open[NumOutputs]); //!< both, called from DoInit() (mostly for motion, but main does ears) RCRegion* InitRegion(unsigned int size); //!< both, called to set up a shared memory region of a given size + void initRNG(); //!< called when we're ready to initialize the RNG, either from sensor values or from static value depending on config settings RCRegion * motmanMemRgn; //!< Motion creates, Main receives RCRegion * motionProfilerMemRgn; //!< Motion creates, Main receives @@ -106,6 +108,24 @@ bool isStopped; //!< true if we've received a DoStart and no DoStop - we need this because sometimes an extra message seems to slip in after we've been told to stop, in which case we should ignore it + //! intercepts changes made to the camera's gain setting, and calls the system API to make it so + class GainSettingListener : public plist::PrimitiveListener { + public: + virtual void plistValueChanged(const plist::PrimitiveBase& pl); + } gainListener; + + //! intercepts changes made to the camera's shutter speed, and calls the system API to make it so + class ShutterSettingListener : public plist::PrimitiveListener { + public: + virtual void plistValueChanged(const plist::PrimitiveBase& pl); + } shutterListener; + + //! intercepts changes made to the camera's white balance setting, and calls the system API to make it so + class WhiteBalanceSettingListener : public plist::PrimitiveListener { + public: + virtual void plistValueChanged(const plist::PrimitiveBase& pl); + } wbListener; + //! Motion only, maintains the activation level of the LEDs, returns whether it should be 'fired' inline OLEDValue calcLEDValue(unsigned int i,float x) { if(x<=0.0) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/aperios/Makefile.aperios ./aperios/Makefile.aperios --- ../Tekkotsu_3.0/aperios/Makefile.aperios 2006-08-22 18:23:05.000000000 -0400 +++ ./aperios/Makefile.aperios 2007-11-07 18:27:00.000000000 -0500 @@ -2,10 +2,18 @@ $(error This makefile is not meant to be run directly. It is intended to contain local-specific build instructions. Please run 'make' from the main project directory.); endif -.PHONY: +.PHONY: #Each directory represents a separate OObject aka process/thread -OOBJECTS:=$(filter-out CVS bin include lib share man,$(subst aperios/,,$(shell find aperios -mindepth 1 -maxdepth 1 -type d -prune))) +OOBJECTS:=$(filter-out .svn CVS bin include lib share man,$(subst aperios/,,$(shell find aperios -mindepth 1 -maxdepth 1 -type d -prune))) + +ESRCS:=$(foreach d,$(OOBJECTS),$(shell find aperios/$(d) -name "*$(SRCSUFFIX)")) +EDEPS:=$(patsubst %$(SRCSUFFIX),$(TK_BD)/%.d,$(ESRCS)) +PLATFORM_OBJS:=$(patsubst %$(SRCSUFFIX),$(TK_BD)/%.o,$(ESRCS)) + +ifeq ($(filter clean% docs dox doc alldocs newstick,$(MAKECMDGOALS)),) +-include $(EDEPS) +endif $(TK_BD)/aperios/aperios.d: $(shell find aperios -name "*$(SRCSUFFIX)") @echo Generating $@... @@ -25,10 +33,7 @@ aperios/%Stub.cc : $(TK_BD)/aperios/aperios.d -OSRCS:=$(shell find aperios -name "*$(SRCSUFFIX)") $(foreach x,$(OOBJECTS),aperios/$(x)/$(x)Stub.cc) -DEPENDS:=$(DEPENDS) $(addprefix $(TK_BD)/,$(OSRCS:$(SRCSUFFIX)=.d)) SRCS:=$(SRCS) $(shell find aperios -maxdepth 1 -name "*$(SRCSUFFIX)") -OBJS:=$(addprefix $(TK_BD)/,$(SRCS:$(SRCSUFFIX)=.o)) #The "fork" we do of MMCombo into MainObj and MotoObj #crashes with optimization turned on... not sure why, but it's @@ -51,4 +56,4 @@ cat $(TK_BD)/aperios/TinyFTPD/$*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \ test $$retval -eq 0; -platformBuild: $(addprefix $(TK_BD)/,$(OSRCS:$(SRCSUFFIX)=.o)) $(TK_BD)/libtekkotsu.a +platformBuild: $(TK_BD)/$(LIBTEKKOTSU) $(PLATFORM_OBJS) diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/aperios/SndPlay/SndPlay.cc ./aperios/SndPlay/SndPlay.cc --- ../Tekkotsu_3.0/aperios/SndPlay/SndPlay.cc 2006-09-18 14:08:02.000000000 -0400 +++ ./aperios/SndPlay/SndPlay.cc 2007-05-21 13:07:24.000000000 -0400 @@ -31,9 +31,6 @@ { for (unsigned int i = 0; i < SOUND_NUM_BUFFER; i++) region[i] = 0; - - //need to register any events which we might be sending - EventTranslator::registerPrototype(); //Sound only sends the basic event type } OStatus @@ -53,8 +50,15 @@ ProcessID::setID(ProcessID::SoundProcess); //Read config file - config=new Config("/ms/config/tekkotsu.cfg"); - + ::config = new Config(); + ::config->setFileSystemRoot("/ms"); + if(::config->loadFile("config/tekkotsu.xml")==0) { + if(::config->loadFile("config/tekkotsu.cfg")==0) + std::cerr << std::endl << " *** ERROR: Could not load configuration file config/tekkotsu.xml *** " << std::endl << std::endl; + else + std::cerr << "Successfully imported settings from old-format tekkotsu.cfg" << std::endl; + } + erouter = new EventRouter; etrans=new IPCEventTranslator(*subject[sbjEventTranslatorComm]); // only expect to be handling audioEGID, but just in case, diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/aperios/TinyFTPD/TinyFTPD.cc ./aperios/TinyFTPD/TinyFTPD.cc --- ../Tekkotsu_3.0/aperios/TinyFTPD/TinyFTPD.cc 2006-05-09 13:27:28.000000000 -0400 +++ ./aperios/TinyFTPD/TinyFTPD.cc 2007-04-09 18:23:42.000000000 -0400 @@ -160,16 +160,16 @@ OSYSDEBUG(("TinyFTPD::LoadPasswd()\n")); size_t bufsize; - char* buf; + byte* buf; - OStatus result = Load(FTP_PASSWD_PATH, (byte**)&buf, &bufsize); + OStatus result = Load(FTP_PASSWD_PATH, &buf, &bufsize); if (result != oSUCCESS) { return result; } - char* end = buf + bufsize; - char* cur = buf; - char* head = buf; + char* end = (char*)(buf + bufsize); + char* cur = (char*)buf; + char* head = (char*)buf; Passwd pass; while (cur < end) { diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/aperios/include/regex.h ./aperios/include/regex.h --- ../Tekkotsu_3.0/aperios/include/regex.h 1969-12-31 19:00:00.000000000 -0500 +++ ./aperios/include/regex.h 2007-05-21 13:05:51.000000000 -0400 @@ -0,0 +1,556 @@ +/* Definitions for data structures and routines for the regular + expression library. + Copyright (C) 1985,1989-93,1995-98,2000,2001,2002,2003,2005,2006 + Free Software Foundation, Inc. + This file is part of the GNU C Library. + + The GNU C Library is free software; you can redistribute it and/or + modify it under the terms of the GNU Lesser General Public + License as published by the Free Software Foundation; either + version 2.1 of the License, or (at your option) any later version. + + The GNU C Library is distributed in the hope that it will be useful, + but WITHOUT ANY WARRANTY; without even the implied warranty of + MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the GNU + Lesser General Public License for more details. + + You should have received a copy of the GNU Lesser General Public + License along with the GNU C Library; if not, write to the Free + Software Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA + 02111-1307 USA. */ + +#ifndef _REGEX_H +#define _REGEX_H 1 + +#include + +/* Allow the use in C++ code. */ +#ifdef __cplusplus +extern "C" { +#endif + +/* The following two types have to be signed and unsigned integer type + wide enough to hold a value of a pointer. For most ANSI compilers + ptrdiff_t and size_t should be likely OK. Still size of these two + types is 2 for Microsoft C. Ugh... */ +typedef long int s_reg_t; +typedef unsigned long int active_reg_t; + +/* The following bits are used to determine the regexp syntax we + recognize. The set/not-set meanings are chosen so that Emacs syntax + remains the value 0. The bits are given in alphabetical order, and + the definitions shifted by one from the previous bit; thus, when we + add or remove a bit, only one other definition need change. */ +typedef unsigned long int reg_syntax_t; + +/* If this bit is not set, then \ inside a bracket expression is literal. + If set, then such a \ quotes the following character. */ +#define RE_BACKSLASH_ESCAPE_IN_LISTS ((unsigned long int) 1) + +/* If this bit is not set, then + and ? are operators, and \+ and \? are + literals. + If set, then \+ and \? are operators and + and ? are literals. */ +#define RE_BK_PLUS_QM (RE_BACKSLASH_ESCAPE_IN_LISTS << 1) + +/* If this bit is set, then character classes are supported. They are: + [:alpha:], [:upper:], [:lower:], [:digit:], [:alnum:], [:xdigit:], + [:space:], [:print:], [:punct:], [:graph:], and [:cntrl:]. + If not set, then character classes are not supported. */ +#define RE_CHAR_CLASSES (RE_BK_PLUS_QM << 1) + +/* If this bit is set, then ^ and $ are always anchors (outside bracket + expressions, of course). + If this bit is not set, then it depends: + ^ is an anchor if it is at the beginning of a regular + expression or after an open-group or an alternation operator; + $ is an anchor if it is at the end of a regular expression, or + before a close-group or an alternation operator. + + This bit could be (re)combined with RE_CONTEXT_INDEP_OPS, because + POSIX draft 11.2 says that * etc. in leading positions is undefined. + We already implemented a previous draft which made those constructs + invalid, though, so we haven't changed the code back. */ +#define RE_CONTEXT_INDEP_ANCHORS (RE_CHAR_CLASSES << 1) + +/* If this bit is set, then special characters are always special + regardless of where they are in the pattern. + If this bit is not set, then special characters are special only in + some contexts; otherwise they are ordinary. Specifically, + * + ? and intervals are only special when not after the beginning, + open-group, or alternation operator. */ +#define RE_CONTEXT_INDEP_OPS (RE_CONTEXT_INDEP_ANCHORS << 1) + +/* If this bit is set, then *, +, ?, and { cannot be first in an re or + immediately after an alternation or begin-group operator. */ +#define RE_CONTEXT_INVALID_OPS (RE_CONTEXT_INDEP_OPS << 1) + +/* If this bit is set, then . matches newline. + If not set, then it doesn't. */ +#define RE_DOT_NEWLINE (RE_CONTEXT_INVALID_OPS << 1) + +/* If this bit is set, then . doesn't match NUL. + If not set, then it does. */ +#define RE_DOT_NOT_NULL (RE_DOT_NEWLINE << 1) + +/* If this bit is set, nonmatching lists [^...] do not match newline. + If not set, they do. */ +#define RE_HAT_LISTS_NOT_NEWLINE (RE_DOT_NOT_NULL << 1) + +/* If this bit is set, either \{...\} or {...} defines an + interval, depending on RE_NO_BK_BRACES. + If not set, \{, \}, {, and } are literals. */ +#define RE_INTERVALS (RE_HAT_LISTS_NOT_NEWLINE << 1) + +/* If this bit is set, +, ? and | aren't recognized as operators. + If not set, they are. */ +#define RE_LIMITED_OPS (RE_INTERVALS << 1) + +/* If this bit is set, newline is an alternation operator. + If not set, newline is literal. */ +#define RE_NEWLINE_ALT (RE_LIMITED_OPS << 1) + +/* If this bit is set, then `{...}' defines an interval, and \{ and \} + are literals. + If not set, then `\{...\}' defines an interval. */ +#define RE_NO_BK_BRACES (RE_NEWLINE_ALT << 1) + +/* If this bit is set, (...) defines a group, and \( and \) are literals. + If not set, \(...\) defines a group, and ( and ) are literals. */ +#define RE_NO_BK_PARENS (RE_NO_BK_BRACES << 1) + +/* If this bit is set, then \ matches . + If not set, then \ is a back-reference. */ +#define RE_NO_BK_REFS (RE_NO_BK_PARENS << 1) + +/* If this bit is set, then | is an alternation operator, and \| is literal. + If not set, then \| is an alternation operator, and | is literal. */ +#define RE_NO_BK_VBAR (RE_NO_BK_REFS << 1) + +/* If this bit is set, then an ending range point collating higher + than the starting range point, as in [z-a], is invalid. + If not set, then when ending range point collates higher than the + starting range point, the range is ignored. */ +#define RE_NO_EMPTY_RANGES (RE_NO_BK_VBAR << 1) + +/* If this bit is set, then an unmatched ) is ordinary. + If not set, then an unmatched ) is invalid. */ +#define RE_UNMATCHED_RIGHT_PAREN_ORD (RE_NO_EMPTY_RANGES << 1) + +/* If this bit is set, succeed as soon as we match the whole pattern, + without further backtracking. */ +#define RE_NO_POSIX_BACKTRACKING (RE_UNMATCHED_RIGHT_PAREN_ORD << 1) + +/* If this bit is set, do not process the GNU regex operators. + If not set, then the GNU regex operators are recognized. */ +#define RE_NO_GNU_OPS (RE_NO_POSIX_BACKTRACKING << 1) + +/* If this bit is set, turn on internal regex debugging. + If not set, and debugging was on, turn it off. + This only works if regex.c is compiled -DDEBUG. + We define this bit always, so that all that's needed to turn on + debugging is to recompile regex.c; the calling code can always have + this bit set, and it won't affect anything in the normal case. */ +#define RE_DEBUG (RE_NO_GNU_OPS << 1) + +/* If this bit is set, a syntactically invalid interval is treated as + a string of ordinary characters. For example, the ERE 'a{1' is + treated as 'a\{1'. */ +#define RE_INVALID_INTERVAL_ORD (RE_DEBUG << 1) + +/* If this bit is set, then ignore case when matching. + If not set, then case is significant. */ +#define RE_ICASE (RE_INVALID_INTERVAL_ORD << 1) + +/* This bit is used internally like RE_CONTEXT_INDEP_ANCHORS but only + for ^, because it is difficult to scan the regex backwards to find + whether ^ should be special. */ +#define RE_CARET_ANCHORS_HERE (RE_ICASE << 1) + +/* If this bit is set, then \{ cannot be first in an bre or + immediately after an alternation or begin-group operator. */ +#define RE_CONTEXT_INVALID_DUP (RE_CARET_ANCHORS_HERE << 1) + +/* If this bit is set, then no_sub will be set to 1 during + re_compile_pattern. */ +#define RE_NO_SUB (RE_CONTEXT_INVALID_DUP << 1) + +/* This global variable defines the particular regexp syntax to use (for + some interfaces). When a regexp is compiled, the syntax used is + stored in the pattern buffer, so changing this does not affect + already-compiled regexps. */ +extern reg_syntax_t re_syntax_options; + +/* Define combinations of the above bits for the standard possibilities. + (The [[[ comments delimit what gets put into the Texinfo file, so + don't delete them!) */ +/* [[[begin syntaxes]]] */ +#define RE_SYNTAX_EMACS 0 + +#define RE_SYNTAX_AWK \ + (RE_BACKSLASH_ESCAPE_IN_LISTS | RE_DOT_NOT_NULL \ + | RE_NO_BK_PARENS | RE_NO_BK_REFS \ + | RE_NO_BK_VBAR | RE_NO_EMPTY_RANGES \ + | RE_DOT_NEWLINE | RE_CONTEXT_INDEP_ANCHORS \ + | RE_UNMATCHED_RIGHT_PAREN_ORD | RE_NO_GNU_OPS) + +#define RE_SYNTAX_GNU_AWK \ + ((RE_SYNTAX_POSIX_EXTENDED | RE_BACKSLASH_ESCAPE_IN_LISTS | RE_DEBUG) \ + & ~(RE_DOT_NOT_NULL | RE_INTERVALS | RE_CONTEXT_INDEP_OPS \ + | RE_CONTEXT_INVALID_OPS )) + +#define RE_SYNTAX_POSIX_AWK \ + (RE_SYNTAX_POSIX_EXTENDED | RE_BACKSLASH_ESCAPE_IN_LISTS \ + | RE_INTERVALS | RE_NO_GNU_OPS) + +#define RE_SYNTAX_GREP \ + (RE_BK_PLUS_QM | RE_CHAR_CLASSES \ + | RE_HAT_LISTS_NOT_NEWLINE | RE_INTERVALS \ + | RE_NEWLINE_ALT) + +#define RE_SYNTAX_EGREP \ + (RE_CHAR_CLASSES | RE_CONTEXT_INDEP_ANCHORS \ + | RE_CONTEXT_INDEP_OPS | RE_HAT_LISTS_NOT_NEWLINE \ + | RE_NEWLINE_ALT | RE_NO_BK_PARENS \ + | RE_NO_BK_VBAR) + +#define RE_SYNTAX_POSIX_EGREP \ + (RE_SYNTAX_EGREP | RE_INTERVALS | RE_NO_BK_BRACES \ + | RE_INVALID_INTERVAL_ORD) + +/* P1003.2/D11.2, section 4.20.7.1, lines 5078ff. */ +#define RE_SYNTAX_ED RE_SYNTAX_POSIX_BASIC + +#define RE_SYNTAX_SED RE_SYNTAX_POSIX_BASIC + +/* Syntax bits common to both basic and extended POSIX regex syntax. */ +#define _RE_SYNTAX_POSIX_COMMON \ + (RE_CHAR_CLASSES | RE_DOT_NEWLINE | RE_DOT_NOT_NULL \ + | RE_INTERVALS | RE_NO_EMPTY_RANGES) + +#define RE_SYNTAX_POSIX_BASIC \ + (_RE_SYNTAX_POSIX_COMMON | RE_BK_PLUS_QM | RE_CONTEXT_INVALID_DUP) + +/* Differs from ..._POSIX_BASIC only in that RE_BK_PLUS_QM becomes + RE_LIMITED_OPS, i.e., \? \+ \| are not recognized. Actually, this + isn't minimal, since other operators, such as \`, aren't disabled. */ +#define RE_SYNTAX_POSIX_MINIMAL_BASIC \ + (_RE_SYNTAX_POSIX_COMMON | RE_LIMITED_OPS) + +#define RE_SYNTAX_POSIX_EXTENDED \ + (_RE_SYNTAX_POSIX_COMMON | RE_CONTEXT_INDEP_ANCHORS \ + | RE_CONTEXT_INDEP_OPS | RE_NO_BK_BRACES \ + | RE_NO_BK_PARENS | RE_NO_BK_VBAR \ + | RE_CONTEXT_INVALID_OPS | RE_UNMATCHED_RIGHT_PAREN_ORD) + +/* Differs from ..._POSIX_EXTENDED in that RE_CONTEXT_INDEP_OPS is + removed and RE_NO_BK_REFS is added. */ +#define RE_SYNTAX_POSIX_MINIMAL_EXTENDED \ + (_RE_SYNTAX_POSIX_COMMON | RE_CONTEXT_INDEP_ANCHORS \ + | RE_CONTEXT_INVALID_OPS | RE_NO_BK_BRACES \ + | RE_NO_BK_PARENS | RE_NO_BK_REFS \ + | RE_NO_BK_VBAR | RE_UNMATCHED_RIGHT_PAREN_ORD) +/* [[[end syntaxes]]] */ + +/* Maximum number of duplicates an interval can allow. Some systems + (erroneously) define this in other header files, but we want our + value, so remove any previous define. */ +#ifdef RE_DUP_MAX +# undef RE_DUP_MAX +#endif +/* If sizeof(int) == 2, then ((1 << 15) - 1) overflows. */ +#define RE_DUP_MAX (0x7fff) + + +/* POSIX `cflags' bits (i.e., information for `regcomp'). */ + +/* If this bit is set, then use extended regular expression syntax. + If not set, then use basic regular expression syntax. */ +#define REG_EXTENDED 1 + +/* If this bit is set, then ignore case when matching. + If not set, then case is significant. */ +#define REG_ICASE (REG_EXTENDED << 1) + +/* If this bit is set, then anchors do not match at newline + characters in the string. + If not set, then anchors do match at newlines. */ +#define REG_NEWLINE (REG_ICASE << 1) + +/* If this bit is set, then report only success or fail in regexec. + If not set, then returns differ between not matching and errors. */ +#define REG_NOSUB (REG_NEWLINE << 1) + + +/* POSIX `eflags' bits (i.e., information for regexec). */ + +/* If this bit is set, then the beginning-of-line operator doesn't match + the beginning of the string (presumably because it's not the + beginning of a line). + If not set, then the beginning-of-line operator does match the + beginning of the string. */ +#define REG_NOTBOL 1 + +/* Like REG_NOTBOL, except for the end-of-line. */ +#define REG_NOTEOL (1 << 1) + +/* Use PMATCH[0] to delimit the start and end of the search in the + buffer. */ +#define REG_STARTEND (1 << 2) + + +/* If any error codes are removed, changed, or added, update the + `re_error_msg' table in regex.c. */ +typedef enum +{ +#ifdef _XOPEN_SOURCE + REG_ENOSYS = -1, /* This will never happen for this implementation. */ +#endif + + REG_NOERROR = 0, /* Success. */ + REG_NOMATCH, /* Didn't find a match (for regexec). */ + + /* POSIX regcomp return error codes. (In the order listed in the + standard.) */ + REG_BADPAT, /* Invalid pattern. */ + REG_ECOLLATE, /* Inalid collating element. */ + REG_ECTYPE, /* Invalid character class name. */ + REG_EESCAPE, /* Trailing backslash. */ + REG_ESUBREG, /* Invalid back reference. */ + REG_EBRACK, /* Unmatched left bracket. */ + REG_EPAREN, /* Parenthesis imbalance. */ + REG_EBRACE, /* Unmatched \{. */ + REG_BADBR, /* Invalid contents of \{\}. */ + REG_ERANGE, /* Invalid range end. */ + REG_ESPACE, /* Ran out of memory. */ + REG_BADRPT, /* No preceding re for repetition op. */ + + /* Error codes we've added. */ + REG_EEND, /* Premature end. */ + REG_ESIZE, /* Compiled pattern bigger than 2^16 bytes. */ + REG_ERPAREN /* Unmatched ) or \); not returned from regcomp. */ +} reg_errcode_t; + +/* This data structure represents a compiled pattern. Before calling + the pattern compiler, the fields `buffer', `allocated', `fastmap', + `translate', and `no_sub' can be set. After the pattern has been + compiled, the `re_nsub' field is available. All other fields are + private to the regex routines. */ + +#ifndef RE_TRANSLATE_TYPE +# define RE_TRANSLATE_TYPE unsigned char * +#endif + +struct re_pattern_buffer +{ + /* Space that holds the compiled pattern. It is declared as + `unsigned char *' because its elements are sometimes used as + array indexes. */ + unsigned char *buffer; + + /* Number of bytes to which `buffer' points. */ + unsigned long int allocated; + + /* Number of bytes actually used in `buffer'. */ + unsigned long int used; + + /* Syntax setting with which the pattern was compiled. */ + reg_syntax_t syntax; + + /* Pointer to a fastmap, if any, otherwise zero. re_search uses the + fastmap, if there is one, to skip over impossible starting points + for matches. */ + char *fastmap; + + /* Either a translate table to apply to all characters before + comparing them, or zero for no translation. The translation is + applied to a pattern when it is compiled and to a string when it + is matched. */ + RE_TRANSLATE_TYPE translate; + + /* Number of subexpressions found by the compiler. */ + size_t re_nsub; + + /* Zero if this pattern cannot match the empty string, one else. + Well, in truth it's used only in `re_search_2', to see whether or + not we should use the fastmap, so we don't set this absolutely + perfectly; see `re_compile_fastmap' (the `duplicate' case). */ + unsigned can_be_null : 1; + + /* If REGS_UNALLOCATED, allocate space in the `regs' structure + for `max (RE_NREGS, re_nsub + 1)' groups. + If REGS_REALLOCATE, reallocate space if necessary. + If REGS_FIXED, use what's there. */ +#define REGS_UNALLOCATED 0 +#define REGS_REALLOCATE 1 +#define REGS_FIXED 2 + unsigned regs_allocated : 2; + + /* Set to zero when `regex_compile' compiles a pattern; set to one + by `re_compile_fastmap' if it updates the fastmap. */ + unsigned fastmap_accurate : 1; + + /* If set, `re_match_2' does not return information about + subexpressions. */ + unsigned no_sub : 1; + + /* If set, a beginning-of-line anchor doesn't match at the beginning + of the string. */ + unsigned not_bol : 1; + + /* Similarly for an end-of-line anchor. */ + unsigned not_eol : 1; + + /* If true, an anchor at a newline matches. */ + unsigned newline_anchor : 1; +}; + +typedef struct re_pattern_buffer regex_t; + +/* Type for byte offsets within the string. POSIX mandates this. */ +typedef int regoff_t; + + +/* This is the structure we store register match data in. See + regex.texinfo for a full description of what registers match. */ +struct re_registers +{ + unsigned num_regs; + regoff_t *start; + regoff_t *end; +}; + + +/* If `regs_allocated' is REGS_UNALLOCATED in the pattern buffer, + `re_match_2' returns information about at least this many registers + the first time a `regs' structure is passed. */ +#ifndef RE_NREGS +# define RE_NREGS 30 +#endif + + +/* POSIX specification for registers. Aside from the different names than + `re_registers', POSIX uses an array of structures, instead of a + structure of arrays. */ +typedef struct +{ + regoff_t rm_so; /* Byte offset from string's start to substring's start. */ + regoff_t rm_eo; /* Byte offset from string's start to substring's end. */ +} regmatch_t; + +/* Declarations for routines. */ + +/* Sets the current default syntax to SYNTAX, and return the old syntax. + You can also simply assign to the `re_syntax_options' variable. */ +extern reg_syntax_t re_set_syntax (reg_syntax_t __syntax); + +/* Compile the regular expression PATTERN, with length LENGTH + and syntax given by the global `re_syntax_options', into the buffer + BUFFER. Return NULL if successful, and an error string if not. */ +extern const char *re_compile_pattern (const char *__pattern, size_t __length, + struct re_pattern_buffer *__buffer); + + +/* Compile a fastmap for the compiled pattern in BUFFER; used to + accelerate searches. Return 0 if successful and -2 if was an + internal error. */ +extern int re_compile_fastmap (struct re_pattern_buffer *__buffer); + + +/* Search in the string STRING (with length LENGTH) for the pattern + compiled into BUFFER. Start searching at position START, for RANGE + characters. Return the starting position of the match, -1 for no + match, or -2 for an int