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 <sstream>
 
 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; i<LEDOffset+NumLEDs; i++)
 		motman->setOutput(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<ControlBase*>& 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<plist::PrimitiveBase*>(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; i<LEDOffset+NumLEDs; i++)
 		motman->setOutput(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<B>::template Factory<B> >
 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 <exception>
+
+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<plist::Collection*>(root->resolveEntry(path));
+	if(curcol==NULL) {
+		clearSlots();
+		pushSlot(new NullControl("[NULL Collection]"));
+		ControlBase::refresh();
+		return;
+	}
+	for(std::vector<ControlBase*>::const_iterator it=options.begin(); it!=options.end(); ++it) {
+		if(StringInputControl * input = dynamic_cast<StringInputControl*>(*it)) {
+			if(input->getLastInput().size()>0) {
+				std::string key=input->getName();
+				if(dynamic_cast<plist::Dictionary*>(curcol))
+					key=key.substr(0,key.find('='));
+				plist::PrimitiveBase * prim = dynamic_cast<plist::PrimitiveBase*>(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<ControlBase*>::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<plist::Dictionary*>(curcol)) {
+		for(plist::Dictionary::const_iterator it=d->begin(); it!=d->end(); ++it) {
+			if(plist::NamedEnumerationBase * neb = dynamic_cast<plist::NamedEnumerationBase*>(it->second)) {
+				pushSlot(new NamedEnumerationEditor(it->first+"="+neb->get(),d->getComment(it->first),*neb));
+			} else if(plist::PrimitiveBase * po = dynamic_cast<plist::PrimitiveBase*>(it->second)) {
+				pushSlot(new StringInputControl(it->first+"="+po->get(),d->getComment(it->first)));
+			} else if(dynamic_cast<plist::Collection*>(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<plist::ArrayBase*>(curcol)) {
+		for(unsigned int i=0; i!=a->size(); ++i) {
+			if(plist::NamedEnumerationBase * neb = dynamic_cast<plist::NamedEnumerationBase*>(&a->getEntry(i))) {
+				pushSlot(new NamedEnumerationEditor(neb->get(),a->getComment(i),*neb));
+			} else if(plist::PrimitiveBase * po = dynamic_cast<plist::PrimitiveBase*>(&a->getEntry(i))) {
+				pushSlot(new StringInputControl(po->get(),a->getComment(i)));
+			} else if(dynamic_cast<plist::Collection*>(&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<ControlBase*>::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.size(); i++)
+		if(ConfigurationEditor * confe = dynamic_cast<ConfigurationEditor*>(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<float>);
+		dict.addEntry("int",new plist::Primitive<int>);
+		dict.addEntry("int (unsigned)",new plist::Primitive<unsigned int>);
+		dict.addEntry("string",new plist::Primitive<std::string>);
+		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<plist::ObjectBase&>(*it->second->clone())));
+		}
+	}
+}
+
+void ConfigurationEditor::NewCollectionEntry::refresh() {
+	std::string key;
+	if(options.size()>0 && options[0]!=NULL)
+		key=dynamic_cast<const StringInputControl&>(*options[0]).getLastInput();
+	options.clear();
+	StringInputControl * keyEdit=NULL;
+	if(dynamic_cast<plist::Dictionary*>(tgt)) {
+		keyEdit = new StringInputControl("Key: "+key,"Enter key for the dictionary entry");
+	} else if(dynamic_cast<plist::ArrayBase*>(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<plist::PrimitiveBase*>(obj)) {
+		pushSlot(new StringInputControl(po->get(),"Enter the intial value for the item"));
+	} else if(plist::Collection * c = dynamic_cast<plist::Collection*>(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<plist::Dictionary*>(tgt)) {
+		std::string key = dynamic_cast<const StringInputControl&>(*options[0]).getLastInput();
+		d->addEntry(key,obj);
+	} else if(plist::ArrayBase* a = dynamic_cast<plist::ArrayBase*>(tgt)) {
+		std::string key = dynamic_cast<const StringInputControl&>(*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<plist::ArrayBase::EntryConstraint<plist::ObjectBase>*>(a)->addEntry(idx,obj);
+	}
+	return NULL;
+}
+
+void ConfigurationEditor::NamedEnumerationEditor::refresh() {
+	options.clear();
+	std::map<int,std::string> names;
+	tgt->getPreferredNames(names);
+	for(std::map<int,std::string>::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<unsigned int>& hi) {
+			if(hi.empty())
+				StringInputControl::setHilights(hi);
+			else // go straight to control base
+				ControlBase::setHilights(std::vector<unsigned int>(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; i<options.size(); i++)
+		for(unsigned int i=0; i<options.size(); i++) {
 			if(options[i]==NULL)
-				ss << "0\n0\n----------\n\n";
-			else 
+				ss << "0\n0\n----------\n0\n\n";
+			else {
+				std::string desc = options[i]->getDescription();
 				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(choice<options.size() && options[choice]!=NULL) {
 				ambiguous=false;
 			} else {
@@ -276,12 +277,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(\"%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; i<EventBase::numEGIDs; i++) {
 		std::string tmp=EventBase::EventGeneratorNames[i];
 		pushSlot(new NullControl(("[ ] "+tmp).c_str(),"Show/hide events from "+tmp));
@@ -36,7 +38,7 @@
 	if(logSocket==NULL) {
 		theOne=this;
 		ASSERT(logSocketRefCount==0,"logSocket is NULL, ref count is non-zero");
-		logSocket=wireless->socket(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<JPEGGenerator*>(&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<JPEGGenerator*>(&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<StateNode*>& subnodes=n->getNodes();
-	if(subnodes.size()==0) {
-		// it's a leaf node, no subnodes or transitions between them
-		indent(depth);
-		logSocket->printf("<state class=\"%s\" id=\"%s\" />\n", n->getClassName().c_str(), n->getName().c_str());
-	} else {
-
-		// first output current node's info
-		indent(depth);
-		logSocket->printf("<state class=\"%s\" id=\"%s\">\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<const Transition*> transitions;
 		// now recurse on sub-nodes, extracting all of the subnodes transitions
 		for(unsigned int i=0; i<subnodes.size(); i++) {
-			spider(subnodes[i],depth+1);
+			spider(subnodes[i],cur);
 			const std::vector<Transition*>& curt=subnodes[i]->getTransitions();
 			transitions.insert(curt.begin(),curt.end());
 		}
 
 		// now output transitions between subnodes we collected in previous step
 		for(std::set<const Transition*>::const_iterator it=transitions.begin(); it!=transitions.end(); it++) {
-			indent(depth+1);
-			logSocket->printf("<transition class=\"%s\" id=\"%s\">\n", (*it)->getClassName().c_str(), (*it)->getName().c_str());
-			const std::vector<StateNode*>& incoming=(*it)->getSources();
-			for(unsigned int i=0; i<incoming.size(); i++) {
-				indent(depth+2);
-				logSocket->printf("<source>%s</source>\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<StateNode*> 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<StateNode*>& outgoing=(*it)->getDestinations();
-			for(unsigned int i=0; i<outgoing.size(); i++) {
-				indent(depth+2);
-				logSocket->printf("<destination>%s</destination>\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("</transition>\n");
 		}
-
-		indent(depth);
-		logSocket->printf("</state>\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<Transition*>(event.getSourceID());
+		const Transition * trans = reinterpret_cast<Transition*>(e.getSourceID());
 		const std::vector<StateNode*>& incoming=trans->getSources();
 		const std::vector<StateNode*>& outgoing=trans->getDestinations();
 		for(std::vector<StateNode*>::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("<event>\n");
-			indent(1);
-			logSocket->printf("<fire id=\"%s\" time=\"%d\" />\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<StateNode*>(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<StateNode*>(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="<event><state%s id=\"%s\" time=\"%d\" /></event>\n"; // unexpected
-				else {
-					queuedEvents.push(event);
-					return;
-				}
-			} else
-				format="  <state%s id=\"%s\" time=\"%d\" />\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("</event>\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 <fstream>
 #include <set>
 #include <queue>
+#include <stack>
 
 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:
+ *  - '<tt>list</tt>' - send list of all instantiated StateNodes
+ *  - '<tt>spider </tt><i>name</i>' - spider the current structure of StateNode named <i>name</i>
+ *  - '<tt>listen </tt><i>name</i>' - send updates regarding the activation status of <i>name</i> and its subnodes; you can specify a state which is not yet running
+ *  - '<tt>ignore </tt><i>name</i>' - cancels a previous listen command
+ *  - '<tt>clear</tt>' - 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 <tt>list</tt> command, the first line will be the number
+ *  of StateNodes, followed by that number of lines, one StateNode
+ *  name per line.
+ *
+ *  After a <tt>spider</tt> 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
+ *  ("<model></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
+ <!DOCTYPE model [
+ <!ELEMENT model (state*, transition*)>
+ <!ELEMENT state (state*, transition*)>
+ <!ELEMENT transition (source+, dest+)>
+ <!ELEMENT source (#PCDATA)>
+ <!ELEMENT dest (#PCDATA)>
+ 
+ <!ATTLIST state id CDATA #REQUIRED>
+ <!ATTLIST state class CDATA #REQUIRED>
+ <!ATTLIST transition id CDATA #REQUIRED>
+ <!ATTLIST transition class CDATA #REQUIRED>
+ ]>@endverbatim
+ *
+ *  The format of status updates following a listen command is:
+ @verbatim
+ <!DOCTYPE event [
+ <!ELEMENT event (fire*, statestart*, statestop*)>
+ <!ELEMENT fire (EMPTY)>
+ <!ELEMENT statestart (EMPTY)>
+ <!ELEMENT statestop (EMPTY)>
+
+ <!ATTLIST fire id CDATA #REQUIRED>
+ <!ATTLIST fire time CDATA #REQUIRED>
+ <!ATTLIST statestart id CDATA #REQUIRED>
+ <!ATTLIST statestart time CDATA #REQUIRED>
+ <!ATTLIST statestop id CDATA #REQUIRED>
+ <!ATTLIST statestop time CDATA #REQUIRED>
+ ]>@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<BehaviorBase*> registry_t; //!< the type of the behavior registry (BehaviorBase::registry)
 
-	typedef std::multiset<const StateNode*> 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<std::string> listen_t; //!< the type of #listen
 	listen_t listen; //!< a set of state machine names which should have their subnodes monitored
 
-	typedef std::queue<EventBase> 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<xmlNode*> 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<xmlNode*> 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 <sys/types.h>
 #include <sys/stat.h>
 #include <unistd.h>
@@ -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; i<path.size(); i++)
+void FileBrowserControl::appendPath(const std::string& path) {
+	paths.push_back(std::string());
+	for(unsigned int i=0; i<path.size(); i++) {
 		if(path[i]!='/')
 			paths.back().append(1,path[i]);
 		else if(paths.back().size()!=0)
 			paths.push_back(std::string());
+	}
 }
 
 
@@ -107,8 +133,7 @@
 	clearSlots();
 	DIR* dir=opendir(makePath().c_str());
 	if(dir==NULL) {
-		pushSlot(new ControlBase("Bad Path"));
-		cout << "bad path: " << makePath() << endl;
+		pushSlot(new NullControl("Bad Path: "+makePath(),makePath(),this));
 		return;
 	}
 	if(paths.size()!=0 && recurse) {
@@ -116,7 +141,7 @@
 		std::string path=makePath("..");
 		int err=stat(path.c_str(),&s);
 		if(err==0 && s.st_mode&S_IFDIR)
-			pushSlot(new ControlBase(".."));
+			pushSlot(new NullControl("..","go up a directory level",this));
 	}
 	struct dirent * ent=readdir(dir);
 	while(ent!=NULL) {
@@ -130,18 +155,18 @@
 			}
 			if(s.st_mode&S_IFDIR) {
 				if(recurse)
-					pushSlot(new ControlBase(std::string(ent->d_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; i<hilights.size(); i++) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/FileBrowserControl.h ./Behaviors/Controls/FileBrowserControl.h
--- ../Tekkotsu_3.0/Behaviors/Controls/FileBrowserControl.h	2004-01-14 15:43:44.000000000 -0500
+++ ./Behaviors/Controls/FileBrowserControl.h	2006-10-30 16:26:45.000000000 -0500
@@ -27,10 +27,10 @@
 	void setRecurse(bool r) { recurse=r; }                 //!< sets #recurse
 	bool getRecurse() const { return recurse; }            //!< returns #recurse
 
-	void setRoot(const std::string& path);                 //!< sets #root
+	void setRoot(const std::string& path);                 //!< sets #root, clears #paths
 	std::string getRoot() const { return root; }           //!< returns #root
 
-	void setPath(const std::string& path);                 //!< sets #paths
+	void appendPath(const std::string& path);                 //!< adds entries to #paths (location relative to #root)
 	
 	void setFilter(const std::string& filt) {filter=filt;} //!< sets #filter; remember can only use one wildcard, e.g. *.ext or filename.ext or filename*
 	//@}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/FileInputControl.h ./Behaviors/Controls/FileInputControl.h
--- ../Tekkotsu_3.0/Behaviors/Controls/FileInputControl.h	2004-03-22 19:55:01.000000000 -0500
+++ ./Behaviors/Controls/FileInputControl.h	2007-01-28 20:16:57.000000000 -0500
@@ -10,15 +10,15 @@
  public:
 	//! Constructor
 	FileInputControl()
-		: FileBrowserControl("Select file","Select a file","/ms"), file(NULL), myfile()
+		: FileBrowserControl("Select file","Select a file","/"), file(NULL), myfile(), acceptNonExistant(false)
 	{}
 
 	//! Constructor
 	FileInputControl(const std::string& nm, const std::string& desc, const std::string& path, std::string* store=NULL)
-		: FileBrowserControl(nm,desc,path), file(store), myfile()
+		: FileBrowserControl(nm,desc,path), file(store), myfile(), acceptNonExistant(false)
 	{}
 
-	//! returns the path to file last selected
+	//! returns the path to file last selected; use takeInput() to assign to this
 	virtual const std::string& getLastInput() { return myfile; }
 
 	//! clears the last input (i.e. so you can easily tell later if new input is entered)
@@ -27,6 +27,11 @@
 	//! pass pointer to an external string you wish to have set when a file is selected; NULL otherwise
 	virtual void setStore(std::string* store) { file=store; }
 	
+	//! sets #acceptNonExistant
+	virtual void setAcceptNonExistant(bool b) { acceptNonExistant=b; }
+	//! returns #acceptNonExistant
+	virtual bool getAcceptNonExistant() const { return acceptNonExistant; }
+	
 protected:
 	virtual ControlBase* selectedFile(const std::string& f) {
 		myfile=f;
@@ -34,9 +39,15 @@
 			*file=f;
 		return NULL;
 	}
+	virtual ControlBase* invalidInput(const std::string& msg, bool ambiguous) {
+		if(!acceptNonExistant)
+			return FileBrowserControl::invalidInput(msg,ambiguous);
+		return selectedFile(makePath(msg));
+	}
 
 	std::string* file;  //!< if we're supposed to store in an external string, this will point to it, otherwise NULL
 	std::string myfile; //!< stores last file selected
+	bool acceptNonExistant; //!< if true, will set #file and #myfile to "invalid" inputs as well -- i.e. inputs that don't correspond to any current file (so user can request a new one)
 
 private:
 	FileInputControl(const FileInputControl& ); //!< don't call
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Controls/LoadCalibration.h ./Behaviors/Controls/LoadCalibration.h
--- ../Tekkotsu_3.0/Behaviors/Controls/LoadCalibration.h	2005-06-06 19:05:51.000000000 -0400
+++ ./Behaviors/Controls/LoadCalibration.h	2007-01-28 20:16:57.000000000 -0500
@@ -14,15 +14,15 @@
 
 	//!Constructor
 	LoadCalibration(WalkMC::CalibrationParam* calp)
-		: FileBrowserControl("Load Calibration...","",config->portPath(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 <string>
 
@@ -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<LedMC> 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<LEDOffset+NumLEDs; i++)
 		pose.setOutputCmd(i,0);
+#endif
 	// add it the motion sequence we'll be using to move to changes
 	SharedObject<SmallMotionSequenceMC> 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; i<LEDOffset; i++)
 			pose(i).value=state->outputs[i];
 		for(unsigned int i=LEDOffset+NumLEDs; i<NumOutputs; i++)
 			pose(i).value=state->outputs[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<LedMC> 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 <OPENR/OPENRAPI.h>
 #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 <fstream>
+#include <cmath>
+
+//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> 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<TinyMotionSequenceMC> 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<PIDMC>(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<PIDMC>(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; i<PIDJointOffset+NumPIDJoints; i++)
+			pushSlot(new TakeMeasurementControl(*this,i));
+		
+		filenameInput->setAcceptNonExistant(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 <vector>
 #include <sstream>
 
@@ -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<WaypointWalkMC> 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<float>("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<int>("Pos. coord. system",desc,(int*)&curway.posType));
+	pushSlot(new ValueEditControl<WaypointWalkMC::Waypoint::posType_t>("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<PostureMC>());
 		// 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<float>(wait,&state->pidduties[LFrLegOffset+RotatorOffset],CompareTrans<float>::LT,-.07,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7));
-    right->addTransition(new SmoothCompareTrans<float>(wait,&state->pidduties[RFrLegOffset+RotatorOffset],CompareTrans<float>::LT,-.07,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7));
+    left->addTransition(new SmoothCompareTrans<float>(wait,&state->pidduties[LFrLegOffset+RotatorOffset],CompareTrans<float>::LT,-.07,EventBase(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID),.7));
+    right->addTransition(new SmoothCompareTrans<float>(wait,&state->pidduties[RFrLegOffset+RotatorOffset],CompareTrans<float>::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<LedMC>());
@@ -63,11 +57,15 @@
 
 	{
 		MMAccessor<LedMC> 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<JPEGGenerator*>(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<JPEGGenerator*>(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<PNGGenerator*>(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<PNGGenerator*>(ProjectInterface::defGrayscalePNGGenerator);
-			chan=config->vision.rawcam_channel;
+			chan=config->vision.rawcam.channel;
 		}
 		if(png!=NULL) {
 			// open file
@@ -166,10 +164,21 @@
 	{
 		MMAccessor<LedMC> 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<const VisionObjectEvent*>(&event)->getCenterX();
 		vert=static_cast<const VisionObjectEvent*>(&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(tilt<DtoR(-20))
-		tilt=DtoR(-20);
-	if(tilt>DtoR(40))
-		tilt=DtoR(40);
-	if(pan>DtoR(80))
-		pan=DtoR(80);
-	if(pan<DtoR(-80))
-		pan=DtoR(-80);
-	HeadPointerMC * headpointer= (HeadPointerMC*)motman->checkoutMotion(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<HeadPointerMC>(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<const FilterBankEvent&>(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<WalkMC> 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<float>(turn,&state->sensors[IRDistOffset],CompareTrans<float>::LT,350,EventBase(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID),.7));
+	move->addTransition(new SmoothCompareTrans<float>(turn,&state->sensors[IRDistOffset],CompareTrans<float>::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<PIDMC>(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()<last_seen+1000)
+				return;
+			cout << endl;
+			
+			const VisionObjectEvent& visob = dynamic_cast<const VisionObjectEvent&>(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"<<state->outputs[HeadOffset] <<' '<< state->outputs[HeadOffset+1] <<' '<< state->outputs[HeadOffset+2] << endl <<kine->getTransform(CameraFrameOffset);
+			hit=kine->projectToPlane(CameraFrameOffset,ray,BaseFrameOffset,p,CameraFrameOffset);
+			cout << "Intersection_camera: (" << hit(1)<<','<<hit(2)<<','<<hit(3)<<')'<<endl;
+			hit=kine->projectToPlane(CameraFrameOffset,ray,BaseFrameOffset,p,BaseFrameOffset);
+			cout << "Intersection_base: (" << hit(1)<<','<<hit(2)<<','<<hit(3)<<')'<<endl;
+			last_seen=get_time();
 		} else {
 			ASSERT(false,"unprocessed event " << e.getName() << endl);
 		}
@@ -77,6 +115,10 @@
 protected:
 	EventBase head_release; //!< event template to match to signal the head's PID joints should be relaxed
 	EventBase head_lock;    //!< event template to match to signal the head's PID joints should be powered up again
+	EventBase target_toggle; //!< event template to indicate that the behavior should watch for visual targets are report their position
+	bool targeting; //!< whether currently targeting
+	EventBase visual_target; //!< event template for the object to track the position of
+	unsigned int last_seen;  //!< time that the last report regarding visual_target's position was displayed
 	EventBase clock;        //!< event template to match to signal a new round of calculations should be performed
 };
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Demos/HeadLevelBehavior.h ./Behaviors/Demos/HeadLevelBehavior.h
--- ../Tekkotsu_3.0/Behaviors/Demos/HeadLevelBehavior.h	2004-11-10 20:45:36.000000000 -0500
+++ ./Behaviors/Demos/HeadLevelBehavior.h	2007-06-26 00:27:43.000000000 -0400
@@ -23,16 +23,8 @@
 			head(),
 			head_id(MotionManager::invalid_MC_ID), pid_id(MotionManager::invalid_MC_ID)
 	{
-		if(state->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<std::string> 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<ResamplingPolicy*>(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<DistributionPolicy*>(&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<DualCoding::PFShapeLocalization::particle_type> MotionModel;
+		if(MotionModel * motion = dynamic_cast<MotionModel*>(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<LedMC> 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<const VisionObjectEvent&>(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<LedMC> 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<HeadPointerMC> 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<LegOrder_t>((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<HeadPointerMC> 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<PostureMC> 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 <fstream>
 
+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<double> p(w.size());
 		double wsum=0;
-		cout << "w =";
+		std::cout << "w =";
 		for(unsigned int i=0; i<w.size(); i++)
-			cout << ' ' << w[i];
-		cout << endl;
+			std::cout << ' ' << w[i];
+		std::cout << std::endl;
 		for(unsigned int i=0; i<w.size(); i++)
 			wsum+=w[i];
 		for(unsigned int i=0; i<w.size(); i++)
 			p[i]=(1-g)*w[i]/wsum+g/w.size();
-		cout << "p =";
+		std::cout << "p =";
 		for(unsigned int i=0; i<w.size(); i++)
-			cout << ' ' << p[i];
-		cout << endl;
+			std::cout << ' ' << p[i];
+		std::cout << std::endl;
 		double psum=0;
 		for(unsigned int i=0; i<w.size(); i++)
 			psum+=p[i];
@@ -53,9 +53,9 @@
 	void reward(bool r) {
 		if(r) {
 			w[last]*=exp(g/lastp/w.size());
-			cout << "REWARD! :)" << endl;
+			std::cout << "REWARD! :)" << std::endl;
 		} else
-			cout << "no reward. :(" << endl;
+			std::cout << "no reward. :(" << std::endl;
 	}
 	//!resets weights
 	void reset() {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/CameraStreamBehavior.cc ./Behaviors/Mon/CameraStreamBehavior.cc
--- ../Tekkotsu_3.0/Behaviors/Mon/CameraStreamBehavior.cc	2006-09-09 00:32:27.000000000 -0400
+++ ./Behaviors/Mon/CameraStreamBehavior.cc	2007-11-11 18:57:19.000000000 -0500
@@ -6,6 +6,8 @@
 #include "Shared/Config.h"
 #include "Shared/WorldState.h"
 
+using namespace std;
+
 #if DEBUG
 void CameraStreamBehavior::processEvent(const EventBase& e) {
 	ASSERTRET(e.getGeneratorID()==EventBase::sensorEGID,"unexpected event");
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/EStopControllerBehavior.cc ./Behaviors/Mon/EStopControllerBehavior.cc
--- ../Tekkotsu_3.0/Behaviors/Mon/EStopControllerBehavior.cc	2004-10-07 15:07:04.000000000 -0400
+++ ./Behaviors/Mon/EStopControllerBehavior.cc	2007-05-21 16:51:20.000000000 -0400
@@ -10,7 +10,7 @@
 	// We listen to the estop
 	erouter->addListener(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(; i<args.size(); i++) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Behaviors/Mon/HeadPointControllerBehavior.cc ./Behaviors/Mon/HeadPointControllerBehavior.cc
--- ../Tekkotsu_3.0/Behaviors/Mon/HeadPointControllerBehavior.cc	2006-09-10 13:00:43.000000000 -0400
+++ ./Behaviors/Mon/HeadPointControllerBehavior.cc	2007-11-12 13:00:41.000000000 -0500
@@ -2,6 +2,8 @@
 #include "Behaviors/Controller.h"
 #include "Motion/MMAccessor.h"
 #include "Motion/HeadPointerMC.h"
+#include "Shared/ERS7Info.h"
+#include "Shared/ERS210Info.h"
 
 HeadPointControllerBehavior* HeadPointControllerBehavior::theOne = NULL;
 
@@ -23,6 +25,7 @@
 #endif
 	
 	// Find out what type of command this is
+#ifdef TGT_IS_AIBO
 	switch(command[0]) {
 	case CMD_tilt:
 		t = fabs(param)*outputRanges[HeadOffset+TiltOffset][param>0?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<HeadPointerMC>());
+	SharedObject<HeadPointerMC> 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<std::string> 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<const JPEGGenerator*>(&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<const JPEGGenerator*>(&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<const JPEGGenerator*>(&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: <i>beginning</i> of each Vision packet, <i>before</i> the FilterBankGenerator header. 
  *  - <@c string:"TekkotsuImage">
- *  - <<tt>Config::vision_config::encoding_t</tt>: rawcam_encoding> <i>(expect single or multiple channels, 0 means color (3 channels), 1 means intensity (1 channel))</i>
- *  - <<tt>Config::vision_config::compression_t</tt>: rawcam_compression> <i>(0==none, 1==jpeg, 2==rle)</i>
+ *  - <<tt>Config::vision_config::encoding_t</tt>: rawcam.encoding> <i>(expect single or multiple channels, 0 means color (3 channels), 1 means intensity (1 channel))</i>
+ *  - <<tt>Config::vision_config::compression_t</tt>: rawcam.compression> <i>(0==none, 1==jpeg, 2==rle)</i>
  *  - <@c unsigned @c int: width> <i>(this is the width of the largest channel - note different channels can be sent at different resolutions!  Provides cheap "compression" of chromaticity channels)</i>
  *  - <@c unsigned @c int: height> <i>(similarly, height of largest channel)</i>
  *  - <@c unsigned @c int: timestamp> <i>(time image was taken, milliseconds since boot)</i>
@@ -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<std::string> 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<RegionGenerator*>(&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<const SegmentedColorGenerator*>((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 <sstream>
+
+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<HeadPointerMC>());
+	arm = motman->addPersistentMotion(SharedObject<PostureMC>());
+}
+
+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<PostureMC>(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<PostureMC>(arm)->solveLinkPosition(tgtX,tgtY,tgtZ,ArmOffset+NumArmJoints-1,0,0,0);
+#elif defined(TGT_HAS_LEGS)
+	MMAccessor<PostureMC>(arm)->solveLinkPosition(tgtX,tgtY,tgtZ,PawFrameOffset,0,0,0);
+#endif
+}
+
+void RoverControllerBehavior::updateHead() {
+	if(maxDist)
+		MMAccessor<HeadPointerMC>(head)->lookAtPoint(lookX,lookY,tgtZ);
+	else
+		MMAccessor<HeadPointerMC>(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<std::string> 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<RLEGenerator*>(&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<const SegmentedColorGenerator*>(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<Transition*>(e.getSourceID());
-		const std::vector<StateNode*>& incoming=trans->getSources();
-		const std::vector<StateNode*>& outgoing=trans->getDestinations();
-		for(std::vector<StateNode*>::const_iterator it=incoming.begin(); it!=incoming.end() && !care; it++)
-			care=isListening(*it);
-		for(std::vector<StateNode*>::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("<event>\n");
-			indent(1);
-			cmdsock->printf("<fire id=\"%s\" time=\"%d\" />\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<StateNode*>(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="<event><state%s id=\"%s\" time=\"%d\" /></event>\n"; // unexpected
-				else {
-					queuedEvents.push(e);
-					return;
-				}
-			} else
-				format="  <state%s id=\"%s\" time=\"%d\" />\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("</event>\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<StateNode*>& subnodes=n->getNodes();
-	if(subnodes.size()==0) {
-		// it's a leaf node, no subnodes or transitions between them
-		indent(depth);
-		cmdsock->printf("<state class=\"%s\" id=\"%s\" />\n", n->getClassName().c_str(), n->getName().c_str());
-	} else {
-
-		// first output current node's info
-		indent(depth);
-		cmdsock->printf("<state class=\"%s\" id=\"%s\">\n", n->getClassName().c_str(), n->getName().c_str());
-
-		std::set<const Transition*> transitions;
-		// now recurse on sub-nodes, extracting all of the subnodes transitions
-		for(unsigned int i=0; i<subnodes.size(); i++) {
-			spider(subnodes[i],depth+1);
-			const std::vector<Transition*>& curt=subnodes[i]->getTransitions();
-			transitions.insert(curt.begin(),curt.end());
-		}
-
-		// now output transitions between subnodes we collected in previous step
-		for(std::set<const Transition*>::const_iterator it=transitions.begin(); it!=transitions.end(); it++) {
-			indent(depth+1);
-			cmdsock->printf("<transition class=\"%s\" id=\"%s\">\n", (*it)->getClassName().c_str(), (*it)->getName().c_str());
-			const std::vector<StateNode*>& incoming=(*it)->getSources();
-			for(unsigned int i=0; i<incoming.size(); i++) {
-				indent(depth+2);
-				cmdsock->printf("<source>%s</source>\n",incoming[i]->getName().c_str());
-			}
-			const std::vector<StateNode*>& outgoing=(*it)->getDestinations();
-			for(unsigned int i=0; i<outgoing.size(); i++) {
-				indent(depth+2);
-				cmdsock->printf("<destination>%s</destination>\n",outgoing[i]->getName().c_str());
-			}
-			indent(depth+1);
-			cmdsock->printf("</transition>\n");
-		}
-
-		indent(depth);
-		cmdsock->printf("</state>\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; i<level; i++)
-		cmdsock->printf("  ");
-}
-
-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<const StateNode*>(*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<const StateNode*>(*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<const StateNode*>(*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("<model></model>\n");
-		} else {
-			cmdsock->printf("<model>\n");
-			spider(n);
-			cmdsock->printf("</model>\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; i<bytes; i++) {
-		if(buf[i]=='\n') {
-			SpiderMachineBehavior::theOne->runCommand(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 <queue>
-
-class StateNode;
-
-//! When active and connected over network socket, outputs structure of requested state machine(s)
-/*! The protocol is:
- *  - '<tt>list</tt>' - send list of all instantiated StateNodes
- *  - '<tt>spider </tt><i>name</i>' - spider the current structure of StateNode named <i>name</i>
- *  - '<tt>listen </tt><i>name</i>' - send updates regarding the activation status of <i>name</i> and its subnodes; you can specify a state which is not yet running
- *  - '<tt>ignore </tt><i>name</i>' - cancels a previous listen command
- *  - '<tt>clear</tt>' - 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 <tt>list</tt> command, the first line will be the number
- *  of StateNodes, followed by that number of lines, one StateNode
- *  name per line.
- *
- *  After a <tt>spider</tt> 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
- *  ("<model></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
- <!DOCTYPE model [
- <!ELEMENT model (state*, transition*)>
- <!ELEMENT state (state*, transition*)>
- <!ELEMENT transition (source+, dest+)>
- <!ELEMENT source (#PCDATA)>
- <!ELEMENT dest (#PCDATA)>
- 
- <!ATTLIST state id CDATA #REQUIRED>
- <!ATTLIST state class CDATA #REQUIRED>
- <!ATTLIST transition id CDATA #REQUIRED>
- <!ATTLIST transition class CDATA #REQUIRED>
- ]>@endverbatim
- *
- *  The format of status updates following a listen command is:
- @verbatim
- <!DOCTYPE event [
- <!ELEMENT event (fire*, statestart*, statestop*)>
- <!ELEMENT fire (EMPTY)>
- <!ELEMENT statestart (EMPTY)>
- <!ELEMENT statestop (EMPTY)>
-
- <!ATTLIST fire id CDATA #REQUIRED>
- <!ATTLIST fire time CDATA #REQUIRED>
- <!ATTLIST statestart id CDATA #REQUIRED>
- <!ATTLIST statestart time CDATA #REQUIRED>
- <!ATTLIST statestop id CDATA #REQUIRED>
- <!ATTLIST statestop time CDATA #REQUIRED>
- ]>@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<BehaviorBase*> registry_t; //!< the type of the behavior registry (BehaviorBase::registry)
-	typedef std::multiset<const StateNode*> expected_t; //!< the type of #expected
-	typedef std::set<std::string> listen_t; //!< the type of #listen
-	typedef std::queue<EventBase> 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 <iostream>
-#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 <iostream>
 
 //! 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<float>()+2*LoadSave::getSerializedSize<unsigned int>();
-	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<float>()+6*LoadSave::getSerializedSize<unsigned int>()+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 <string>
 
 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<class T>
-	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<PostureMC,defPostureNodeName,defPostureNodeDesc,true> {
+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<PostureMC,defPostureNodeName,defPostureNodeDesc,true>(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<PostureMC,defPostureNodeName,defPostureNodeDesc,true>::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(tilt<outputRanges[HeadOffset+TiltOffset][MinRange]*3/4)
-		tilt=outputRanges[HeadOffset+TiltOffset][MinRange]*3/4;
-	if(pan>outputRanges[HeadOffset+PanOffset][MaxRange]*2/3)
-		pan=outputRanges[HeadOffset+PanOffset][MaxRange]*2/3;
-	if(pan<outputRanges[HeadOffset+PanOffset][MinRange]*2/3)
-		pan=outputRanges[HeadOffset+PanOffset][MinRange]*2/3;
-	{MMAccessor<HeadPointerMC>(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(tilt<outputRanges[tiltIdx][MinRange]*3/4)
+		tilt=outputRanges[tiltIdx][MinRange]*3/4;
+	if(pan>outputRanges[panIdx][MaxRange]*2/3)
+		pan=outputRanges[panIdx][MaxRange]*2/3;
+	if(pan<outputRanges[panIdx][MinRange]*2/3)
+		pan=outputRanges[panIdx][MinRange]*2/3;
+	MMAccessor<HeadPointerMC>(headpointer_id)->setJoints(tilt,pan,0); // note no variable name, one-line scope
 	
 	{
 		MMAccessor<WalkMC> 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<typename W, const char* mcName=defWaypointWalkNodeName, const char* mcDesc=defWaypointWalkNodeDesc>
+class WaypointEngineNode : public MCNode<W,mcName,mcDesc> {
+public:
+
+  //! constructor
+  WaypointEngineNode() : MCNode<W,mcName,mcDesc>() {}
+
+  //! constructor
+  WaypointEngineNode(const std::string& name) : MCNode<W,mcName,mcDesc>(name) {}
+
+  //!destructor
+  ~WaypointEngineNode() {}
+
+  virtual void DoStart() {
+    MCNode<W,mcName,mcDesc>::DoStart();
+    erouter->addListener(this,EventBase::locomotionEGID,MCNode<W,mcName,mcDesc>::getMC_ID(),EventBase::statusETID);
+  }
+
+protected:
+
+  //! constructor
+  WaypointEngineNode(const std::string& className, const std::string& instanceName) : 
+    MCNode<W,mcName,mcDesc>(className,instanceName) {}
+
+  void processEvent(const EventBase &event) {
+    if ( static_cast<const LocomotionEvent&>(event).isStop() )
+      MCNode<W,mcName,mcDesc>::postCompletionEvent();
+  }
+
+};
+
+//! the prototypical WaypointWalkNode, using a WaypointWalkMC
+typedef WaypointEngineNode<WaypointWalkMC> 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; i<ERS210Info::EarOffset+ERS210Info::NumEarJoints; i++)
+		if(RobotName == ERS210Info::TargetName) {
+			int ear=capabilities.getOutputOffset(ERS210Info::outputNames[ERS210Info::EarOffset]);
+			for(unsigned int i=ear; i<ear+ERS210Info::NumEarJoints; i++)
 				pose->setOutputCmd(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; i<ERS7Info::EarOffset+ERS7Info::NumEarJoints; i++)
+		} else if(RobotName == ERS220Info::TargetName) {
+			int light=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::RetractableHeadLEDOffset]);
+			pose->setOutputCmd(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; i<ear+ERS7Info::NumEarJoints; i++)
 				pose->setOutputCmd(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 ParticleT>
+class DeadReckoningBehavior : public BehaviorBase, public HolonomicMotionModel<ParticleT> {
+public:
+	//! constructor
+	explicit DeadReckoningBehavior(const std::string& name="DeadReckoningBehavior") : BehaviorBase(name), HolonomicMotionModel<ParticleT>() {}
+	
+	//! constructor
+	DeadReckoningBehavior(float xVariance, float yVariance, float aVariance)
+	: BehaviorBase("DeadReckoningBehavior"), HolonomicMotionModel<ParticleT>(xVariance,yVariance,aVariance) {}
+	
+	virtual void DoStart() {
+		BehaviorBase::DoStart(); // do this first (required)
+		HolonomicMotionModel<ParticleT>::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<const LocomotionEvent&>(event);
+			HolonomicMotionModel<ParticleT>::setVelocity(locoevt.x,locoevt.y,locoevt.a,locoevt.getTimeStamp());
+		} else if (event.getGeneratorID() == EventBase::timerEGID) {
+			float tempx;
+			float tempy;
+			float tempa;
+			HolonomicMotionModel<ParticleT>::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<ParticleT>() {}
+};
+
+/*! @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<<TopBrLEDOffset; //default in case we don't recognize model
-			if(state->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; j<NumLEDs; j++)
@@ -174,6 +186,7 @@
 	ms->play();
 }
 
+#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<std::string> 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 <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/state.shtml">tutorial page on State Machines</a>.
+ *  
  *  There are two StateNode templates in <a href="http://cvs.tekkotsu.org/cgi/viewcvs.cgi/Tekkotsu/project/templates/"><i>project</i><tt>/templates/</tt></a>:
  *  - <a href="http://cvs.tekkotsu.org/cgi/viewcvs.cgi/Tekkotsu/project/templates/statenode.h?rev=HEAD&content-type=text/vnd.viewcvs-markup">statenode.h</a>
  *    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<size_t>(this),EventBase::statusETID,0,getName(),1);
+	erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast<size_t>(this),EventBase::activateETID,0,getName(),1);
 
 	for(unsigned int i=0; i<srcs.size(); i++)
 		if(srcs[i]->isActive()) //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<size_t>(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<size_t>(getSources()[i]),
 			   EventBase::statusETID);
     };
   }
@@ -47,7 +47,7 @@
   virtual void processEvent(const EventBase &event) {
     int numcomplete = 0;
     for ( unsigned int i=0; i<getSources().size(); i++ ) {
-      if ( event.getSourceID() == (unsigned int)getSources()[i] )
+      if ( event.getSourceID() == reinterpret_cast<size_t>(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<size_t>(this),EventBase::activateETID,0,getName(),1);
+	
   if ( sound.size()!=0 )
     sndman->playFile(sound);
 
@@ -56,6 +59,8 @@
       };
   }
 
+	erouter->postEvent(EventBase::stateTransitionEGID,reinterpret_cast<size_t>(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]<distanceThreshold)
 			fire();
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/AgentData.cc ./DualCoding/AgentData.cc
--- ../Tekkotsu_3.0/DualCoding/AgentData.cc	2006-05-19 13:14:59.000000000 -0400
+++ ./DualCoding/AgentData.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"  // agentDataType
 
 #include "SketchSpace.h"
@@ -17,6 +17,8 @@
 #include "AgentData.h"
 #include "ShapeAgent.h"
 
+using namespace std;
+
 namespace DualCoding {
 
 DATASTUFF_CC(AgentData);
@@ -51,17 +53,17 @@
 	//cout << "color = " << getColor() << 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 AgentData::applyTransform(const NEWMAT::Matrix& Tmat) {
+void AgentData::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) {
   //  cout << "AgentData::applyTransform: " << getId() << endl;
   //  cout << Tmat << endl;
-  center_pt.applyTransform(Tmat);
-  orientation_pt.applyTransform(Tmat);
+  center_pt.applyTransform(Tmat,newref);
+  orientation_pt.applyTransform(Tmat,newref);
   orientation = orientation - (AngTwoPi)atan2(Tmat(1,2),Tmat(1,1));
   //  updateOrientation();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/AgentData.h ./DualCoding/AgentData.h
--- ../Tekkotsu_3.0/DualCoding/AgentData.h	2006-10-03 19:23:00.000000000 -0400
+++ ./DualCoding/AgentData.h	2007-11-09 13:08:32.000000000 -0500
@@ -4,7 +4,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"  // agentDataType
 
 namespace DualCoding {
@@ -13,6 +13,7 @@
 class SketchSpace;
 template<typename T> 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<ShapeRoot> &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<typename T> class Sketch;
 class ShapeRoot;
+class ShapeSpace;
 class SketchDataRoot;
 template<typename T> 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<bool>& getRendering();
   
+private:
   //! Render into a sketch space.
   virtual Sketch<bool>* 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<run> &_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<Shape<BlobData> >
 BlobData::extractBlobs(const Sketch<bool> &sketch, 
-		       const set<int>& 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<bool> to
   // Sketch<uchar> is done with a simple reinterpret_cast; no copying.
-  std::vector<Shape<BlobData> > result(extractBlobs((Sketch<uchar>&)sketch,colors,minarea,orient,maxblobs));
-  rgb rgbvalue(sketch->getColor());
+  set<color_index> dummyColors;
+  dummyColors.insert(1); // converting bool to uchar always yields color index 1
+  map<color_index,int> minareas;
+  minareas[1] = minarea;
+  map<color_index,BlobOrientation_t> orients;
+  orients[1] = orient;
+  map<color_index,coordinate_t> heights;
+  heights[1] = height;
+  std::vector<Shape<BlobData> > result(extractBlobs((Sketch<uchar>&)sketch,dummyColors,minareas,orients,heights,maxblobs));
+  rgb sketchColor(sketch->getColor());
   for ( std::vector<Shape<BlobData> >::iterator it = result.begin();
 	it != result.end(); it++ )
-    (*it)->setColor(rgbvalue);
+    (*it)->setColor(sketchColor);
   return result;
 }
 
 std::vector<Shape<BlobData> > 
-BlobData::extractBlobs(const Sketch<bool> &sketch, int minarea,
-	     BlobData::BlobOrientation_t orient, int maxblobs) {
+BlobData::extractBlobs(const Sketch<uchar> &sketch,
+		       int minarea,
+		       BlobOrientation_t orient,
+		       coordinate_t height,
+		       int maxblobs) {
   const int numColors = ProjectInterface::getNumColors();
-  set<int> colors;
-  for (int i = 1; i < numColors; i++) colors.insert(i);
-  return extractBlobs(sketch, colors, minarea, orient, maxblobs);
+  set<color_index> colors;
+  map<color_index,int> minareas;
+  map<color_index,BlobOrientation_t> orients;
+  map<color_index,coordinate_t> 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<Shape<BlobData> >
 BlobData::extractBlobs(const Sketch<uchar> &sketch, 
-		       const set<int>& colors, int minarea,
-		       BlobData::BlobOrientation_t orient, int maxblobs) {
+		       const std::set<color_index>& colors,
+		       const std::map<color_index,int>& minareas,
+		       const std::map<color_index,BlobOrientation_t>& orients,
+		       const std::map<color_index,coordinate_t>& 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<int>::const_iterator it = colors.begin();
+  for (set<color_index>::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<map<color_index,int>&>(minareas)[color];
+      BlobOrientation_t const orient = (orients.find(color)==orients.end()) ? 
+	groundplane : const_cast<map<color_index,BlobOrientation_t>&>(orients)[color];
+      coordinate_t const height = (heights.find(color)==heights.end()) ? 0 : const_cast<map<color_index,coordinate_t>&>(heights)[color];
       for (int i=0; list_head!=NULL && i<maxblobs && list_head->area >= 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<BlobData>(blobdat));
       }
@@ -275,20 +284,11 @@
   return result;
 }
 
-std::vector<Shape<BlobData> > 
-BlobData::extractBlobs(const Sketch<uchar> &sketch, int minarea,
-	     BlobData::BlobOrientation_t orient, int maxblobs) {
-  const int numColors = ProjectInterface::getNumColors();
-  set<int> 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 &reg,
-			     const CMVision::run<uchar> *rle_buff, 
-			     const BlobData::BlobOrientation_t orient,
+			     const CMVision::run<CMVision::uchar> *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<Point> BlobData::findCorners(unsigned int nExpected, 
+					   std::vector<Point>& 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<Point> BlobData::findCorners(unsigned int nExpected, std::vector<Point>& candidates, float &bestValue)
-  {
     std::vector<Point> 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<BlobData> &b1, const Shape<BlobData> &b2) const {
+bool BlobData::AreaLessThan::operator() (const Shape<BlobData> &b1, const Shape<BlobData> &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 <vector>
 #include <set>
+#include <map>
 #include <iostream>
 #include <string>
 
@@ -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<run> 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<run> 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<run> &_runvec, 
-	   const BlobOrientation_t _orientation,
-	   const rgb rgbvalue);
+	   const float _area=0,
+	   const std::vector<run> &_runvec=std::vector<run>(), 
+	   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<bool> as a vector of Shape<BlobData>
   static std::vector<Shape<BlobData> > 
-  extractBlobs(const Sketch<bool> &sketch, 
-	       const set<int>& colors, int minarea=0,
-	       BlobData::BlobOrientation_t orient=BlobData::groundplane, 
-	       int maxblobs=50);
-  static std::vector<Shape<BlobData> > 
-  extractBlobs(const Sketch<bool> &sketch, int minarea=0,
-	       BlobData::BlobOrientation_t orient=BlobData::groundplane, 
+  extractBlobs(const Sketch<bool> &sketch,
+	       int minarea=25,
+	       BlobOrientation_t orient=BlobData::groundplane, 
+	       coordinate_t height=0,
 	       int maxblobs=50); 
 
-  //! Import blobs from Sketch<uchar> as a vector of Shape<BlobData>
+  //! Import blobs of all colors from Sketch<uchar> as a vector of Shape<BlobData>
   static std::vector<Shape<BlobData> >
-  extractBlobs(const Sketch<CMVision::uchar> &sketch, 
-	       const set<int>& colors, int minarea=0,
-	       BlobData::BlobOrientation_t orient=BlobData::groundplane,
+  extractBlobs(const Sketch<uchar> &sketch,
+	       int minarea=25,
+	       BlobOrientation_t orient=BlobData::groundplane,
+	       const coordinate_t height=0,
 	       int maxblobs=50);
+
+  //! Import blobs of specified colors from Sketch<uchar> as a vector of Shape<BlobData>
   static std::vector<Shape<BlobData> >
-  extractBlobs(const Sketch<CMVision::uchar> &sketch, int minarea=0,
-	       BlobData::BlobOrientation_t orient=BlobData::groundplane,
-	       int maxblobs=50);
+  extractBlobs(const Sketch<uchar> &sketch, 
+	       const std::set<color_index>& colors,
+	       const std::map<color_index,int>& minareas,
+	       const std::map<color_index,BlobOrientation_t>& orients,
+	       const std::map<color_index,coordinate_t>& 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 &reg, 
 	   const CMVision::run<CMVision::uchar> *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<Point> findCorners(unsigned int nExpected, std::vector<Point>& candidates, float &bestValue);
-
   std::vector<Point> findCornersDerivative();
-
   std::vector<Point> findCornersDiagonal();
-
   std::vector<Point> findCornersShapeFit(unsigned int ncorners, std::vector<Point>& candidates, float &bestValue);
-
+  //@}
 
  // comparison predicates
 
-  class areaLessThan : public BinaryShapePred<BlobData> {
+  class AreaLessThan : public BinaryShapePred<BlobData> {
   public:
     bool operator() (const Shape<BlobData> &b1, const Shape<BlobData> &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: ("<<centroid.coordX()<<","<<centroid.coordY()<<","<<centroid.coordZ()<<")\n";
+  centroid.setRefFrameType(egocentric);
+  std::cout << "New centroid: " << centroid << endl;
 
 }
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/BrickData.h ./DualCoding/BrickData.h
--- ../Tekkotsu_3.0/DualCoding/BrickData.h	2006-07-21 13:57:45.000000000 -0400
+++ ./DualCoding/BrickData.h	2007-11-11 18:57:20.000000000 -0500
@@ -4,7 +4,6 @@
 
 #include <vector>
 #include <iostream>
-#include <string>
 
 #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<Shape<BlobData> > blobs2,
 							    std::vector<Shape<BlobData> > blobs3);
 
-  static Shape<BrickData> extractBrick(ShapeSpace& space, vector<Shape<BlobData> > &blobs);
+  static Shape<BrickData> extractBrick(ShapeSpace& space, std::vector<Shape<BlobData> > &blobs);
     
-  static vector<Point> findOrthogonalBoundingBox(ShapeSpace& space, Shape<BlobData> blob, Point centroid, Shape<LineData> parallel);
+  static std::vector<Point> findOrthogonalBoundingBox(ShapeSpace& space, Shape<BlobData> blob, Point centroid, Shape<LineData> parallel);
 private:
   //! Render into a sketch space and return reference. (Private.)
   Sketch<bool>* 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<Point>& corners, Sketch<bool> edgeImage, 
+  float getBoundingQuadrilateralScore(BlobData &blob, std::vector<Point>& corners, Sketch<bool> edgeImage, 
 				      int& borderCount, ShapeSpace &space);
 
   float getBoundingQuadrilateralInteriorPointRatio(BlobData &blob, 
-						   vector<Point>& corners, 
+						   std::vector<Point>& corners, 
 						   ShapeSpace &space);
 
-  float getQuadrilateralArea(vector<Point>& corners);
+  float getQuadrilateralArea(std::vector<Point>& corners);
 
-  int countBorderPixelFit(BlobData &blob, const vector<Point> &corners, 
+  int countBorderPixelFit(BlobData &blob, const std::vector<Point> &corners, 
 			  Sketch<bool> edges, ShapeSpace &space);
      
-  int pickMove(vector<float> scores, float weight);
+  int pickMove(std::vector<float> 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<Point,Point> 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<Point,Point> 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<Region> regionlist = Region::extractRegions(labels,REGION_THRESH);
   std::vector<Shape<EllipseData> > 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<Point,Point> findFeaturePoints() const;
+  std::pair<Point,Point> 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<float> 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<PointData> LineData::firstPtShape() {
+  Shape<PointData> result(new PointData(*space, firstPt()));
+  result->setName("firstPt");
+  result->inheritFrom(*this);
+  result->setViewable(false);
+  return result;
+}
+
+Shape<PointData> LineData::secondPtShape() {
+  Shape<PointData> 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<LineData*>(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<float,float> 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<float> 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<float> 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<LineData>& 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<LineData>& 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<Region> 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 <<std::endl;
   
-  NEW_SKETCH_N(skelDist,usint,visops::edist(skeleton));
+  NEW_SKETCH_N(skelDist,uint,visops::edist(skeleton));
   if ( abs(m) <= 1 )  // when |slope| <= 1, scan along x, else scan along y
     extracted_line->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<bool>& 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<usint>& skelDist, 
+void LineData::scanHorizForEndPts(const Sketch<uint>& skelDist, 
 				  const Sketch<bool>& 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<usint>& skelDist, 
+void LineData::scanVertForEndPts(const Sketch<uint>& skelDist, 
 				  const Sketch<bool>& 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<bool>& sketch) {
   const Sketch<bool>& line_rendering = getRendering();
-  usint const clear_dist = 5;
+  uint const clear_dist = 5;
   Sketch<bool> 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<LineData> &line) {
+bool LineData::IsHorizontal::operator() (const Shape<LineData> &line) const {
       const AngPi orient = line->getOrientation();
       return  (orient <= threshold) || (orient >= M_PI - threshold);
     }
 
+bool LineData::IsVertical::operator() (const Shape<LineData> &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 <vector>
 #include <iostream>
-#include <string>
 
 #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<LineData> 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<PointData> topPtShape();
   Shape<PointData> bottomPtShape();
 
-  //! The first point of a line is the leftmost point if the line is horizontal, 
-  //! else the topmost point.  With an optional Shape<LineData> argument, uses the current
-  //! line's orientation to pick the appropriate point of the other line.
-  //@{
   EndPoint& firstPt();
   EndPoint& firstPt(const Shape<LineData> &otherline) const;
   EndPoint& secondPt();
   EndPoint& secondPt(const Shape<LineData> &otherline) const;
 
+  Shape<PointData> firstPtShape();
+  Shape<PointData> secondPtShape();
+
   coordinate_t firstPtCoord() const;
   coordinate_t firstPtCoord(const Shape<LineData> &otherline) const;
   coordinate_t secondPtCoord() const;
   coordinate_t secondPtCoord(const Shape<LineData> &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<float,float> lineEquation_mb() const;
-  vector<float> lineEquation_abc() const;
-  vector<float> lineEquation_abc_xz() const;
+  std::pair<float,float> lineEquation_mb() const;
+  std::vector<float> lineEquation_abc() const;
+  std::vector<float> 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<LineData> &other);
@@ -160,7 +161,7 @@
   //@}
   
   
-  //! Predicates based on line length.
+  //!@name Predicates based on line length
   //@{
   bool isLongerThan(const Shape<LineData>& 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<LineData>& 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<LineData> extractLine(Sketch<bool>& skelsketch, 
 				     const Sketch<bool>& occlusions);
+  //@}
   
   //! Helper functions used by extractLine().
   //@{
@@ -221,17 +221,17 @@
   //! Clears a line from a sketch.
   void clearLine(Sketch<bool>& sketch);
   
-  void scanHorizForEndPts(const Sketch<usint>& skelDist, const Sketch<bool>& occlusions,
+  void scanHorizForEndPts(const Sketch<uint>& skelDist, const Sketch<bool>& occlusions,
 			  float m, float b);
-  void scanVertForEndPts(const Sketch<usint>& skelDist, const Sketch<bool>& occlusions,
+  void scanVertForEndPts(const Sketch<uint>& skelDist, const Sketch<bool>& occlusions,
 			  float m, float b);
 
   void balanceEndPointHoriz(EndPoint &pt, Sketch<bool> const &occluders, float m, float b);
   void balanceEndPointVert(EndPoint &pt, Sketch<bool> const &occluders, float m, float b);
 
-  static vector<Shape<LineData> > extractLines(Sketch<bool> const& sketch, int const num_lines=10);
+  static std::vector<Shape<LineData> > extractLines(Sketch<bool> const& sketch, int const num_lines=10);
   
-  static vector<Shape<LineData> > extractLines(Sketch<bool> const& skel,
+  static std::vector<Shape<LineData> > extractLines(Sketch<bool> const& skel,
 					       Sketch<bool> 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<LineData> {
   public:
     bool operator() (const Shape<LineData> &ln1, const Shape<LineData> &ln2) const;
   };
 
+  //! True if difference in line orientations is <= tolerance (default 20 deg)
   class ParallelTest : public BinaryShapePred<LineData> {
   public:
     AngPi tolerance;
@@ -261,6 +263,7 @@
   };
 
 
+  //! True if difference in line orientations is 90 deg +/- tolerance (default 20 deg)
   class PerpendicularTest : public BinaryShapePred<LineData> {
   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<LineData> {
   public:
     AngPi ang_tol;
@@ -278,14 +282,23 @@
     bool operator() (const Shape<LineData> &line1, const Shape<LineData> &ln2) const;
   };
 
+  //! Predicate returns true if line orientation is within @a threshold of horizontal
   class IsHorizontal : public UnaryShapePred<LineData> {
   public:
     IsHorizontal(AngPi thresh=M_PI/6) : UnaryShapePred<LineData>(), threshold(thresh) {}
-    bool operator() (const Shape<LineData> &line);
+    bool operator() (const Shape<LineData> &line) const;
   private:
     AngPi threshold;
   };
       
+  //! Predicate returns true if line orientation is within threshold of vertical
+  class IsVertical : public UnaryShapePred<LineData> {
+  public:
+    IsVertical(AngPi thresh=M_PI/3) : UnaryShapePred<LineData>(), threshold(thresh) {}
+    bool operator() (const Shape<LineData> &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 <math.h>
+
+#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<LocalizationParticleData>& 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<bool>* 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<bool>& draw_result = 
+    *new Sketch<bool>(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<typename T> 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<bool>* 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<HeadPointerMC> head_mc;
+  SharedObject<PostureMC> posture_mc;
+  SharedObject<MediumMotionSequenceMC> 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<Point> Lookout::getVisionObjectData() {
+vector<DualCoding::Point> Lookout::groundSearchPoints() {
+  vector<Point> 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<LookoutPointRequest>(req);
+    break;
+  case LookoutRequest::scan:
+    pushRequest<LookoutScanRequest>(req);
+    break;
+  case LookoutRequest::track:
+    pushRequest<LookoutTrackRequest>(req); 
+    break;
+  case LookoutRequest::search:
+    pushRequest<LookoutSearchRequest>(req); 
+    break;
+  default:
+    cout << "Lookout::executeRequest: unknown request type " << req.getHeadMotionType() << endl;
+  };
+  const unsigned int reqid = requests.back()->requestID = ++idCounter;  
+  executeRequest();
+  return reqid;
 }
 
-vector<Point> 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<LookoutPointRequest*>(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<pixelHistograms.size(); i++ )
+	pixelHistograms[i].clear();
+      break;
+#ifdef TGT_HAS_IR_DISTANCE
+    case LookoutRequest::distanceResult:
+      while ( distanceSamples.size() > 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<HeadPointerMC>(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<PostureMC>(posture_id)->solveLinkVector(pt.coords,NearIRFrameOffset,Kinematics::pack(0,0,1));
+#else
+    successSave = MMAccessor<PostureMC>(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; i<pixelHistograms.size(); i++)
+    pixelHistograms[i][curPAR->image[i]]++;
+  if ( curPAR->sampleCounter < curPAR->numSamples )
+    return false;
+  // we have enough samples; compute the mode
+  for (size_t i = 0; i<pixelHistograms.size(); i++) {
+    unsigned int maxCount = 0;
+    uchar maxChar = 0;
+    for (map<uchar, unsigned int>::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; i<npops; i++ ) distanceSamples.pop();
+  return distanceSamples.top();
+}
+
+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
+}
+
+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<LookoutPointRequest*>(saveReq)->toBaseMatrix,
+					     EventBase::lookoutEGID, saveReq->requestID, EventBase::deactivateETID));
+      break;
+    case LookoutRequest::imageResult:
+      erouter->postEvent(LookoutSketchEvent(success,static_cast<LookoutPointRequest*>(saveReq)->image,
+					    static_cast<LookoutPointRequest*>(saveReq)->toBaseMatrix,
+					    EventBase::lookoutEGID, saveReq->requestID, EventBase::deactivateETID));
+      break;
+#ifdef TGT_HAS_IR_DISTANCE
+    case LookoutRequest::distanceResult:
+      erouter->postEvent(LookoutIREvent(success,getDistanceModeValue(), static_cast<LookoutPointRequest*>(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<LookoutScanRequest*>(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<uchar> 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<Point>& data, const set<color_index>& colors, int minArea) {
+  const unsigned char *img = 
+    ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0);
+  const color_class_state *regions = reinterpret_cast<const color_class_state*> (img);
+  for (set<color_index>::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<Point>& 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<ScanRequest*>(curReq);
-  if (curScanReq != curReq) curScanReq = dynamic_cast<ScanRequest*>(curReq);
+  const LookoutScanRequest* curScanReq = dynamic_cast<LookoutScanRequest*>(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<SmallMotionSequenceMC>(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<const ScanRequest::VisionTask*>(task);
-	  for(set<int>::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<ScanRequest::VisionRegionTask*>(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<LookoutRequest::VisionRegionTask*>(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<const VisionObjectEvent*>(&event);    
-      for (vector<ScanRequest::Task*>::iterator it = curScanReq->tasks.begin();
+      const VisionObjectEvent &voe = static_cast<const VisionObjectEvent&>(event);    
+      for (vector<LookoutRequest::Task*>::const_iterator it = curScanReq->tasks.begin();
 	   it != curScanReq->tasks.end(); it++)
-	if ((*it)->getTaskType() == ScanRequest::Task::visObj) {
-	  ScanRequest::VisionTask& vTask = *dynamic_cast<ScanRequest::VisionTask*>(*it);
+	if ((*it)->getTaskType() == LookoutRequest::Task::visObjTask) {
+	  LookoutRequest::VisionTask& vTask = *dynamic_cast<LookoutRequest::VisionTask*>(*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<Point>& data, const set<int>& colors, int minArea) {
-  const unsigned char *img = 
-    ProjectInterface::defRegionGenerator->getImage(ProjectInterface::fullLayer,0);
-  const color_class_state *regions = reinterpret_cast<const color_class_state*> (img);
-  for (set<int>::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<const LookoutScanRequest*>(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<LineData> &line = ShapeRootTypeConst(curScan->searchArea,LineData);
+    scanAlongLine(line->firstPt(), line->secondPt());
+    break;
+  }
+  case polygonDataType:{
+    const Shape<PolygonData> &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<LookoutScanRequest*>(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<const LookoutRequest::VisionTask*>(task);
+      for(set<color_index>::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<MediumMotionSequenceMC>(sequence_id)->play();
+}
+
+void Lookout::scanAlongLine(const Point& startPt, const Point& endPt) {
+  motman->setPriority(pointer_id,MotionManager::kIgnoredPriority); // just to be safe
+  MMAccessor<HeadPointerMC> pointer_acc(pointer_id);
+
+  // first compute joint angles for final point
+  pointer_acc->lookAtPoint(endPt.coordX(),endPt.coordY(),endPt.coordZ());
+	std::vector<float> anglesA(NumHeadJoints);
+	for(unsigned int i=0; i<NumHeadJoints; ++i)
+		anglesA[i]=pointer_acc->getJointValue(i);
   
-void Lookout::storeIRDataTo(vector<Point>& 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<float> anglesB(NumHeadJoints);
+	for(unsigned int i=0; i<NumHeadJoints; ++i)
+		anglesB[i]=pointer_acc->getJointValue(i);
+	
+	float total_joint_distance=0;
+	for(unsigned int i=0; i<NumHeadJoints; ++i) {
+		float diff = anglesA[i] - anglesB[i];
+		total_joint_distance += diff*diff;
+	}
+  const unsigned int movement_time = (unsigned int)(sqrt(total_joint_distance) / dynamic_cast<const LookoutScanRequest*>(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<MediumMotionSequenceMC> mseq_acc(sequence_id);
+  mseq_acc->clear();
+  mseq_acc->pause();
+#ifdef TGT_HAS_HEAD
+	for(unsigned int i=0; i<NumHeadJoints; ++i)
+		mseq_acc->setOutputCmd(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; i<NumHeadJoints; ++i)
+		mseq_acc->setOutputCmd(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<map<uchar, unsigned int> > colorCount(npixels);
-  if (modeRequest.numImages-- == 0) { // finished collecting samples, find modes
-    for (size_t i = 0; i<npixels; i++) {
-      unsigned int maxCount = 0; uchar maxChar = 0;
-      for (map<uchar, unsigned int>::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<Point> const &vertices, const bool closed) {
+	if ( vertices.size() == 0 )
+		requestComplete();
+	vector<Point> 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<HeadPointerMC> pointer_acc(pointer_id);
+	MMAccessor<MediumMotionSequenceMC> mseq_acc(sequence_id);
+	mseq_acc->pause();
+	mseq_acc->clear();
+	float const speed = dynamic_cast<const LookoutScanRequest*>(curReq)->scanSpeed;
+	std::vector<float> anglesA(NumHeadJoints,0), anglesB(NumHeadJoints,0);
+	for ( vector<Point>::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; i<NumHeadJoints; ++i)
+			anglesB[i]=pointer_acc->getJointValue(i);
+		if ( it != vertices_copy.begin() ) {
+			float total_joint_distance=0;
+			for(unsigned int i=0; i<NumHeadJoints; ++i) {
+				float diff = anglesA[i] - anglesB[i];
+				total_joint_distance += diff*diff;
+			}
+			const unsigned int movement_time = (unsigned int)(sqrt(total_joint_distance) /speed + 200);
+			// cout << "Movement time " << movement_time << "msec to " << *it << endl;
+			mseq_acc->advanceTime(movement_time);
+		}
+#ifdef TGT_HAS_HEAD
+		for(unsigned int i=0; i<NumHeadJoints; ++i)
+			mseq_acc->setOutputCmd(HeadOffset+i,anglesB[i]);
+		mseq_acc->advanceTime(200);
+		for(unsigned int i=0; i<NumHeadJoints; ++i)
+			mseq_acc->setOutputCmd(HeadOffset+i,anglesB[i]);
+#endif
+		anglesA.swap(anglesB);
 	}
-      modeRequest.image[i] = maxChar;
-      colorCount[i].clear();
-    }
-    return true;
-  }
-  else {
-    for (size_t i = 0; i<npixels; i++)
-      colorCount[i][modeRequest.image[i]]++;
-    return false;
+	
+	pointer_acc->lookAtPoint(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<const LookoutTrackRequest*>(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<HeadPointerMC>(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<const PointAtBase*>(curReq)->duration, false);
+
+void Lookout::processTrackEvent(const EventBase &event) {
+  const LookoutTrackRequest *curTR = static_cast<const LookoutTrackRequest*>(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<const CMVision::color_class_state*>
+      (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<HeadPointerMC>(pointer_id)->lookAtPoint(target.coordX(),target.coordY(),target.coordZ());
+  }
     break;
-  case EventBase::timerEGID:
-    if (event.getSourceID() == dur_timer) { 
-      PointAtBase* baseReq = dynamic_cast<PointAtBase*>(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<PointAtBase*>(curReq);
-    baseReq->toBaseMatrix = kine->jointToBase(baseReq->joint);
-    VRmixin::camSkS.clear();
-    StoreImageRequest& storeImageReq = *dynamic_cast<StoreImageRequest*>(curReq);
-    storeImageReq.image = (*storeImageReq.sketchFunc)();
-    if (StoreModeImageRequest* modeReq = dynamic_cast<StoreModeImageRequest*>(curReq))
-      if ( ! findPixelModes(*modeReq) ) {
-	erouter->addTimer(this, dur_timer, modeReq->interval, false);
-	return;
-      }
-    requestComplete();
-  }
     break;
-  case EventBase::sensorEGID: {
-    MeasureDistanceRequest* measureDistReq = dynamic_cast<MeasureDistanceRequest*>(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<const PointAtBase*>(&req)->getPointAtType()) {
-    case PointAtBase::storeImage:
-      if (dynamic_cast<const StoreModeImageRequest*>(&req))
-	pushRequest<StoreModeImageRequest>(req);
-      else
-	pushRequest<StoreImageRequest>(req);
-      break;
-    case PointAtBase::measureDist:
-      pushRequest<MeasureDistanceRequest>(req); break;
-    default: 
-      cout << "Lookout::executeRequest: unknown PointAtRequest type\n"; 
-      break;
-    };
-    break;
-  case LookoutRequest::pointAt:
-    switch (dynamic_cast<const PointAtRequest*>(&req)->getPointAtType()) {
-    case PointAtBase::none:
-      pushRequest<PointAtRequest>(req); break;
-    case PointAtBase::storeImage:
-      if (dynamic_cast<const StoreModeImageAtRequest*>(&req))
-	pushRequest<StoreModeImageAtRequest>(req);
-      else
-	pushRequest<StoreImageAtRequest>(req);
-      break;
-    case PointAtBase::measureDist:
-      pushRequest<MeasureDistanceAtRequest>(req); break;
-    default: cout << "Lookout::executeRequest: unknown PointAtRequest type\n"; break;
-    };
-    break;
-  case LookoutRequest::scan:
-    if (dynamic_cast<const ScanRequest*>(&req)->getScanType() == ScanRequest::line)
-      pushRequest<ScanAlongLineRequest>(req);
-    else
-      pushRequest<ScanAreaRequest>(req); 
-    break;
-  case LookoutRequest::track:
-    pushRequest<TrackRequest>(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<const PointAtBase*>(curReq)->duration,false);
-    break;
-  case LookoutRequest::pointAt: {
-    const Point& pt = dynamic_cast<const PointAtRequest*>(curReq)->gazePt;
-    if (dynamic_cast<const PointAtBase*>(curReq)->getPointAtType() == PointAtBase::measureDist) {
-      SharedObject<PostureMC> 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<HeadPointerMC> 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<ScanRequest*>(curReq)->tasks,
-			EventBase::lookoutEGID,curReq->requestID, EventBase::deactivateETID));
-  }
-  else if (curReq->getHeadMotionType() == LookoutRequest::pointAt
-	   || curReq->getHeadMotionType() == LookoutRequest::none) {
-    const NEWMAT::Matrix& toBase = dynamic_cast<const PointAtBase*>(curReq)->toBaseMatrix;
-    switch (dynamic_cast<const PointAtBase*>(curReq)->getPointAtType()) {
-    case PointAtRequest::none:
-      erouter->postEvent(LookoutPointAtEvent(toBase,EventBase::lookoutEGID,
-						curReq->requestID, EventBase::deactivateETID));
-      break;
-    case PointAtRequest::storeImage:
-      erouter->postEvent(LookoutSketchEvent
-			 (dynamic_cast<StoreImageRequest*>(curReq)->image,
-			  toBase,EventBase::lookoutEGID,
-			  curReq->requestID, EventBase::deactivateETID));
-      break;
-    case PointAtRequest::measureDist:
-      erouter->postEvent(LookoutIREvent
-			 (dynamic_cast<const MeasureDistanceRequest*>(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<const ScanRequest*>(curReq)->scanSpeed 
-       << "  (rad / millisec)\n";
-  if (dynamic_cast<const ScanRequest*>(curReq)->getScanType()==ScanRequest::line) {
-    const ScanAlongLineRequest& scanLineReq = *dynamic_cast<const ScanAlongLineRequest*>(curReq);
-    scanAlongLine(scanLineReq.beginPt, scanLineReq.endPt);
-  }
-  else {
-    const ScanAreaRequest& scanLineReq = *dynamic_cast<const ScanAreaRequest*>(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<const LookoutSearchRequest*>(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<HeadPointerMC>(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<HeadPointerMC> 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<const ScanRequest*>(curReq)->scanSpeed);
-  
-  SharedObject<SmallMotionSequenceMC> 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<const LookoutSearchRequest*>(curReq);
+  switch ( event.getGeneratorID() ) {
 
-void Lookout::scanArea(coordinate_t left, coordinate_t right,
-			  coordinate_t far, coordinate_t near) {
-  const float& scanSpeed = dynamic_cast<const ScanRequest*>(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<HeadPointerMC> 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<const CMVision::color_class_state*>
+      (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<HeadPointerMC>(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<SmallMotionSequenceMC> 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<const LookoutSearchRequest*>(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<float> 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<MediumMotionSequenceMC> mseq_acc(sequence_id);
+  mseq_acc->clear();
+#ifdef TGT_HAS_HEAD
+  for ( std::vector<float>::const_iterator it = jointvals.begin(); it != jointvals.end(); ) {
+		mseq_acc->advanceTime(800);
+		for(unsigned int i=0; i<NumHeadJoints; ++i)
+			mseq_acc->setOutputCmd(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<float> &jointvals,
+		       const Point &target) {
+	hpmc_temp.lookAtPoint(target.coordX() ,target.coordY() ,target.coordZ());
+	for(unsigned int i=0; i<NumHeadJoints; ++i)
+		jointvals.push_back(hpmc_temp.getJointValue(i));
 }
 
 } // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Lookout.h ./DualCoding/Lookout.h
--- ../Tekkotsu_3.0/DualCoding/Lookout.h	2006-08-10 23:13:15.000000000 -0400
+++ ./DualCoding/Lookout.h	2007-11-11 18:57:20.000000000 -0500
@@ -3,24 +3,26 @@
 #define INCLUDED_Lookout_h_
 
 #include <queue>
+
 #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<DualCoding::Point> 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<class T>
   void pushRequest(const LookoutRequest& req) {
-    requests.push(new T(*dynamic_cast<const T*>(&req)));
+    requests.push(new T(dynamic_cast<const T&>(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<Point>& 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<Point>&, const std::set<color_index>&, int);
+#ifdef TGT_HAS_IR_DISTANCE
+  void storeIRDataTo(std::vector<Point>&);
+#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<float> &jointvals,
+		       const Point &target);
+  //@}
 
-  void storeVisionRegionDataTo(vector<Point>&, const set<int>&, int);
-  void storeIRDataTo(vector<Point>&);
 
-  //  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<LookoutRequest*> requests;
-  LookoutRequest *curReq;
-  bool /*pan_prior, */landmarkInView;
+  std::vector<std::map<uchar,unsigned int> > pixelHistograms;
+  std::priority_queue<float> 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<LookoutRequest*> 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<Task*>::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<uchar> (&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<uchar> image; //<! stores image here
-  Sketch<uchar> (*sketchFunc)(); //<! function used to generate image
-private:
-  StoreImageRequest& operator=(const StoreImageRequest&);
-};
+  LookoutResultType_t getResultType() const { return resultType; }
+  void setResultType(const LookoutResultType_t rtype) { resultType = rtype; }
 
-class StoreImageAtRequest : public PointAtRequest, public StoreImageRequest {
-public:
   //! Constructor
-  StoreImageAtRequest(const Point& pt, Sketch<uchar> (&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<uchar> (&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<uchar> (&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<Task*> tasks;
-  float scanSpeed; // in rad/msec
-  static const float defSpd;
-  ScanRequest(const ScanRequest& req)
-    : LookoutRequest(req), tasks(), scanSpeed(req.scanSpeed) {
-    for (vector<Task*>::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<const VisionRegionTask*>(&t))); break;
-    case Task::visObj:
-      tasks.push_back(new VisionObjectTask(*dynamic_cast<const VisionObjectTask*>(&t))); break;
-    case Task::ir:
-      tasks.push_back(new IRTask(*dynamic_cast<const IRTask*>(&t))); break;
-    default: return;
-    };
-  }
-  virtual ~ScanRequest() {
-    for (vector<Task*>::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<Point> 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<Point> 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<int> index;
+    virtual TaskType_t getTaskType() const { return noTask; }
+    std::set<color_index> index;
     VisionTask(const VisionTask& vt) : Task(vt), index(vt.index) {}
-  protected:
-    VisionTask(const set<int>& _index, AngPi _interval)
-      : Task(_interval), index(_index) {}
-    VisionTask(int _index, AngPi _interval)
-      : Task(_interval), index() { index.insert(_index); }
+    VisionTask(const std::set<color_index>& _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<int>& sid, AngPi _interval)
-      : VisionTask(sid,_interval) {}
+    VisionObjectTask(const std::set<color_index>& 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<int>& colorIndex, AngPi _interval,
+    VisionRegionTask(const std::set<color_index>& 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<uchar> image; //<! stores image here
+  Sketch<uchar> (*sketchFunc)(); //<! function used to generate image
+
+private:
+  LookoutPointRequest& operator=(const LookoutPointRequest&); // don't call
 };
 
-class ScanAreaRequest : public ScanRequest {
+
+// ================ LookoutScanRequest ================
+
+class LookoutScanRequest : public LookoutRequest {
 public:
-  ScanAreaRequest(coordinate_t _left, coordinate_t _right,
-		  coordinate_t _far, coordinate_t _near, 
-		  float _speed=defSpd)
-    : ScanRequest(_speed),left(_left),
-      right(_right),far(_far),near(_near) {}
-  ScanAreaRequest(const ScanAreaRequest& req)
-    : ScanRequest(req), left(req.left),
-      right(req.right), far(req.far), near(req.near) {}
-  //  virtual HeadMotionType_t getHeadMotionType() const { return scanArea; }
-  virtual ScanType_t getScanType() const { return area; }
-  coordinate_t left,right,far,near;
+
+  std::vector<Task*> 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<Task*>::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<ScanRequest::VisionTask>& _landmarks, const ShapeRoot& _area)
-    : landmarks(_landmarks), area(_area), lmLocation(), lmInView(false) {}
-  TrackRequest(const vector<ScanRequest::VisionTask>& _landmarks, const Point& pt, const ShapeRoot& _area)
-    : landmarks(_landmarks), area(_area), lmLocation(pt), lmInView(false) {}
-  virtual HeadMotionType_t getHeadMotionType() const { return track; }
-  vector<ScanRequest::VisionTask> 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<ShapeType_t,set<int> > 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<const TakeSnapAtRequest*>(&req))
-      requests.push(new TakeSnapAtRequest(*snapAtReq)); 
-    else
-      requests.push(new TakeSnapRequest(*dynamic_cast<const TakeSnapRequest*>(&req))); 
-    break;
-  case MapBuilderRequest::localMap:
-    if (const LocalMapTestRequest* testReq = dynamic_cast<const LocalMapTestRequest*>(&req))
-      requests.push(new LocalMapTestRequest(*testReq)); 
-    else
-      requests.push(new LocalMapRequest(*dynamic_cast<const LocalMapRequest*>(&req))); 
-    break;
-  case MapBuilderRequest::worldMap:
-    if (const WorldMapTestRequest* testReq = dynamic_cast<const WorldMapTestRequest*>(&req))
-      requests.push(new WorldMapTestRequest(*testReq)); 
-    else
-      requests.push(new WorldMapRequest(*dynamic_cast<const WorldMapRequest*>(&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<const TakeSnapAtRequest*>(curReq))
-      storeImageAt(snapAtReq->gazePt);
-    else
-      storeImage();
-  else {
-    const LocalMapRequest& curMapReq = *dynamic_cast<const LocalMapRequest*> (&(*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<const TextMsgEvent&>(e);
-    if ( strcmp(txtev.getText().c_str(),"MoveHead") == 0 )
+  case EventBase::textmsgEGID:
+    if ( strcmp(dynamic_cast<const TextMsgEvent&>(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<uchar>& camImg = dynamic_cast<const LookoutSketchEvent*>(&e)->getSketch();
-      NEW_SKETCH(camFrame, uchar, camImg);
-      const NEWMAT::Matrix& camToBase = dynamic_cast<const LookoutSketchEvent*>(&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<const LookoutSketchEvent&>(e));
+    else if ( e.getSourceID() == scanID ) {
       const vector<Point>& pts = dynamic_cast<const LookoutScanEvent*>(&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<uchar>& 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<ShapeRoot>& shapes) {
-  const LocalMapRequest *locReq = dynamic_cast<const LocalMapRequest*>(curReq);
-  if ( locReq == NULL || ! locReq->pursueShapes )
-    return false;
+  if ( ! curReq->pursueShapes ) return false;
   HeadPointerMC headpointer_mc;
   for (vector<ShapeRoot>::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<Point>& gazePts) {
-  HeadPointerMC headpointer_mc;
   for (vector<Point>::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<Point>::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<LocalMapRequest*>(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<uchar> 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<int> colors;
-  for (colorMap::const_iterator it1 = curReq->objectColors.begin();
+void MapBuilder::scanForGazePts() {
+  LookoutScanRequest lreq;
+  lreq.searchArea = curReq->searchArea;
+  lreq.motionSettleTime = curReq->motionSettleTime;
+  set<color_index> colors;  // colors of all the shape types we're looking for
+  for (map<ShapeType_t,set<color_index> >::const_iterator it1 = curReq->objectColors.begin();
        it1 != curReq->objectColors.end(); it1++)
-    for (set<int>::const_iterator it2 = it1->second.begin();
+    for (set<color_index>::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<ShapeRoot> 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<ShapeRoot> 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<const LocalMapTestRequest*>(curReq))
-    return ((*localTestReq->exitTest)());
-  else if (const WorldMapTestRequest* worldTestReq = dynamic_cast<const WorldMapTestRequest*>(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<int> polCols, bool mergeSrc, bool mergeDst) {
+				  set<color_index> polCols, bool mergeSrc, bool mergeDst) {
   vector<ShapeRoot> src_shapes = srcShS.allShapes();
   vector<ShapeRoot> dst_shapes = dstShS.allShapes();
   vector<LineData> polygon_edges;
@@ -571,8 +636,9 @@
   for (vector<ShapeRoot>::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<ShapeRoot>::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<ShapeRoot> shapes = ShS.allShapes();
@@ -668,25 +737,27 @@
       for (vector<LineData>::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<ShapeRoot> 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<Point> &gazePts, const ShapeRoot& area, bool doScan) {
-  cout << "MapBuilder::defineGazePts\n";
-  static const float meshSize=50;
-  switch (area->getType()) {
-  case lineDataType: {
-    const Shape<LineData>& 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<BlobData>& blob = ShapeRootTypeConst(area,BlobData);
-    if (doScan) {
-      ScanAreaRequest req(blob->topLeft.coordY(),blob->bottomRight.coordY(),
-			  blob->topLeft.coordX(),blob->bottomRight.coordX());
-      scan(req);
-    }
-    else {
-      vector<Point> 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<PolygonData> &poly = ShapeRootTypeConst(area,PolygonData);
-    const vector<Point> &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<Point>& gazePts, const vector<Point>& 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<Point>::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<LineData> 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<LineData>& 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<LineData>::const_iterator H_it = horizontal.begin();
-       H_it != horizontal.end(); H_it++)
-    for (vector<LineData>::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<PolygonData> &poly = ShapeRootTypeConst(sArea,PolygonData);
+	const vector<Point> &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<Point> &gazePts, const NEWMAT::Matrix& baseToCam) {
-  if ( ! dynamic_cast<const LocalMapRequest*>(curReq)->removePts )
-    return;
-  int num_points_seen = 0;
-  for ( vector<Point>::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<Point>::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<uchar>& 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<Shape<LineData> > MapBuilder::getCamLines(const Sketch<uchar> &camFrame, const set<int>& objectColors, 
-						    const set<int>& occluderColors) const {
-  vector<Shape<LineData> > lines;
-  if (objectColors.empty() ) 
-    return lines;
-  cout << "*** Find the lines ***" << endl;
+vector<Shape<LineData> > MapBuilder::getCamLines(const Sketch<uchar> &camFrame, const set<color_index>& objectColors, 
+						 const set<color_index>& occluderColors) const {
+  vector<Shape<LineData> > linesReturned;
+  if ( objectColors.empty() ) 
+    return linesReturned;
+  if ( verbosity & MBVshapeSearch )
+    cout << "*** Find the lines ***" << endl;
   NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
-  for ( set<int>::const_iterator it = occluderColors.begin();
+  for ( set<color_index>::const_iterator it = occluderColors.begin();
 	it != occluderColors.end(); it++ )
     occluders |= visops::minArea(visops::colormask(camFrame,*it));
 
-  for (set<int>::const_iterator it = objectColors.begin();
+  for (set<color_index>::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<Shape<LineData> > 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<Shape<LineData> > 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<Shape<EllipseData> > 
 MapBuilder::getCamEllipses(const Sketch<uchar> &camFrame,
-			      const set<int>& objectColors, const set<int>& ) const {
+			   const set<color_index>& objectColors, const set<color_index>& ) const {
   vector<Shape<EllipseData> > ellipses;
   if (objectColors.empty())
     return ellipses;
-  cout << "*** Find the ellipses ***" << endl;
-  for (set<int>::const_iterator it = objectColors.begin();
+  if ( verbosity & MBVshapeSearch )
+    cout << "*** Find the ellipses ***" << endl;
+  for (set<color_index>::const_iterator it = objectColors.begin();
        it !=objectColors.end(); it++) {
     NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it));
     vector<Shape<EllipseData> > 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<Shape<PolygonData> > 
 MapBuilder::getCamPolygons(const Sketch<uchar> &camFrame,
-			      const set<int>& objectColors, const set<int>& occluderColors) const {
+			      const set<color_index>& objectColors, const set<color_index>& occluderColors) const {
   vector<Shape<PolygonData> > 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<int>::const_iterator it = occluderColors.begin();
+  for ( set<color_index>::const_iterator it = occluderColors.begin();
 	it !=occluderColors.end(); it++ )
     occluders |= visops::colormask(camFrame,*it);
   
-  for (set<int>::const_iterator it = objectColors.begin();
+  for (set<color_index>::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<Shape<LineData> > 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<Shape<SphereData> > 
 MapBuilder::getCamSpheres(const Sketch<uchar> &camFrame,
-			     const set<int>& objectColors, const set<int>& ) const {
+			  const set<color_index>& objectColors, const set<color_index>& ) const {
   vector<Shape<SphereData> > spheres;
   if ( objectColors.empty() )
     return spheres;
-  cout << "*** Find the spheres ***" << endl;
-  for (set<int>::const_iterator it = objectColors.begin();
+  if ( verbosity & MBVshapeSearch )
+    cout << "*** Find the spheres ***" << endl;
+  for (set<color_index>::const_iterator it = objectColors.begin();
        it !=objectColors.end(); it++) {
     NEW_SKETCH_N(colormask,bool,visops::colormask(camFrame,*it));
-    vector<ShapeRoot> sphere_shapes = SphereData::extractSpheres(colormask);
+    vector<Shape<SphereData> > 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<uchar> &camFrame, unsigned int floorColor) const {
   if (floorColor == 0)
     return vector<Shape<LineData> >();
-  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<uchar>& camFrame,
+			     const set<color_index>& colors,
+			     const map<color_index,int>& minBlobAreas,
+			     const map<color_index, BlobData::BlobOrientation_t>& blobOrientations,
+			     const map<color_index,coordinate_t>& assumedBlobHeights) {
+  if ( colors.empty() )
+    return;
+  int const maxblobs = 50;
+  vector<Shape<BlobData> > 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<int>& blobColors = curReq->objectColors[blobDataType];
-  //  unsigned int const numBlobColors = blobColors.size();
-  //  for ( unsigned int i = 0; i<numBlobColors; i++ ) {
-  for (set<int>::const_iterator it = blobColors.begin();
+  if ( verbosity & MBVshapeSearch )
+    cout << "*** Find the blobs ***" << endl;
+  const set<color_index>& blobColors = curReq->objectColors[blobDataType];
+  for (set<color_index>::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<Shape<BlobData> > 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<Shape<BlobData> > 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<Shape<BlobData> > blob_shapes(VRmixin::getBlobsFromRegionGenerator(*it,minarea,orient,height));
+    if ( verbosity & MBVshapesFound )
+      cout << "Found " << blob_shapes.size() << " " << ProjectInterface::getColorName(*it) << " blobs." << endl;
   }
 }
 
+vector<Shape<TargetData> > 
+MapBuilder::getCamTargets(const Sketch<uchar> &camFrame, const set<color_index>& objectColors, const set<color_index>& occluderColors) const {
+  vector<Shape<TargetData> > targets;
+  if (objectColors.empty())
+    return targets;
+  if ( verbosity & MBVshapeSearch )
+    cout << "*** Find the targets ***" << endl;
+  
+  NEW_SKETCH_N(occluders,bool,visops::zeros(camFrame));
+  for (set<color_index>::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<color_index>::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<TargetData> 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<Point> gazePts;
-    vector<NEWMAT::Matrix> 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<AgentData> &theAgent; //!< agent in the world frame
-   //! trasformation matrices between local and world frames.
+  friend class Lookout;
+
+  Shape<AgentData> &theAgent; //!< Agent in the world frame
+   //!@name Transformation matrices between local and world frames
+  //@{
   NEWMAT::Matrix localToWorldMatrix, worldToLocalTranslateMatrix, worldToLocalRotateMatrix;
+  //@}
 
-  vector<Point> 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<Point> badGazePoints; //!<  gaze points for which HeadPointerMC.lookAtPoint() returned false
 
-  queue<MapBuilderRequest*> requests;
+  std::queue<MapBuilderRequest*> 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<uchar>&, 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<AgentData>& 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<ShapeRoot> getShapes(const ShapeSpace& ShS, int minConf=2) const {
-    const vector<ShapeRoot> allShapes = ShS.allShapes();
+  std::vector<ShapeRoot> getShapes(const ShapeSpace& ShS, int minConf=2) const {
+    const std::vector<ShapeRoot> allShapes = ShS.allShapes();
     if (&ShS == &camShS || &ShS == &groundShS || minConf <= 0) 
       return allShapes;
-    vector<ShapeRoot> nonNoiseShapes;
-    for (vector<ShapeRoot>::const_iterator it = allShapes.begin();
+    std::vector<ShapeRoot> nonNoiseShapes;
+    for (std::vector<ShapeRoot>::const_iterator it = allShapes.begin();
 	 it != allShapes.end(); it++)
       if ((*it)->getConfidence() >= minConf)
 	nonNoiseShapes.push_back(*it);
     return nonNoiseShapes;
   }
 
-  const vector<Point>& getGazePts() const { return cur->gazePts; }
-  static bool returnTrue() { return true; }
-  static bool returnFalse() { return false; }
-  //}@
+  void importLocalToWorld();
 
-  //!@ Shape extraction functions
-  vector<Shape<LineData> > 
-  getCamLines(const Sketch<uchar>&, const set<int>& objectColors, 
-	      const set<int>& occluderColors) const ;
-  vector<Shape<PolygonData> > 
-  getCamPolygons(const Sketch<uchar>&, const set<int>& objectColors, 
-		 const set<int>& occluderColors) const ;
-  vector<Shape<EllipseData> > 
-  getCamEllipses(const Sketch<uchar>&, const set<int>& objectColors, 
-		 const set<int>& occluderColors) const ;
-  vector<Shape<SphereData> >  
-  getCamSpheres(const Sketch<uchar>&, const set<int>& objectColors, 
-		const set<int>& occluderColors) const ;
-  vector<Shape<LineData> >  
-  getCamWalls(const Sketch<uchar>&, unsigned int) const ;
-  vector<Shape<BlobData> >  
-  getCamBlobs(const Sketch<uchar>& sketch, const set<int>& objectColors) const {
-    return BlobData::extractBlobs(sketch, objectColors);
-  }
-  //}@
+  ShapeRoot importWorldToLocal(const ShapeRoot &worldShape);
+  template<class T> Shape<T> importWorldToLocal(const Shape<T> &worldShape);
 
-  static Shape<BlobData> formBoundingBox(coordinate_t left, coordinate_t right, 
-					 coordinate_t front, coordinate_t rear) {
-    return Shape<BlobData>
-      (new BlobData(VRmixin::groundShS, Point(front,left), Point(front,right), 
-		    Point(rear,right), Point(rear,left), fabs((left-right)*(front-rear)), 
-		    vector<BlobData::run>(), BlobData::groundplane, rgb()));
-  }
+protected:
+  //!@name Shape extraction functions
+  //@{
+  void getCameraShapes(const Sketch<uchar>& camFrame);
+
+  std::vector<Shape<LineData> > 
+  getCamLines(const Sketch<uchar>&, const std::set<color_index>& objectColors, 
+	      const std::set<color_index>& occluderColors) const;
+
+  std::vector<Shape<EllipseData> > 
+  getCamEllipses(const Sketch<uchar>&, const std::set<color_index>& objectColors, 
+		 const std::set<color_index>& occluderColors) const;
+
+  std::vector<Shape<PolygonData> > 
+  getCamPolygons(const Sketch<uchar>&, const std::set<color_index>& objectColors, 
+		 const std::set<color_index>& occluderColors) const;
+
+  std::vector<Shape<LineData> >  
+  getCamWalls(const Sketch<uchar>&, unsigned int) const;
+
+  std::vector<Shape<SphereData> >  
+  getCamSpheres(const Sketch<uchar>&, const std::set<color_index>& objectColors, 
+		const std::set<color_index>& occluderColors) const;
+
+  void getCamBlobs(const Sketch<uchar>& camFrame,
+		   const std::set<color_index>& colors,
+		   const std::map<color_index,int>& minBlobAreas,
+		   const std::map<color_index, BlobData::BlobOrientation_t>& blobOrientations,
+		   const std::map<color_index,coordinate_t>& assumedBlobHeights);
+  void getCamBlobs();
+  
+  std::vector<Shape<TargetData> > 
+  getCamTargets(const Sketch<uchar> &camFrame, const std::set<color_index>& objectColors,
+    const std::set<color_index>& occluderColors) const;
+  //@}
 
-  void importLocalToWorld();
-  void importWorldToLocal(const ShapeRoot &shape);
   // matching shapes between two spaces.
-  static void matchSrcToDst(ShapeSpace &src, ShapeSpace &dst, set<int> polygonEdgeColors=set<int>(),
+  static void matchSrcToDst(ShapeSpace &src, ShapeSpace &dst, std::set<color_index> polygonEdgeColors=std::set<color_index>(),
 			    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<Point>&, const ShapeRoot& area, bool doScan);// {}
-  void defineGazePts(vector<Point>& gazePts, const vector<Point>& corners, float meshSize);
+  void defineGazePts();
   
-  void getCameraShapes(const Sketch<uchar>& 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<Point>&, const NEWMAT::Matrix& baseToCam);
+  void removeGazePts(std::vector<Point>&, 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<ShapeRoot>&);
-  // Returns true if an element of gazePt can be looked at; sets it up as nextGazePoint
-  bool determineNextGazePoint(vector<Point> &gazePts);
+  bool determineNextGazePoint(const std::vector<ShapeRoot>&);
+  // Returns true if an element of gazePts can be looked at; sets it up as nextGazePoint
+  bool determineNextGazePoint(std::vector<Point> &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<class T> Shape<T> MapBuilder::importWorldToLocal(const Shape<T> &worldShape) {
+  ShapeRoot temp(localShS.importShape(worldShape));
+  Shape<T> 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<typename T> void deleteAll(std::queue<T*> &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 <queue>
+
+#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<ShapeType_t, std::set<color_index> > objectColors;		//!< For each object type, a set of object color indices
+  std::map<ShapeType_t, std::set<color_index> > occluderColors;		//!< For each object type, a set of occluder color indices
+  std::map<color_index, int> minBlobAreas;	//!< Minimum acceptable areas for blobs of specified colors, e.g., req.minBlobAreas[pink_index]=50
+  std::map<color_index, BlobData::BlobOrientation_t> blobOrientations; //!< Default orientation for blobs of specified colors
+  std::map<color_index, coordinate_t> 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<LookoutSearchRequest*> 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<Point> gazePts;
+  std::vector<NEWMAT::Matrix> 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<ShapeType_t,set<int> > 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<int, int> minBlobAreas;
-  map<int, BlobData::BlobOrientation_t> 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<BlobData>
-	   (new BlobData
-	    (VRmixin::groundShS,Point(maxX,maxY),Point(maxX,minY),
-	     Point(minX,maxY),Point(minX,minY),(maxX-minX)*(maxY-minY),
-	     vector<BlobData::run>(),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<PointData>(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<BlobData>
-	   (new BlobData
-	    (VRmixin::groundShS,Point(maxX,maxY),Point(maxX,minY),
-	     Point(minX,maxY),Point(minX,minY),(maxX-minX)*(maxY-minY),
-	     vector<BlobData::run>(),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 <math.h>
-
-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 <cmath>
+#include <iostream>
+
+#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<PfLine&>(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; j<localLms.size(); j++ ) {
+      float distsq = HUGE_VAL; // HUGE_VAL is defined in math.h
+      localMatches[j] = -1;
+      for ( unsigned int k=0; k<worldLms.size(); k++ ) {
+	if ( localLms[j]->type == 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<PfLine*>(localLms[j]);
+	    PfLine &worldLine = *static_cast<PfLine*>(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<PolygonData> &bounds) {
+    PFShapeDistributionPolicy<LocalizationParticle> *dist =
+      dynamic_cast<PFShapeDistributionPolicy<LocalizationParticle> *>(&(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<LocalizationParticleData>();
+    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<particles.size(); i+=increment)
+      if ( i != bestIndex ) {
+	NEW_SHAPE(pt, LocalizationParticleData, new LocalizationParticleData(wShS,particles[i]));
+      }
+  }
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PFShapeLocalization.h ./DualCoding/PFShapeLocalization.h
--- ../Tekkotsu_3.0/DualCoding/PFShapeLocalization.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PFShapeLocalization.h	2007-04-20 06:50:52.000000000 -0400
@@ -0,0 +1,240 @@
+//-*-c++-*-
+
+#ifndef _LOADED_PFShapeLocalization_h_
+#define _LOADED_PFShapeLocalization_h_
+
+#include <vector>
+#include <iostream>
+#include <cmath>
+#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<float>& getLocalScores() const { return localScores; }
+  unsigned int getNumMatches() const { return numMatches; }
+
+  std::vector<PfRoot*> localLms; //!< a vector of the landmarks in the local space
+  std::vector<PfRoot*> 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<int> 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<float> 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<float> particleViewX;		//!< x coords of local landmarks according to the currently-selected particle
+  std::vector<float> particleViewY;		//!< y coords of local landmarks according to the currently-selected particle
+  std::vector<float> particleViewX2;		//!< x coords of other point of local line
+  std::vector<float> 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<typename ParticleT>
+class ShapeSensorModel : public ParticleFilter<ParticleT>::SensorModel {
+public:
+  typedef typename ParticleFilter<ParticleT>::SensorModel::index_t index_t; //!< convenience typedef
+  typedef typename ParticleFilter<ParticleT>::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; p<particles.size(); ++p) {
+      eval.evaluate(particles[p]);
+      for(unsigned int i=0; i<eval.getNumMatches(); ++i) {
+#if USE_LOGWEIGHTS
+	particles[p].weight += -eval.getLocalScores()[i]/stdevSq;
+#else
+	particles[p].weight *= normpdf(eval.getLocalScores()[i]);
+#endif
+      }
+      if(particles[p].weight>bestWeight) {
+	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<typename ParticleT>
+class PFShapeDistributionPolicy : public LocalizationParticleDistributionPolicy<ParticleT> {
+public:
+  typedef ParticleT particle_type;  //!< just for convenience
+  typedef typename ParticleFilter<particle_type>::index_t index_t; //!< just for convenience
+
+  PFShapeDistributionPolicy() : LocalizationParticleDistributionPolicy<ParticleT>(), 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<ParticleT>::mapWidth + 
+	  LocalizationParticleDistributionPolicy<ParticleT>::mapMinX;
+	begin->y = float(rand())/RAND_MAX * LocalizationParticleDistributionPolicy<ParticleT>::mapHeight + 
+	  LocalizationParticleDistributionPolicy<ParticleT>::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<ParticleT>::positionVariance*var;
+	float ry = DRanNormalZig32()*LocalizationParticleDistributionPolicy<ParticleT>::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<ParticleT>::orientationVariance*var;
+      ++begin;
+    }
+  }
+
+  virtual void setWorldBounds(const Shape<PolygonData> bounds) {
+    worldBounds = bounds;
+    if ( worldBounds.isValid() ) {
+      BoundingBox b(worldBounds->getBoundingBox());
+      LocalizationParticleDistributionPolicy<ParticleT>::mapMinX = b.xmin;
+      LocalizationParticleDistributionPolicy<ParticleT>::mapWidth = b.xmax - b.xmin;
+      LocalizationParticleDistributionPolicy<ParticleT>::mapMinY = b.ymin;
+      LocalizationParticleDistributionPolicy<ParticleT>::mapHeight = b.ymax - b.ymin;
+    }
+  }
+
+protected:
+  Shape<PolygonData> 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<LocalizationParticle> {
+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<LocalizationParticle>(numParticles, new DeadReckoningBehavior<LocalizationParticle>),
+      sensorModel(new ShapeSensorModel<LocalizationParticle>(localShS,worldShS))
+  {
+    getResamplingPolicy()->setDistributionPolicy(new PFShapeDistributionPolicy<LocalizationParticle>);
+    if(BehaviorBase* motBeh = dynamic_cast<BehaviorBase*>(motion))
+      motBeh->DoStart();
+  }
+
+  //! destructor
+  virtual ~PFShapeLocalization() { 
+    if(BehaviorBase* motBeh = dynamic_cast<BehaviorBase*>(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<LocalizationParticle>& 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<LocalizationParticle>* 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<LocalizationParticle>::setPosition;
+
+  //! sets boundary within which particles should lie
+  virtual void setWorldBounds(const Shape<PolygonData> &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<LocalizationParticle> * 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 <iostream>
+#include <cmath>
+
+#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; i<localMatches.size(); i++)
+      part.addLocal[i] = ( localMatches[i] == -1 && localLms[i]->mobile );
+    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; j<localLms.size(); j++) {
+      if ( localLms[j]->mobile  ) {
+	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<localLms.size(); j2++) {
+	  if (localMatches[j2] != localMatches[j] || localMatches[j2] == -1)
+	    continue;
+	  if (localScores[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<localLms.size(); j++) {
+      if ( localMatches[j] != -1 )
+	part.deleteWorld[localMatches[j]] = false;  // don't delete world LM if it matches
+      if ( particleViewX[j] < minXLoc )
+	minXLoc = particleViewX[j];
+      else if (particleViewX[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; k<worldLms.size(); k++)
+      if ( ! worldLms[k]->mobile ||
+	   !( 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<LocalizationParticleData>();
+    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<particles.size(); i+=increment)
+      if ( i != bestIndex ) {
+	NEW_SHAPE(pt, LocalizationParticleData, new LocalizationParticleData(wShS,particles[i]));
+      }
+  }
+
+  ostream& operator << (ostream& os, const SLAMShapesParticle &p){
+    os << "Particle(p=" << p.weight
+       << ", dx=" << p.x
+       << ", dy=" << p.y
+       << ", th=" << p.theta;
+	
+    os << ", add=";
+    for (unsigned int i = 0; i<p.addLocal.size(); i++)
+      os << p.addLocal[i];
+	
+    os << ", del=";
+    for (unsigned int i = 0; i<p.deleteWorld.size(); i++)
+      os << p.deleteWorld[i];
+	
+    os << ")";
+    return os;
+  }
+
+} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PFShapeSLAM.h ./DualCoding/PFShapeSLAM.h
--- ../Tekkotsu_3.0/DualCoding/PFShapeSLAM.h	1969-12-31 19:00:00.000000000 -0500
+++ ./DualCoding/PFShapeSLAM.h	2007-11-11 18:57:21.000000000 -0500
@@ -0,0 +1,186 @@
+//-*-c++-*-
+
+#ifndef _LOADED_PFShapeSLAM_h_
+#define _LOADED_PFShapeSLAM_h_
+
+#include <vector>
+#include <iostream>
+#include <cmath>
+#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<SLAMShapesParticle> DistributionPolicy;
+
+    //! Constructor
+    SLAMShapesParticle() : LocalizationParticle(), addLocal(), deleteWorld() {}
+	
+    std::vector<bool> addLocal;	//!< true for local landmarks missing from the world map
+    std::vector<bool> 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; j<localLms.size(); j++ )
+	localMobile |= localLms[j]->mobile;
+      for ( unsigned int k=0; k<worldLms.size(); k++ )
+	worldMobile |= worldLms[k]->mobile;
+    }
+    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<typename ParticleT>
+  class SLAMShapesSensorModel : public ParticleFilter<ParticleT>::SensorModel {
+  public:
+    typedef typename ParticleFilter<ParticleT>::SensorModel::index_t index_t; //!< convenience typedef
+    typedef typename ParticleFilter<ParticleT>::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()<particleLocalLandmarks/2)
+	for(typename particle_collection::iterator it=particles.begin(); it!=particles.end(); ++it)
+	  it->addLocal.resize(particleLocalLandmarks);
+		
+      if(eval.worldLms.size()>particleWorldLandmarks || eval.worldLms.size()<particleWorldLandmarks/2)
+	for(typename particle_collection::iterator it=particles.begin(); it!=particles.end(); ++it)
+	  it->deleteWorld.resize(particleWorldLandmarks);
+		
+      for(typename particle_collection::size_type p=0; p<particles.size(); ++p) {
+	eval.evaluate(particles[p]);
+	for(unsigned int i=0; i<eval.numMatches; ++i) {
+#if USE_LOGWEIGHTS
+	  particles[p].weight += -eval.localScores[i]/stdevSq;
+#else
+	  particles[p].weight *= normpdf(eval.localScores[i]);
+#endif
+	}
+	if(particles[p].weight>bestWeight) {
+	  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<SLAMShapesParticle> {
+  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<SLAMShapesParticle>(numParticles, new DeadReckoningBehavior<SLAMShapesParticle>),
+	sensorModel(new SLAMShapesSensorModel<SLAMShapesParticle>(localShS,worldShS))
+    {
+      if(BehaviorBase* motBeh = dynamic_cast<BehaviorBase*>(motion))
+	motBeh->DoStart();
+    }
+    //! destructor
+    virtual ~PFShapeSLAM() {
+      if(BehaviorBase* motBeh = dynamic_cast<BehaviorBase*>(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<SLAMShapesParticle>& 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<SLAMShapesParticle>* 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<SLAMShapesParticle> * 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 <iostream>
-#include <stdlib.h>
-
-#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<p.addLocal.size(); i++)
-    os << p.addLocal[i];
-  // os << ", del=";
-  // for (unsigned int i = 0; i<p.deleteWorld.size(); i++)
-  // os << p.deleteWorld[i] << " ";
-  // os << endl;
-  os << ")";
-  return os;
-}
-
-} // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/Particle.h ./DualCoding/Particle.h
--- ../Tekkotsu_3.0/DualCoding/Particle.h	2006-05-10 19:21:57.000000000 -0400
+++ ./DualCoding/Particle.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,36 +0,0 @@
-//-*-c++-*-
-
-#ifndef _LOADED_Particle_h_
-#define _LOADED_Particle_h_
-
-#include <vector>
-#include <iostream>
-
-#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<bool> addLocal;	//!< true for local landmarks missing from the world map
-  // vector<bool> 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 <iostream>
-#include <vector>
-
-#include <math.h>
-
-#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<PolygonData>();
-  bestIndex = -1;
-  localScores.clear();
-  localMatches.clear();
-}
-
-void ParticleFilter::makeParticles() {
-  delete curParticles;
-  delete newParticles;
-  curParticles = new vector<Particle>(numParticles);
-  newParticles = new vector<Particle>(numParticles);
-}
-
-void ParticleFilter::resizeParticles() {
-  for ( int i=0; i<numParticles; i++ ) {
-    (*curParticles)[i].addLocal.resize(nlocal);
-    (*newParticles)[i].addLocal.resize(nlocal);
-  }
-  particleViewX.resize(nlocal);
-  particleViewY.resize(nlocal);
-  particleViewX2.resize(nlocal);
-  particleViewY2.resize(nlocal);
-  localScores.resize(nlocal);
-  localMatches.resize(nlocal);
-}
-
-void ParticleFilter::loadLms() {
-  PfRoot::deleteLms(localLms);
-  PfRoot::deleteLms(worldLms);
-  localLms = PfRoot::loadLms(localShS.allShapes(), false);
-  worldLms = PfRoot::loadLms(worldShS.allShapes(), true);
-  nlocal = localLms->size();
-  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<Particle> * 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<numParticles; i++ ) {
-	 Particle &part = (*curParticles)[i];
-	 part.dx += xdelta;
-	 part.dy += ydelta;
-	 part.theta = part.theta + tdelta;
-  }
-  computeParticleScores();
-}
-
-
-void ParticleFilter::getInitialGuess() {
-  float const minAcceptableProb = pow(((double)0.3),((double)nlocal)); 
-  for ( int tryCounter = 0; tryCounter < numTries; tryCounter++ ) {
-    computeParticleScores();
-    if ( (*curParticles)[bestIndex].prob >= 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<numParticles; i++ ) {
-    setParticleView(i);
-    (*curParticles)[i].addLocal.assign(nlocal,false);
-    for ( int j = 0; j<nlocal; j++ )
-      computeLocalMatch(i,j);
-    determineAdditions(i);
-    // determineDeletions(i);
-    float s = localScores[0];
-    for ( int j=1; j<nlocal; j++ )
-      s *= localScores[j];
-    (*curParticles)[i].prob = s;
-    if ( s > 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<PfLine&>(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; k<nworld; k++ ) {
-    if ( (*localLms)[j]->type == (*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<PfLine*>((*localLms)[j]);
-	PfLine &worldLine = *dynamic_cast<PfLine*>((*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<numParticles; i++ ) {
-      float spawnChance = float(rand())/RAND_MAX;
-      if ( spawnChance <= 0.8 * (*curParticles)[i].prob / normFactor ) {
-		  spawnInto(i, newParticleCount++);
-		  if ( newParticleCount == numParticles )
-			 break;
-      }
-		if ( float(rand())/RAND_MAX < PERCENT_RANDOM ) {
-		  randomizeNewParticle(newParticleCount++); 
-		  if ( newParticleCount == numParticles )
-			 break;
-		}
-    }
-  }
-  vector<Particle> * 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<nlocal; j++) {
-    float const randval = float(rand()) / (RAND_MAX*6);
-    if (randval >= localScores[j]) {
-      part.addLocal[j] = true;
-      localScores[j] = ADDITION_PENALTY;
-      localMatches[j] = -1;
-    } 
-    else
-      for (int j2 = (j+1); j2<nlocal; j2++)
-	if (localMatches[j2] == localMatches[j] && localMatches[j2] != -1)
-	  if (localScores[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<nlocal; j++) {
-    if ( localMatches[j] != -1 )
-      part.deleteWorld[localMatches[j]] = false;  // don't delete world LM if it matches
-    if ( particleViewX[j] < minXLoc )
-      minXLoc = particleViewX[j];
-    else if (particleViewX[j] > maxXLoc)
-      maxXLoc = particleViewX[j];
-    if (particleViewY[j] < minYLoc)
-      minYLoc = particleViewY[j];
-    else if (particleViewY[j] > maxYLoc)
-      maxYLoc = particleViewY[j];
-  }
-  
-  for (int k = 0; k<nworld; k++)
-    if ( !( 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 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 <vector>
-#include <string>
-
-#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<PolygonData> 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<Particle> *curParticles;	//!< Pointer to vector holding the current set of particles
-  int bestIndex;			//!< Index of highest scoring particle from most recent resampling.
- 
-  //private:
-  vector<Particle> *newParticles;	//!< Pointer to vector where new particles are generated by resampling
-  vector<PfRoot*> *localLms;		//!< Pointer to current vector of local landmarks
-  vector<PfRoot*> *worldLms;		//!< Pointer to current vector of world landmarks
-  vector<float> particleViewX;		//!< x coords of local landmarks according to the currently-selected particle
-  vector<float> particleViewY;		//!< y coords of local landmarks according to the currently-selected particle
-  vector<float> particleViewX2;		//!< x coords of other point of local line
-  vector<float> particleViewY2;		//!< y coords of other point of local line
-  vector<float> localScores;		//!< Match scores for local landmarks according to the currently-selected particle
-  vector<int> 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<PolygonData> &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*>* PfRoot::loadLms(const vector<ShapeRoot> &lms, bool isWorld){
+void PfRoot::loadLms(const std::vector<ShapeRoot> &lms, bool isWorld, std::vector<PfRoot*>& landmarks){
   int id;
   int type;
   rgb color;
-  vector<PfRoot*> *landmarks = new vector<PfRoot*>(2*lms.size(),(PfRoot*)NULL);
-  landmarks->clear();
+  bool mobile;
+  deleteLms(landmarks);
+  landmarks.reserve(lms.size());
   for (unsigned int i = 0; i<lms.size(); i++){
     type = lms[i]->getType();
     color = lms[i]->getColor();
+    mobile = lms[i]->getMobile();
     if (type == lineDataType) {
       const Shape<LineData> &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<EllipseData> &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<PointData> &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<BlobData> &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<PfRoot*> *vec) {
-  if ( vec != NULL ) {
-    for ( unsigned int i = 0; i < vec->size(); i++ )
-      delete (*vec)[i];
-    delete vec;
-  }
+void PfRoot::deleteLms(std::vector<PfRoot*>& vec) {
+	for ( unsigned int i = 0; i < vec.size(); i++ )
+		delete vec[i];
+	vec.clear();
 }
 
-void PfRoot::findBounds(const vector<PfRoot*> &landmarks, 
+void PfRoot::findBounds(const std::vector<PfRoot*> &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<PfRoot*> &landmarks) {
+void PfRoot::printLms(const std::vector<PfRoot*> &landmarks) {
   for (unsigned int i = 0; i<landmarks.size(); i++)
     cout << *landmarks[i] << endl;
 }
 
-void PfRoot::printRootInfo(ostream &os) const {
+void PfRoot::printRootInfo(std::ostream &os) const {
     os << "id=" << id
        << ", x=" << x
-       << ", y=" << y;
+       << ", y=" << y
+       << ", mobile=" << mobile;
   }
 
-ostream& operator<<(ostream &os, const PfRoot &obj) {
+ostream& operator<<(std::ostream &os, const PfRoot &obj) {
   obj.print(os);
   return os;
 }
 
-void PfLine::print(ostream &os) const {
+void PfLine::print(std::ostream &os) const {
   os << "PfLine(";
   printRootInfo(os);
   os << ", x2=" << x2
@@ -128,19 +128,19 @@
      << ")";
 }
 
-void PfEllipse::print(ostream &os) const {
+void PfEllipse::print(std::ostream &os) const {
   os << "PfEllipse(";
   printRootInfo(os);
   os << ")";
 }
 
-void PfPoint::print(ostream &os) const {
+void PfPoint::print(std::ostream &os) const {
   os << "PfPoint(";
   printRootInfo(os);
   os << ")";
 }
 
-void PfBlob::print(ostream &os) const {
+void PfBlob::print(std::ostream &os) const {
   os << "PfBlob(";
   printRootInfo(os);
   os << ")";
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/ParticleShapes.h ./DualCoding/ParticleShapes.h
--- ../Tekkotsu_3.0/DualCoding/ParticleShapes.h	2006-05-10 19:21:57.000000000 -0400
+++ ./DualCoding/ParticleShapes.h	2007-11-11 18:57:21.000000000 -0500
@@ -7,7 +7,7 @@
 
 #include "Vision/colors.h"
 
-#include "Measures.h"     // coordinate_t
+#include "Shared/Measures.h"     // coordinate_t
 #include "ShapeRoot.h"
 
 namespace DualCoding {
@@ -18,27 +18,28 @@
   int type;
   int id;
   rgb color;
+  bool mobile;
   coordinate_t x, y;
   const ShapeRoot* link;
 
-  PfRoot(int _type, int _id, rgb _color, coordinate_t _x, coordinate_t _y) :
-    type(_type), id(_id), color(_color), x(_x), y(_y), link(0) {}
+  PfRoot(int _type, int _id, rgb _color, bool _mobile, coordinate_t _x, coordinate_t _y) :
+    type(_type), id(_id), color(_color), mobile (_mobile), x(_x), y(_y),link(0) {}
     
   virtual ~PfRoot() {} //!< destructor, doesn't delete #link
 
-  virtual void print(ostream &os) const = 0;
+  virtual void print(std::ostream &os) const = 0;
 
-  void printRootInfo(ostream &os) const;
+  void printRootInfo(std::ostream &os) const;
 
-  static vector<PfRoot*>* loadLms(const vector<ShapeRoot> &lms, bool isWorld);
+  static void loadLms(const std::vector<ShapeRoot> &lms, bool isWorld, std::vector<PfRoot*>& landmarks);
 
-  static void deleteLms(vector<PfRoot*> *vec);
+  static void deleteLms(std::vector<PfRoot*>& vec);
 
-  static void findBounds(const vector<PfRoot*> &map, 
+  static void findBounds(const std::vector<PfRoot*> &map, 
 			 coordinate_t &xmin, coordinate_t &ymin,
 			 coordinate_t &xmax, coordinate_t &ymax);
   
-  static void printLms(const vector<PfRoot*> &lmvec);
+  static void printLms(const std::vector<PfRoot*> &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<int,int> lms) {
+PathPlanner::state* PathPlanner::thereIs(unsigned int pos, PathPlanner::direction dir, std::pair<int,int> lms) {
   //  cout << "thereIs: " << pos << ',' << dir << ',' << (pos+dir) << endl;
   const vector<state*>& states = unreached[pos*4 + (unsigned int) dir];
   for (vector<state*>::const_iterator it = states.begin();
@@ -301,7 +301,7 @@
 }
 
 
-vector<pair<int,int> > PathPlanner::findLMs(location loc) {
+std::vector<std::pair<int,int> > PathPlanner::findLMs(location loc) {
   vector<int> lms;
   lms.push_back(-1); // no landmark is also an option
   for (map<unsigned int, PointData>::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<int,int> lms;
+    std::pair<int,int> 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<int,int> _lms)
+    state(location _loc, std::pair<int,int> _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<state> allStates; // all possible states
-  vector<state*> *unreached; // collection of states for which optimal action is not determined yet
+  std::queue<state> allStates; // all possible states
+  std::vector<state*> *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<edge,vector<edge>,lessCost> reached;
+  std::priority_queue<edge,std::vector<edge>,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 <Cost, unsigned int> costs; // all costs must be positive for this algorithm to work
+  std::map <Cost, unsigned int> 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<unsigned int, PointData> landmarks; 
+  std::map<unsigned int, PointData> landmarks; 
   // maps b/w shape ids and their score(distinguishability from other lms) 
-  map<unsigned int, unsigned int> lmCosts; 
-  vector<pair<Point, unsigned int> > obstacles; //<! position of obstacles and their relative costs
+  std::map<unsigned int, unsigned int> lmCosts; 
+  std::vector<std::pair<Point, unsigned int> > obstacles; //<! position of obstacles and their relative costs
 
 public:
   void findPath(); // finds path from goal to start using Dijkstra's algorithm
   void addLandmark(const ShapeRoot& lm) { //adds landmark
-    landmarks.insert(make_pair<unsigned int,PointData>
+    landmarks.insert(std::make_pair<unsigned int,PointData>
 		     (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<Point,unsigned int>(lm->getCentroid(),cost));
+    obstacles.push_back(std::pair<Point,unsigned int>(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<pair<int,int> > findLMs(location loc);
-  state* thereIs(unsigned int pos, direction dir, pair<int,int> lms);
+  std::vector<std::pair<int,int> > findLMs(location loc);
+  state* thereIs(unsigned int pos, direction dir, std::pair<int,int> 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<WaypointWalkMC> waypointwalk_mc;
+  waypointwalk_id = motman->addPersistentMotion(waypointwalk_mc,MotionManager::kIgnoredPriority);
+  SharedObject<PostureMC> 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<TargetData>& 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<TargetData>& 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<TargetData> best;
+  int bestCount = 0;
+  std::vector<Shape<TargetData> >target_vector = select_type<TargetData>(localShS);
+  std::vector<Shape<TargetData> >::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<TargetData> 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<TargetData> 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<WaypointWalkMC>(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<WaypointWalkMC>(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 <queue>
+
+#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<Motion> motions;
-  vector<Constraint> constraints;
+  class GotoShape : public WaypointWalkNode {
+  public:
+    GotoShape() : WaypointWalkNode("GotoShape") {}
+    virtual void DoStart();
+  };
 
-private:
-  PilotRequest(requestType_t _reqType, unsigned int _request_id, 
-	       const vector<Motion>& _motions, const vector<Constraint>& _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<Constraint>& _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<Constraint>& _constraints)
-  { return PilotRequest(reactiveWalk, _request_id, Motion(Motion::rotate,speed), _constraints); }
-  static PilotRequest translateX(unsigned int _request_id, float speed, const vector<Constraint>& _constraints)
-  { return PilotRequest(reactiveWalk, _request_id, Motion(Motion::transX,speed), _constraints); }
-  static PilotRequest translateY(unsigned int _request_id, float speed, const vector<Constraint>& _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<Motion>(),vector<Constraint>()); }
+  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<PilotRequest> requests;
-  //  vector<unsigned int> 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<PilotRequest*> 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<LineData>& line1, const Shape<LineData>& line2) const;
   bool isBetween(const LineData& line1, const LineData& line2) const;
-  bool isInside(const vector<LineData>& bound) const;
+  bool isInside(const std::vector<LineData>& 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<PointData> 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<bool>* render() const;
+  virtual Sketch<bool>* 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<LineData>::iterator it = edges.begin();
        it != edges.end(); it++)
-    it->applyTransform(Tmat);
+    it->applyTransform(Tmat,newref);
   for (vector<Point>::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<LineData>::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<LineData>& ln1,const Shape<LineData>& ln2) { 
   return ln1->isLongerThan(ln2);
 }
 
 Sketch<bool>* PolygonData::render() const {
-  string const result_name = "render(" + getName() + ")";
-  Sketch<bool> canvas(space->getDualSpace(), result_name);
-  canvas = 0;
+  Sketch<bool> *canvas = new Sketch<bool>(space->getDualSpace(),"");
+  (*canvas) = 0;
   const int width = space->getDualSpace().getWidth();
   const int height = space->getDualSpace().getHeight();
   float x1, y1, x2, y2;
   for (vector<LineData>::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<bool>(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<bool>(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<LineData> edges; // edges which consist this polygon
+  std::vector<LineData> edges; // edges which consist this polygon
 private:
-  vector<Point> vertices; // cache of vertices
+  std::vector<Point> vertices; // cache of vertices
 
 public:
   static ShapeType_t getStaticType() { return polygonDataType; }
@@ -42,19 +42,19 @@
 
   //! Constructors
   PolygonData(const LineData&);
-  PolygonData(ShapeSpace& space, const vector<Point>& pts, bool closed, 
+  PolygonData(ShapeSpace& space, const std::vector<Point>& pts, bool closed, 
 	      bool end1Valid=true, bool end2Valid=true);
-  PolygonData(const vector<LineData>& lns)
+  PolygonData(const std::vector<LineData>& lns)
     : BaseData(lns.front()), edges(lns), vertices() { updateVertices(); }
   PolygonData(const PolygonData& other)
     : BaseData(other), edges(other.edges), vertices(other.vertices) {}
   
-  static vector<Shape<LineData> > extractPolygonEdges(Sketch<bool> const& sketch, Sketch<bool> const& occluder); //!< extracts then-edges lines
+  static std::vector<Shape<LineData> > extractPolygonEdges(Sketch<bool> const& sketch, Sketch<bool> 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<ShapeRoot> formPolygons(const vector<LineData>&, 
-					vector<Shape<PolygonData> >& existing, vector<ShapeRoot>& deleted); 
-  static vector<ShapeRoot> formPolygons(const vector<LineData>&); //!< forms polygons from lines
+  static std::vector<ShapeRoot> formPolygons(const std::vector<LineData>&, 
+					std::vector<Shape<PolygonData> >& existing, std::vector<ShapeRoot>& deleted); 
+  static std::vector<ShapeRoot> formPolygons(const std::vector<LineData>&); //!< 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<Point>& getVertices() const { return vertices; } //!< returns all vertices of this polygon
-  const vector<LineData>& getEdges() const { return edges; } //!< returns all edges of this polygon
-  vector<LineData>& getEdgesRW() { return edges; } //!< returns address of edge vector for modification
+  const std::vector<Point>& getVertices() const { return vertices; } //!< returns all vertices of this polygon
+  const std::vector<LineData>& getEdges() const { return edges; } //!< returns all edges of this polygon
+  std::vector<LineData>& getEdgesRW() { return edges; } //!< returns address of edge vector for modification
   //@}
   
   BoundingBox getBoundingBox() const;
 
-  vector<ShapeRoot> updateState();
+  std::vector<ShapeRoot> updateState();
 
   bool isClosed() const ; //<! returns if this polygon is closed
   
@@ -103,10 +103,12 @@
   virtual int getConfidence() const; //!< returns minimum confidence of all edges
   virtual bool isInside(const Point& pt) const;
   virtual void printParams() const;
-  virtual void applyTransform(const NEWMAT::Matrix& Tmat);
+  virtual void applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref=unspecified);
   virtual void projectToGround(const NEWMAT::Matrix& camToBase,
 			       const NEWMAT::ColumnVector& groundplane);
-  virtual void setColor(rgb new_color);
+  virtual void setColor(const rgb &new_color);
+  virtual void setColor(const unsigned int color_index);
+  virtual void setColor(const std::string &color_name);
   virtual Sketch<bool>* 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: ("<<centroid.coordX()<<","<<centroid.coordY()<<","<<centroid.coordZ()<<")\n";
+    std::cout << "New centroid: " << centroid << endl;
   }
 
   // =====================================================
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/PyramidData.h ./DualCoding/PyramidData.h
--- ../Tekkotsu_3.0/DualCoding/PyramidData.h	2006-07-21 13:57:52.000000000 -0400
+++ ./DualCoding/PyramidData.h	2007-11-11 18:57:21.000000000 -0500
@@ -68,11 +68,9 @@
   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
-  //void projectToGround(const NEWMAT::ColumnVector& groundplane);
-
   void projectToGround(const NEWMAT::Matrix & camToBase, 
 		       const NEWMAT::ColumnVector& groundplane);
     
@@ -80,9 +78,9 @@
 
   //! Extraction.
 
-  static Shape<PyramidData> extractPyramid(ShapeSpace& space, vector<Shape<BlobData> > &blobs);
+  static Shape<PyramidData> extractPyramid(ShapeSpace& space, std::vector<Shape<BlobData> > &blobs);
     
-  static vector<Point> findBoundingTriangle(ShapeSpace& space, Shape<BlobData> blob, 
+  static std::vector<Point> findBoundingTriangle(ShapeSpace& space, Shape<BlobData> blob, 
 					    Point centroid, Shape<LineData> 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 <vector>
 #include <list>
 
-#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> Region::extractRegions(const Sketch<usint>& labels, int area_thresh)
+std::list<Region> Region::extractRegions(const Sketch<uint>& labels, uint area_thresh)
 {
   size_t length = labels->getNumPixels();
   
   // tally up areas
-  vector<int> areas(labels->max()+1, 0); // not having +1 may have caused malloc crash
+  std::vector<uint> 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<Region> 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 <list>
 
-#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<Region> extractRegions(const Sketch<usint>& labels, int area_thresh = 10);
+  static std::list<Region> extractRegions(const Sketch<uint>& labels, uint area_thresh = 10);
 
   //! Return a single region from a sketch<bool>
   static Region extractRegion(const Sketch<bool>& 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<AgentData>(ShapeSpace &s, Point centerval=Point(0,0,0)) :
+  Shape<AgentData>(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<EllipseData> : 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<Shape<_type> > _name((_value));
+  std::vector<DualCoding::Shape<_type> > _name((_value));
 
 //! Create a new vector of shapes of mixed type
 #define NEW_SHAPEROOTVEC(_name, _value) \
-  vector<ShapeRoot> _name((_value));
+  std::vector<DualCoding::ShapeRoot> _name((_value));
 
 //! Iterate over the shapes in a vector; _var is the iterator
 #define SHAPEVEC_ITERATE(_shapesvec,_type,_var) \
-  for ( std::vector<Shape<_type> >::iterator _var##_it = _shapesvec.begin(); \
+  for ( std::vector<DualCoding::Shape<_type> >::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<Shape<_type> >::iterator _var2##_it = ++std::vector<Shape<_type> >::iterator(_var1##_it); \
+  for ( std::vector<DualCoding::Shape<_type> >::iterator _var2##_it = ++std::vector<DualCoding::Shape<_type> >::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<ShapeRoot>::iterator _var##_it = _shapesvec.begin(); \
+  for ( std::vector<DualCoding::ShapeRoot>::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<Shape<_type> >::iterator _var##_it = _shapesvec.begin(); \
+  for ( std::vector<DualCoding::Shape<_type> >::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<Shape<_type> >::iterator _var2##_it = ++std::vector<Shape<_type> >::iterator(_var1##_it); \
+  for ( std::vector<DualCoding::Shape<_type> >::iterator _var2##_it = ++std::vector<DualCoding::Shape<_type> >::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<ShapeRoot>::iterator _var##_it = _shapesvec.begin(); \
+  for ( std::vector<DualCoding::ShapeRoot>::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<ShapeRoot, bool> {
+class UnaryShapeRootPred : public std::unary_function<ShapeRoot, bool> {
 public:
 	virtual ~UnaryShapeRootPred() {} //!< virtual destructor to satisfy warning
 };
 
 //! Binary predicates over ShapeRoot objects
-class BinaryShapeRootPred : public binary_function<ShapeRoot, ShapeRoot, bool> {
+class BinaryShapeRootPred : public std::binary_function<ShapeRoot, ShapeRoot, bool> {
 public:
 	virtual ~BinaryShapeRootPred() {} //!< virtual destructor to satisfy warning
 };
 
 //! Unary predicates over Shape<T> objects
 template <class T>
-class UnaryShapePred : public unary_function<Shape<T>, bool> {
+class UnaryShapePred : public std::unary_function<Shape<T>, bool> {
 public:
 	virtual ~UnaryShapePred() {} //!< virtual destructor to satisfy warning
 };
 
 //! Binary predicates over Shape<T> objects
 template <class T>
-class BinaryShapePred : public binary_function<Shape<T>, Shape<T>, bool> {
+class BinaryShapePred : public std::binary_function<Shape<T>, Shape<T>, 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<typename PredType1, typename PredType2>
-class shortcircuit_and : public unary_function<typename PredType1::argument_type,bool> {
+class shortcircuit_and : public std::unary_function<typename PredType1::argument_type,bool> {
  public:
   PredType1 p1;
   PredType2 p2;
   shortcircuit_and(PredType1 _p1, PredType2 _p2) :
-    unary_function<typename PredType1::argument_type,bool>(), p1(_p1), p2(_p2) {}
+    std::unary_function<typename PredType1::argument_type,bool>(), p1(_p1), p2(_p2) {}
   bool operator() (const typename PredType1::argument_type &shape) const {
     if ( p1(shape) )
       return p2(shape);
@@ -127,12 +131,12 @@
 };
 
 template<typename PredType1, typename PredType2>
-class shortcircuit_or : public unary_function<typename PredType1::argument_type,bool> {
+class shortcircuit_or : public std::unary_function<typename PredType1::argument_type,bool> {
  public:
   PredType1 p1;
   PredType2 p2;
   shortcircuit_or(PredType1 _p1, PredType2 _p2) :
-    unary_function<typename PredType1::argument_type,bool>(), p1(_p1), p2(_p2) {}
+    std::unary_function<typename PredType1::argument_type,bool>(), 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<typename PredType1, typename PredType2>
-shortcircuit_and<PredType1,PredType2> andPred(PredType1 p1, PredType2 p2) {
+shortcircuit_and<PredType1,PredType2> AndPred(PredType1 p1, PredType2 p2) {
   return shortcircuit_and<PredType1,PredType2>(p1,p2);
 }
 
 //! Disjunction of two predicates; p2 is called only if p1 returns false
 template<typename PredType1, typename PredType2>
-shortcircuit_or<PredType1,PredType2>  orPred(PredType1 p1, PredType2 p2) {
+shortcircuit_or<PredType1,PredType2>  OrPred(PredType1 p1, PredType2 p2) {
   return shortcircuit_or<PredType1,PredType2>(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<typename PredType>
+ShapeRoot find_if(const std::vector<ShapeRoot> &vec, PredType pred) {
+  typename std::vector<ShapeRoot>::const_iterator result = find_if(vec.begin(),vec.end(),pred);
+  if ( result != vec.end() )
+    return *result;
+  else
+    return ShapeRoot();
+}
+
+//! Find a Shape<T> in a vector of ShapeRoot satisfying pred
 template<class T, typename PredType>
-Shape<T> find_if(const vector<Shape<T> > &vec, PredType pred) {
-  typename vector<Shape<T> >::const_iterator result = find_if(vec.begin(),vec.end(),pred);
+Shape<T> find_if(const std::vector<ShapeRoot> &vec, PredType pred) {
+  shortcircuit_and<IsType,PredType> tpred(AndPred(IsType(T::getStaticType()),pred));
+  typename std::vector<ShapeRoot>::const_iterator result = find_if(vec.begin(),vec.end(),tpred);
+  if ( result != vec.end() )
+    return ShapeRootTypeConst(*result,T);
+  else
+    return Shape<T>();
+}
+
+//! Find a Shape<T> satisfying pred
+template<class T, typename PredType>
+Shape<T> find_if(const std::vector<Shape<T> > &vec, PredType pred) {
+  typename std::vector<Shape<T> >::const_iterator result = find_if(vec.begin(),vec.end(),pred);
   if ( result != vec.end() )
     return *result;
   else
     return Shape<T>();
 }
 
+//! Find a Shape<T> in a vector of ShapeRoot
+template<class T>
+Shape<T> find_if(const std::vector<ShapeRoot> &vec) {
+  typename std::vector<ShapeRoot>::const_iterator result = find_if(vec.begin(),vec.end(),IsType(T::getStaticType()));
+  if ( result != vec.end() )
+    return ShapeRootTypeConst(*result,T);
+  else
+    return Shape<T>();
+}
+
 //! Return the first ShapeRoot with the specified name, else return an invalid ShapeRoot
 template<class T>
-Shape<T> find_shape(const vector<ShapeRoot> &vec, const std::string &name) {
-  for ( vector<ShapeRoot>::const_iterator it = vec.begin();
+Shape<T> find_shape(const std::vector<ShapeRoot> &vec, const std::string &name) {
+  for ( std::vector<ShapeRoot>::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<Shape<T> > select_type(std::vector<ShapeRoot> &vec) {
   std::vector<Shape<T> > 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<const Shape<T>&>(element));
   });
   return result;
 }
 
+//! Find all elements in a vector of Shape<T> satisfying pred
 template<class T, typename PredType>
 std::vector<Shape<T> > subset(const std::vector<Shape<T> > &vec, PredType pred) {
   std::vector<Shape<T> > result;
@@ -235,21 +272,56 @@
   return result;
 }
 
+//! Find all elements in a vector of ShapeRoot satisfying pred
+template<typename PredType>
+std::vector<ShapeRoot> subset(const std::vector<ShapeRoot> &vec, PredType pred) {
+  std::vector<ShapeRoot> result;
+  remove_copy_if(vec.begin(), vec.end(),
+		 std::back_insert_iterator<std::vector<ShapeRoot> >(result),
+		 not1(pred));
+  return result;
+}
+
+//! Find all elements of type T in a vector of ShapeRoot satisfying pred
+template<class T, typename PredType>
+std::vector<T> subset(const std::vector<ShapeRoot> &vec, PredType pred) {
+  std::vector<Shape<T> > result;
+  shortcircuit_and<IsType,PredType> tpred(AndPred(IsType(T::getStaticType()),pred));
+  remove_copy_if(vec.begin(), vec.end(),
+		 std::back_insert_iterator<std::vector<Shape<T> > >(result),
+		 not1(tpred));
+  return result;
+}
+
 template<class T, typename ComparisonType>
-Shape<T> max_element(const vector<Shape<T> > &vec, ComparisonType comp) {
-  typename vector<Shape<T> >::const_iterator result = max_element(vec.begin(),vec.end(),comp);
+Shape<T> max_element(const std::vector<Shape<T> > &vec, ComparisonType comp) {
+  typename std::vector<Shape<T> >::const_iterator result = max_element(vec.begin(),vec.end(),comp);
   if ( result != vec.end() )
     return *result;
   else
     return Shape<T>();
 }
 
+template<typename ComparisonType>
+ShapeRoot max_element(const std::vector<ShapeRoot> &vec, ComparisonType comp) {
+  typename std::vector<ShapeRoot>::const_iterator result = max_element(vec.begin(),vec.end(),comp);
+  if ( result != vec.end() )
+    return *result;
+  else
+    return ShapeRoot();
+}
+
 template<class T, typename ComparisonType>
-Shape<T> min_element(const vector<Shape<T> > &vec, ComparisonType comp) {
+Shape<T> min_element(const std::vector<Shape<T> > &vec, ComparisonType comp) {
   return max_element(vec, not2(comp));
 }
 
 
+template<typename ComparisonType>
+ShapeRoot min_element(const std::vector<ShapeRoot> &vec, ComparisonType comp) {
+  return max_element(vec, not2(comp));
+}
+
 template<class T, typename PredType>
 std::vector<Shape<T> > stable_sort(const std::vector<Shape<T> > &vec, PredType pred) {
   std::vector<Shape<T> > result(vec);
@@ -257,11 +329,18 @@
   return result;
 }
 
+template<typename PredType>
+std::vector<ShapeRoot> stable_sort(const std::vector<ShapeRoot> &vec, PredType pred) {
+  std::vector<ShapeRoot> 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<LineData> : 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 <iostream>
+
+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<LocalizationParticleData> : 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<size_t>(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<T>
+//! Parent class for all Shape<xxxData> objects
 
 /*! Shape<T> points to data objects of type T within a ShapeSpace, e.g.,
-    Shape<LineData> points to a LineData object.
+    @a Shape<LineData> 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 <vector>
 #include <sstream>
 #include <string>
+#include <float.h>
+#include <cmath>
 
 #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<ShapeRoot>(30);
+  shapeCache = std::vector<ShapeRoot>(30);
   shapeCache.clear();
 }
 
@@ -44,8 +49,8 @@
   return shapeCache[shapeCache.size()-1];
 };
 
-void ShapeSpace::importShapes(vector<ShapeRoot>& foreign_shapes) {
-  for (vector<ShapeRoot>::const_iterator it = foreign_shapes.begin();
+void ShapeSpace::importShapes(std::vector<ShapeRoot>& foreign_shapes) {
+  for (std::vector<ShapeRoot>::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<ShapeRoot>::iterator it = shapeCache.begin();
+    for ( std::vector<ShapeRoot>::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<ShapeRoot>& shapes_vec) {
+void ShapeSpace::deleteShapes(std::vector<ShapeRoot>& 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<ShapeRoot> allShapes_vec = allShapes();
+void ShapeSpace::applyTransform(const NEWMAT::Matrix& Tmat, const ReferenceFrameType_t newref) {
+  std::vector<ShapeRoot> 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<ShapeRoot> allShapes_vec = allShapes();
+  std::vector<ShapeRoot> allShapes_vec = allShapes();
   return(getCentroidOfSubset(allShapes_vec));
 }
 
-Point ShapeSpace::getCentroidOfSubset(const vector<ShapeRoot>& subsetShapes_vec) {
+Point ShapeSpace::getCentroidOfSubset(const std::vector<ShapeRoot>& 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<ShapeRoot> &allShapes_vec = allShapes();
-  ostringstream liststream;
+std::string ShapeSpace::getShapeListForGUI(void) {
+  std::vector<ShapeRoot> &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<PolygonData>& current = ShapeRootTypeConst(allShapes_vec[i],PolygonData);
 	liststream << "num_vtx: " << current->getVertices().size() << endl;
-	for (vector<Point>::const_iterator vtx_it = current->getVertices().begin();
+	for (std::vector<Point>::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<LocalizationParticleData>& 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<ShapeRoot> &allShapes_vec = allShapes();
+  std::vector<ShapeRoot> &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<ShapeRoot> allShapes_vec = allShapes();
+  std::vector<ShapeRoot> allShapes_vec = allShapes();
   int cur;
   int num = (int)(allShapes_vec.size());
   cout << "SHAPE SPACE : SUMMARY BEGIN" << endl;
-  vector<int> shape_counts;
+  std::vector<int> 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<ShapeRoot> temp;
+  temp.reserve(shapeCache.size());
+  for ( std::vector<ShapeRoot>::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<ShapeRoot> shapeCache;
+  std::vector<ShapeRoot> 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<ShapeRoot>& shapes_vec); 
+  template<typename T> 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<TargetData> : public ShapeRoot {
+public:
+  SHAPESTUFF_H(TargetData);  // defined in ShapeRoot.h
+
+  //! Make a target from a point, two end points, and a height
+  Shape<TargetData>(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<TargetData>(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<bool> 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<bool>& operator^= (Sketch<bool>& arg1, Sketch<bool> 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<T> operator[] (const Sketch<usint>& indirection) const;
+  const Sketch<T> operator[] (const Sketch<uint>& 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<uchar>
   operator Sketch<uchar>() const;
 
-  //! operator for implicity or explicitly converting to Sketch<usint>
-  operator Sketch<usint>() const;
+  //! operator for implicity or explicitly converting to Sketch<uint>
+  operator Sketch<uint>() const;
 
   //! operator for implicity or explicitly converting to Sketch<float>
   operator Sketch<float>() const;
@@ -135,7 +135,7 @@
 template <class T>
 Sketch<T>::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 <class T>
-const Sketch<T> Sketch<T>::operator[] (const Sketch<usint>& indirection) const
+const Sketch<T> Sketch<T>::operator[] (const Sketch<uint>& indirection) const
 {
   checkValid();
   Sketch<T> result(*(data->space), "shift("+(*this)->getName()+","+indirection->getName()+")");
@@ -289,9 +288,10 @@
 template <class T>
 Sketch<T>& Sketch<T>::operator= (const Sketch<T>& 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<bool> 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<bool>& operator&= (Sketch<bool>& arg1, Sketch<bool> const& arg2);
 Sketch<bool>& operator|= (Sketch<bool>& arg1, Sketch<bool> const& arg2);
+Sketch<bool>& operator^= (Sketch<bool>& arg1, Sketch<bool> const& arg2);
 //@}
 
 template <class T>
@@ -483,13 +485,13 @@
 Sketch<uchar>::operator Sketch<bool>() const;
 
 template <class T>
-Sketch<T>::operator Sketch<usint>() const {
+Sketch<T>::operator Sketch<uint>() const {
   /*
   std::cout << "Converting " << this << " '" << getName() << "'"
 	    << " id=" << getId() << ",parent=" << getParentId() << ",refcount=" << data->refcount
-	    << " to Sketch<usint>\n";
+	    << " to Sketch<uint>\n";
   */
-  Sketch<usint> converted("usint("+(*this)->getName()+")", *this);
+  Sketch<uint> 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<class T>
 SketchData<T>::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<uchar>::getType() const { return sketchUchar; }
 template<>
-inline SketchType_t SketchData<usint>::getType() const { return sketchUsint; }
+inline SketchType_t SketchData<uint>::getType() const { return sketchUint; }
 template<>
 inline SketchType_t SketchData<float>::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 <class T>
 unsigned int SketchData<T>::savePixels(char buf[], unsigned int avail) const
 {
-	const unsigned int imglength  = getWidth() * getHeight() * sizeof(T);
-	ASSERTRETVAL(imglength<avail,"Insufficient space for image",0);
-	memcpy(buf,(const unsigned char*)&(pixels[0]),imglength);
-	return imglength;
+  const unsigned int imglength  = getWidth() * getHeight() * sizeof(T);
+  ASSERTRETVAL(imglength<avail,"Insufficient buffer space for image",0);
+  memcpy(buf,(const unsigned char*)&(pixels[0]),imglength);
+  return imglength;
 }
 
 #ifdef __POWERPC__
@@ -327,14 +327,14 @@
 template<>
 inline unsigned int SketchData<bool>::savePixels(char buf[], unsigned int avail) const
 {
-	const unsigned int imglength  = getWidth() * getHeight() * sizeof(char);
-	ASSERTRETVAL(imglength<avail,"Insufficient space for image",0);
-	if(sizeof(bool)==sizeof(char))
-		memcpy(buf,(const unsigned char*)&(pixels[0]),imglength);
-	else
-		for(unsigned int i=0; i<imglength; ++i)
-			buf[i]=pixels[i]; //do manual copy to ensure one byte per pixel
-	return imglength;
+  const unsigned int imglength  = getWidth() * getHeight() * sizeof(char);
+  ASSERTRETVAL(imglength<avail,"Insufficient buffer space for image",0);
+  if(sizeof(bool)==sizeof(char))
+    memcpy(buf,(const unsigned char*)&(pixels[0]),imglength);
+  else
+    for(unsigned int i=0; i<imglength; ++i)
+      buf[i]=pixels[i]; //do manual copy to ensure one byte per pixel
+  return imglength;
 }
 #endif
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchDataRoot.cc ./DualCoding/SketchDataRoot.cc
--- ../Tekkotsu_3.0/DualCoding/SketchDataRoot.cc	2006-03-03 06:13:07.000000000 -0500
+++ ./DualCoding/SketchDataRoot.cc	2007-03-07 00:58:19.000000000 -0500
@@ -40,4 +40,13 @@
   if ( !_name.empty() ) setName(_name);
 }
 
+void SketchDataRoot:: setColor(const std::string &colorname) {
+  setColor(ProjectInterface::getColorRGB(colorname));
+}
+
+void SketchDataRoot::setColor(const color_index cindex) {
+  setColor(ProjectInterface::getColorRGB(cindex));
+}
+
+
 } // namespace
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchDataRoot.h ./DualCoding/SketchDataRoot.h
--- ../Tekkotsu_3.0/DualCoding/SketchDataRoot.h	2006-07-19 17:54:12.000000000 -0400
+++ ./DualCoding/SketchDataRoot.h	2007-03-07 00:58:19.000000000 -0500
@@ -75,8 +75,11 @@
   void setParentId(int const _id) { parentId = _id; }
   bool isViewable() const { return viewable; }
   void setViewable(bool const v) { viewable=v; }
+  int getRefcount() const { return refcount; }
   rgb getColor() const { return color; }
-  void setColor(const rgb _color) { color = _color; }
+  void setColor(const rgb &_color) { color = _color; }
+  void setColor(const std::string &colorname);
+  void setColor(const color_index cindex);
   ColorMapType_t getColorMap() const { return colormap; }
   void setColorMap(const ColorMapType_t _map) { colormap = _map; }
   const std::string& getName() const { return name; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/DualCoding/SketchIndices.cc ./DualCoding/SketchIndices.cc
--- ../Tekkotsu_3.0/DualCoding/SketchIndices.cc	2006-04-27 18:53:10.000000000 -0400
+++ ./DualCoding/SketchIndices.cc	2007-08-24 21:49:16.000000000 -0400
@@ -7,7 +7,7 @@
 
 namespace DualCoding {
 
-const SketchIndices SketchIndices::operator[] (const Sketch<usint>& indirection) const {
+const SketchIndices SketchIndices::operator[] (const Sketch<uint>& 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 <iosfwd> // forward declaration for ostream
-
 #include <ext/hash_set>
-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<usint, hash<usint>, equal_to<usint> > SketchIndicesTable;
+  typedef __gnu_cxx::hash_set<uint, __gnu_cxx::hash<uint>, std::equal_to<uint> > 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<usint>& indirection) const;
+  const SketchIndices operator[] (const Sketch<uint>& 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 <iostream>
 #include <sstream> // 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<SketchData<T>*> elements;
   
-  SketchPool<T>(SketchSpace *_space, int poolsize = 0); 
+  //! Constructor
+  SketchPool<T>(SketchSpace *_space, const std::string& _name, int poolsize = 0); 
   
+	//! Destructor
   ~SketchPool<T>();
   
-  //! 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<T>* get_free_element(void); 
+  SketchData<T>* getFreeElement(void); 
   
   SketchData<T>* findSketchData(const std::string &name);
 
@@ -55,9 +58,9 @@
 // **************** Implementation ****************
 
 template <class T>
-SketchPool<T>::SketchPool(SketchSpace *_space, int poolsize) :
-	SketchPoolRoot(_space),
-	elements(std::vector<SketchData<T>*>(poolsize)) 
+SketchPool<T>::SketchPool(SketchSpace *_space, const std::string& _name, int poolsize) :
+  SketchPoolRoot(_space,_name),
+  elements(std::vector<SketchData<T>*>(poolsize)) 
 {
   for (int i=0; i<poolsize; i++) {
     elements[i] = new SketchData<T>(space);
@@ -66,13 +69,18 @@
 
 template <class T>
 SketchPool<T>::~SketchPool() {
-  for (unsigned int i = 0; i < elements.size(); i++) {
+	deleteElements();
+}
+
+template <class T>
+void SketchPool<T>::deleteElements() {
+  for (unsigned int i = 0; i < elements.size(); i++)
     if(elements[i]->refcount > 0)
       printf("ERROR in ~SketchPool<T>: 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 <class T>
@@ -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 <class T>
-SketchData<T>* SketchPool<T>::get_free_element(void) 
+SketchData<T>* SketchPool<T>::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<class T>
-SketchData<T>* SketchPool<T>::findSketchData(const std::string &name) {
+SketchData<T>* SketchPool<T>::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 <class T>
-void SketchPool<T>::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<T>::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<T>.
 /*! SketchPoolRoot is the non-templated parent class of SketchPool<T>.
     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<bool>& faker = *reinterpret_cast<const Sketch<bool>*>(this);
-  return *(faker.data);
+const SketchDataRoot* SketchRoot::rootGetData() const {
+  const Sketch<bool>* faker = reinterpret_cast<const Sketch<bool>*>(this);
+  return reinterpret_cast<const SketchDataRoot*>(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<usint>(*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<uint>(*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<usint>(*this,"idN");
-    idxS = new Sketch<usint>(*this,"idS");
-    idxE = new Sketch<usint>(*this,"idE");
-    idxW = new Sketch<usint>(*this,"idW");
+    idxN = new Sketch<uint>(*this,"idN");
+    idxS = new Sketch<uint>(*this,"idS");
+    idxE = new Sketch<uint>(*this,"idE");
+    idxW = new Sketch<uint>(*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<usint>(*this,"idNE");
-    idxNW = new Sketch<usint>(*this,"idNW");
-    idxSE = new Sketch<usint>(*this,"idSE");
-    idxSW = new Sketch<usint>(*this,"idSW");
+    idxNE = new Sketch<uint>(*this,"idNE");
+    idxNW = new Sketch<uint>(*this,"idNW");
+    idxSE = new Sketch<uint>(*this,"idSE");
+    idxSW = new Sketch<uint>(*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<usint>& 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<uint>& 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<T> classes
   //@{
-  SketchPool<bool>  boolPool; 
+  SketchPool<bool>  boolPool;
   SketchPool<uchar> ucharPool;
-  SketchPool<usint> usintPool;
+  SketchPool<uint> uintPool;
   SketchPool<float> floatPool; 
   //@}
   
@@ -54,15 +54,15 @@
 
   //!@name Pre-generated indices for different directions
   //@{
-  Sketch<usint> *idx;
-  Sketch<usint> *idxN;
-  Sketch<usint> *idxS;
-  Sketch<usint> *idxE;
-  Sketch<usint> *idxW;
-  Sketch<usint> *idxNE;
-  Sketch<usint> *idxNW;
-  Sketch<usint> *idxSE;
-  Sketch<usint> *idxSW;
+  Sketch<uint> *idx;
+  Sketch<uint> *idxN;
+  Sketch<uint> *idxS;
+  Sketch<uint> *idxE;
+  Sketch<uint> *idxW;
+  Sketch<uint> *idxNE;
+  Sketch<uint> *idxNW;
+  Sketch<uint> *idxSE;
+  Sketch<uint> *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<bool>&  get_pool(const Sketch<bool>&)  { return boolPool; }
   SketchPool<uchar>& get_pool(const Sketch<uchar>&) { return ucharPool; }
-  SketchPool<usint>& get_pool(const Sketch<usint>&) { return usintPool; }
+  SketchPool<uint>&  get_pool(const Sketch<uint>&)  { return uintPool; }
   SketchPool<float>& get_pool(const Sketch<float>&) { 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<usint>& indices, int x, int y, int shift_i);
+  void setIdx(Sketch<uint>& 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<ShapeRoot> SphereData::extractSpheres(const Sketch<bool>& sketch)
+std::vector<Shape<SphereData> > SphereData::extractSpheres(const Sketch<bool>& 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<Region> regionlist = Region::extractRegions(labels,REGION_THRESH);
-  std::vector<ShapeRoot> spheres;
+  std::vector<Shape<SphereData> > 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<SphereData> 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<SphereData>(temp_sphere));
     };
   }
   return spheres;
 }
 
-std::vector<ShapeRoot> SphereData::get_spheres(const Sketch<uchar>& cam) {
+std::vector<Shape<SphereData> > SphereData::get_spheres(const Sketch<CMVision::uchar>& cam) {
   //! Declare all colors as valid.
   std::vector<bool> Valid_Colors;
   Valid_Colors.resize(ProjectInterface::getNumColors(),true);
   return(get_spheres(cam,Valid_Colors));
 }
 
-std::vector<ShapeRoot> SphereData::get_spheres(const Sketch<uchar>& cam,
+std::vector<Shape<SphereData> > SphereData::get_spheres(const Sketch<CMVision::uchar>& cam,
 						 std::vector<bool>& Valid_Colors) {
-  std::vector<ShapeRoot> spheres_vec;
+  std::vector<Shape<SphereData> > 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<ShapeRoot> spheresList = SphereData::extractSpheres(pmask);
+      std::vector<Shape<SphereData> > 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<ShapeRoot> extractSpheres(const Sketch<bool>& sketch);
-  static std::vector<ShapeRoot> get_spheres(const Sketch<CMVision::uchar>& cam);
-  static std::vector<ShapeRoot> get_spheres(const Sketch<CMVision::uchar>& cam,
-					     vector<bool>& Valid_Colors);
+  static std::vector<Shape<SphereData> > extractSpheres(const Sketch<bool>& sketch);
+  static std::vector<Shape<SphereData> > get_spheres(const Sketch<CMVision::uchar>& cam);
+  static std::vector<Shape<SphereData> > get_spheres(const Sketch<CMVision::uchar>& cam,
+					     std::vector<bool>& 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<TargetData>& 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<TargetData>& 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<TargetData>& 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<bool>* TargetData::render() const {
+  SketchSpace &SkS = space->getDualSpace();
+  
+  Sketch<bool>& draw_result = 
+    *new Sketch<bool>(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> 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<TargetData> result = extractLineTarget(frontSketch, backSketch, rightSketch, occluders, height);
+  
+  // delete temporary camera shapes
+  //camShS.deleteShapes(horBlobs);
+  //camShS.deleteShapes(vertBlobs);
+  
+  return result;
+}
+
+Shape<TargetData> TargetData::extractLineTarget(Sketch<bool>& frontSketch, Sketch<bool>& backSketch, Sketch<bool>& rightSketch, Sketch<bool>& 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<TargetData> 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> TargetData::extractLineTarget(Shape<LineData>& frontLine, Shape<LineData>& backLine, Shape<LineData>& 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<TargetData> 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<TargetData> 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<TargetData> 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<typename T> 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<TargetData> extractLineTarget(std::string frontColor = "yellow", std::string backColor = "pink", std::string rightColor = "blue", std::string occluderColor = "orange", const float height = 90.0f);
+  static Shape<TargetData> extractLineTarget(Sketch<bool>& frontSketch, Sketch<bool>& backSketch, Sketch<bool>& rightSketch, Sketch<bool>& occluderSketch, const float height = 90.0f);
+  static Shape<TargetData> extractLineTarget(Shape<LineData>& camFrontLine, Shape<LineData>& camBackLine, Shape<LineData>& camRightLine, rgb color, const float height = 90.0f);
+  
+private:
+  //! Render into a sketch space and return reference. (Private.)
+  Sketch<bool>* 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<AgentData>(worldShS,Point());
+    theAgent = Shape<AgentData>(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<AgentData>();
     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<uchar>
-Sketch<uchar> VRmixin::sketchFromChannel(RawCameraGenerator::channel_id_t chan) {
-  if ( chan < 0 || chan >= RawCameraGenerator::NUM_CHANNELS)
-    chan = RawCameraGenerator::CHAN_Y;
+Sketch<uchar> 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<uchar> 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<BlobData>
 vector<Shape<BlobData> >
-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<Shape<BlobData> > result;
   const CMVision::run<uchar> *rle_buffer = reinterpret_cast<const CMVision::run<uchar>*>
     (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 && i<maxblobs && list_head->area >= 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<BlobData>(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<AgentData> 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<uchar> sketchFromSeg();
   
   //! Import channel n image as a Sketch<uchar>
-  static Sketch<uchar> sketchFromChannel(RawCameraGenerator::channel_id_t chan);
+  static Sketch<uchar> sketchFromChannel(const RawCameraGenerator::channel_id_t chan);
   
   //! Import the current y-channel camera image as a Sketch<uchar>
   static Sketch<uchar> sketchFromRawY();
   
   //! Import blobs from the current region list as a vector of Shape<BlobData>
   static std::vector<Shape<BlobData> >
-  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<usint>
+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<usint> 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<bool> colormask(const Sketch<uchar>& src, std::string colorname) {
+Sketch<bool> colormask(const Sketch<uchar>& src, const std::string &colorname) {
   return colormask(src, ProjectInterface::getColorIndex(colorname));
 }
 
-Sketch<bool> colormask(const Sketch<uchar>& src, int color_idx) {
-  Sketch<bool> result(src == color_idx);
-  result->setColor(ProjectInterface::getColorRGB(color_idx));
+Sketch<bool> colormask(const Sketch<uchar>& src, color_index cindex) {
+  Sketch<bool> result(src == cindex);
+  result->setColor(ProjectInterface::getColorRGB(cindex));
   return result;
 }
 
-Sketch<usint> bdist(const Sketch<bool>& dest, 
+Sketch<uint> bdist(const Sketch<bool>& dest, 
 			    const Sketch<bool>& obst, 
-			    const int maxdist) {
+			    const uint maxdist) {
   SketchSpace &space = dest->getSpace();
   space.requireIdx4way();
-  Sketch<float> 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<uint> 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<usint> edist(const Sketch<bool>& target) {
+Sketch<uint> edist(const Sketch<bool>& 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<usint> dist("edist("+target->getName()+")", target);
+  Sketch<uint> 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<usint> labelcc(const Sketch<bool>& sketch, int minarea) {
+Sketch<uint> labelcc(const Sketch<bool>& sketch, int minarea) {
   Sketch<uchar> 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<usint> oldlabelcc(const Sketch<bool>& source, Connectivity_t connectivity)
+Sketch<uint> oldlabelcc(const Sketch<bool>& source, Connectivity_t connectivity)
 {
   bool conn8 = (connectivity == EightWayConnect);
   const int width = source.width;
   const int height = source.height;
-  Sketch<usint> labels("oldlabelcc("+source->getName()+")",source);
+  Sketch<uint> 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<int> eq_classes(500); // vector of equivalence classes for union-find
+  std::vector<int> 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<usint> areacc(const Sketch<bool>& source, Connectivity_t connectivity) {
-  NEW_SKETCH_N(labels, usint, visops::oldlabelcc(source,connectivity));
+Sketch<uint> areacc(const Sketch<bool>& source, Connectivity_t connectivity) {
+  NEW_SKETCH_N(labels, uint, visops::oldlabelcc(source,connectivity));
   return visops::areacc(labels);
 }
 
-Sketch<usint> areacc(const Sketch<usint>& labels) {
-  vector<int> areas(1+labels->max(), 0);
-  for (usint i = 0; i<labels->getNumPixels(); i++)
+Sketch<uint> areacc(const Sketch<uint>& labels) {
+  std::vector<int> areas(1+labels->max(), 0);
+  for (uint i = 0; i<labels->getNumPixels(); i++)
     ++areas[labels[i]];
   areas[0] = 0;
-  Sketch<usint> result("areacc("+labels->getName()+")",labels);
-  for (usint i = 0; i<labels->getNumPixels(); i++)
+  Sketch<uint> result("areacc("+labels->getName()+")",labels);
+  for (uint i = 0; i<labels->getNumPixels(); i++)
     result[i] = areas[labels[i]];
   return result;
 }
 
 Sketch<bool> minArea(const Sketch<bool>& 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<uchar> 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<bool> skel(const Sketch<bool>& im)
-{
+Sketch<bool> skel(const Sketch<bool>& im) {
   NEW_SKETCH_N(result, bool, horsym(im) | versym(im));
   result->setName("skel("+im->getName()+")");
   return result;
 }
 
-Sketch<bool> seedfill(const Sketch<bool>& borders, size_t index)
-{
+Sketch<bool> seedfill(const Sketch<bool>& 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<uint> &regions, Sketch<bool> &result, std::vector<bool> &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<bool> fillExterior(const Sketch<bool>& 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<bool> 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<bool> fillInterior(const Sketch<bool>& borders) {
+  return ! (borders | fillExterior(borders));
+}
+
 Sketch<bool> leftHalfPlane(const Shape<LineData> &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<usint> convolve(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
+Sketch<uint> convolve(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
 		       int istart, int jstart, int width, int height) {
-  Sketch<usint> result("convolve("+sketch->getName()+")",sketch);
+  Sketch<uint> 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<height; kj++)
 	  if ( si+di+ki >= 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<usint> templateMatch(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
+Sketch<uint> templateMatch(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
 		       int istart, int jstart, int width, int height) {
-  Sketch<usint> result("convolve0("+sketch->getName()+")",sketch);
+  Sketch<uint> 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<bool> of same size as parent @a sketch
   Sketch<bool> zeros(const SketchRoot& sketch);
 
-  //! Returns a copy of the sketch.
+  //! Returns a deep copy of the sketch: actually copies the pixels
   template<class T>
   Sketch<T> copy(const Sketch<T>& other) {
-    Sketch<T> result("copy("+other->getName()+")", other);
+    Sketch<T> 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<T> max(const Sketch<T>& src, const T value) {
     Sketch<T> 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<class T>
   Sketch<T> max(const Sketch<T>& arg1, const Sketch<T>& arg2) {
-    Sketch<T> result("max("+arg1->getName()+","+arg2->getName+")",arg1);
+    Sketch<T> 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<T> min(const Sketch<T>& src, const T value) {
     Sketch<T> 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<class T>
   Sketch<T> min(const Sketch<T>& arg1, const Sketch<T>& arg2) {
-    Sketch<T> result("min("+arg1->getName()+","+arg2->getName+")",arg1);
+    Sketch<T> 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<bool> seedfill(const Sketch<bool>& 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<bool> fillExterior(const Sketch<bool>& 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<bool> fillInterior(const Sketch<bool>& borders);
+
+  //@}
+
   //!@name Miscellaneous functions
   //@{
 
   //! Returns all the pixels of the named color.
-  Sketch<bool> colormask(const Sketch<uchar>& src, const std::string colorname);
+  Sketch<bool> colormask(const Sketch<uchar>& src, const std::string &colorname);
 
   //! Returns all the pixels with the specified color index.
-  Sketch<bool> colormask(const Sketch<uchar>& src, int color_idx);
-
-  //! Fills a region bounded by borders, starting at position given by index
-  Sketch<bool> seedfill(const Sketch<bool>& borders, size_t index);
+  Sketch<bool> colormask(const Sketch<uchar>& 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<usint> bdist(const Sketch<bool> &dest, const Sketch<bool> &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<uint> bdist(const Sketch<bool> &dest, const Sketch<bool> &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<usint> edist(const Sketch<bool> &dest);
+  Sketch<uint> edist(const Sketch<bool> &dest);
   
   //! Connected components labeling using CMVision.  Components numbered sequentially from 1.
-  Sketch<usint> labelcc(const Sketch<bool>& source, int minarea=1);
+  Sketch<uint> labelcc(const Sketch<bool>& 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<usint> oldlabelcc(const Sketch<bool>& source, 
+  Sketch<uint> oldlabelcc(const Sketch<bool>& source, 
 		      Connectivity_t connectivity=EightWayConnect);
 
   //! Each pixel of the result is the area of that connected component.
-  Sketch<usint> areacc(const Sketch<bool>& source, Connectivity_t connectivity=EightWayConnect);
+  Sketch<uint> areacc(const Sketch<bool>& source, Connectivity_t connectivity=EightWayConnect);
 
   //! Each pixel of the result is the area of that connected component.
-  Sketch<usint> areacc(const Sketch<usint>& labels);
+  Sketch<uint> areacc(const Sketch<uint>& labels);
 
   //! Low-pass filter by eliminating small regions
   Sketch<bool> minArea(const Sketch<bool>& sketch, int minval=5);
 
   //@}
 
-  //! @name Conditional assignment
+  //! @name Masking and conditional assignment
   //@{
+  //! Returns pixels of @a A masked by bool sketch @a B
+  template<typename T>
+  Sketch<T> mask(const Sketch<T> &A, const Sketch<bool> &B) {
+    Sketch<T> 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<typename T>
@@ -255,6 +280,7 @@
   Sketch<bool> topHalfPlane(const Shape<LineData> &ln);
 
   Sketch<bool> bottomHalfPlane(const Shape<LineData> &ln);
+  //@}
 
   //! Returns a copy of im except that its pixels within offset from boundaries are removed
   Sketch<bool> non_bounds(const Sketch<bool>& im, int offset);
@@ -269,11 +295,11 @@
   Sketch<bool> susan_edge_points(const Sketch<uchar>& im, int brightness);
   
   //! Convolves a kernel with an image.
-  Sketch<usint> convolve(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
+  Sketch<uint> convolve(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
 			 int i, int j, int width, int height);
 
   //! Convolves a kernel with an image, normalizing the kernel to zero mean.
-  Sketch<usint> templateMatch(const Sketch<uchar> &sketch, Sketch<uchar> &kernel, 
+  Sketch<uint> templateMatch(const Sketch<uchar> &sketch, Sketch<uchar> &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<class T>
+template<class T, int TID=-1>
 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<T,TID> >(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<T,TID> >);
+#endif
+	}
+	static const EventBase::classTypeID_t autoRegisterDataEvent; //!< causes class type id to automatically be regsitered with EventBase's FamilyFactory (getTypeRegistry())
 };
 
+template<class T,int TID>
+const EventBase::classTypeID_t DataEvent<T,TID>::autoRegisterDataEvent=DataEvent<T,TID>::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 <stdio.h>
 #include <sstream>
 #include <libxml/tree.h>
 #include "Shared/debuget.h"
+#include "Events/RemoteRouter.h"
+
+// just to give linkage for the auto register:
+const EventBase::classTypeID_t EventBase::autoRegisterEventBase=getTypeRegistry().registerType<EventBase>(makeClassTypeID("BASE"));
+#include "FilterBankEvent.h"
+const EventBase::classTypeID_t FilterBankEvent::autoRegisterFilterBankEvent=getTypeRegistry().registerType<FilterBankEvent>(makeClassTypeID("FBKE"));
+#include "SegmentedColorFilterBankEvent.h"
+const EventBase::classTypeID_t SegmentedColorFilterBankEvent::autoRegisterSegmentedColorFilterBankEvent=getTypeRegistry().registerType<SegmentedColorFilterBankEvent>(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<char>(); //genID is an enum, override to char
 	used+=getSerializedSize<char>(); //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<EventGeneratorID_t>(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<unsigned long>(sourceID));
 	xmlSetProp(node,(const xmlChar*)"sid",(const xmlChar*)buf);
+
+	snprintf(buf,20,"%lu",static_cast<long>(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 <string>
 
 //! 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
- *  <center>(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID)</center>
+ *  <center>(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID)</center>
  *  
  *  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<EventBase,classTypeID_t> 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<const unsigned int*>(str); }
+	static unsigned int makeClassTypeID(const char* str) {
+#if LOADSAVE_SWAPBYTES
+		unsigned int x;
+		byteswap(x,*reinterpret_cast<const unsigned int*>(str));
+		return x;
+#else
+		return *reinterpret_cast<const unsigned int*>(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 <algorithm>
 #include "Events/TimerEvent.h"
+#include "EventTranslator.h"
+#include "Events/RemoteRouter.h"
+#include "Events/EventProxy.h"
+
+#include <sstream>
+
+#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<ProcessID::NumProcesses; ++i) {
+		forwards[i]=NULL;
+	}
+
+}
+
+EventRouter::~EventRouter() {
+	reset();
+	removeAllTimers();
+	for(unsigned int i=0; i<ProcessID::NumProcesses; ++i) {
+		delete forwards[i];
+		forwards[i]=NULL;
+	}
+
+	//Delete all the event proxies
+	printf("Deleting %zu EventProxies and %zu RemoteRouters\n", proxies.size(), rrouters.size());
+	for (std::list<EventProxy *>::iterator pi = proxies.begin(); pi != proxies.end(); pi++)
+		delete *pi;
+	
+	//Delete the remote routers
+	for (std::map<int, RemoteRouter *>::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<EventBase::numETIDs; et++)
 		listeners.addMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
@@ -133,7 +168,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, EventBase::EventTypeID_t etid) {
+void EventRouter::addListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) {
 	bool hadListener=hasListeners(egid);
 	listeners.addMapping(el,egid,sid,etid);
 	if(!hadListener)
@@ -150,6 +185,146 @@
 		postEvent(EventBase(EventBase::erouterEGID,e.getGeneratorID(),EventBase::statusETID,0,EventBase::EventGeneratorNames[e.getGeneratorID()],1));
 }
 
+//Start of remote event code------------------
+void EventRouter::addRemoteListener(EventListener* el, int host,
+									EventBase::EventGeneratorID_t egid) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	addListener(el, egid);
+	rr.addListener(egid);
+}
+
+void EventRouter::addRemoteListener(EventListener* el, int host,
+									EventBase::EventGeneratorID_t egid, size_t sid) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	addListener(el, egid, sid);
+	rr.addListener(egid, sid);
+}
+
+void EventRouter::addRemoteListener(EventListener* el, int host, const EventBase& e){
+	addRemoteListener(el, host, e.getGeneratorID(), e.getSourceID(), e.getTypeID());
+}
+
+void EventRouter::addRemoteListener(EventListener* el, int host,
+									EventBase::EventGeneratorID_t egid, size_t sid,
+									EventBase::EventTypeID_t etid) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	addListener(el, egid, sid, etid);
+	rr.addListener(egid, sid, etid);
+}
+
+
+void EventRouter::removeRemoteListener(EventListener* el, int host,
+									   EventBase::EventGeneratorID_t egid) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	removeListener(el, egid);
+	rr.removeListener(egid);
+}
+
+void EventRouter::removeRemoteListener(EventListener* el, int host,
+									   EventBase::EventGeneratorID_t egid, size_t sid) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	removeListener(el, egid, sid);
+	rr.removeListener(egid, sid);	
+}
+    
+void EventRouter::removeRemoteListener(EventListener* el, int host,
+									   const EventBase& e) {
+	removeRemoteListener(el, host, e.getGeneratorID(), e.getSourceID(), e.getTypeID());	
+}
+
+void EventRouter::removeRemoteListener(EventListener* el, int host,
+									   EventBase::EventGeneratorID_t egid, size_t sid,
+									   EventBase::EventTypeID_t etid) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	removeListener(el, egid, sid, etid);
+	rr.removeListener(egid, sid, etid);
+}
+
+
+void EventRouter::requestRemoteStateUpdates(int host, RemoteState::StateType type,
+											unsigned int interval) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	rr.requestStateUpdates(type, interval);
+}
+
+void EventRouter::stopRemoteStateUpdates(int host, RemoteState::StateType type) {
+	RemoteRouter &rr = remoteRouterForHost(host);
+	rr.stopStateUpdates(type);
+}
+
+RemoteRouter &EventRouter::remoteRouterForHost(int host) {
+	RemoteRouter *rr = rrouters[host];
+	if (rr) {
+		printf("Returning existing remote router for host %s", intToStringIP(host).c_str());
+		return *rr;
+	} else {
+		rrouters[host] = rr = new RemoteRouter(host);
+		printf("Returning new remote router for host %s", intToStringIP(host).c_str());
+		return *rr;
+	}
+}
+
+std::string EventRouter::intToStringIP(int ip) {
+	std::stringstream ret;
+	ret << (ip >> 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; eg<EventBase::numEGIDs; eg++) {
 		EventBase::EventGeneratorID_t egid=(EventBase::EventGeneratorID_t)eg;
@@ -171,7 +346,7 @@
 	else
 		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
-void EventRouter::removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid) {
+void EventRouter::removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid) {
 	unsigned int removed=0;
 	for(unsigned int et=0; et<EventBase::numETIDs; et++)
 		removed+=listeners.removeMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
@@ -183,7 +358,7 @@
 	else
 		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
-void EventRouter::removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) {
+void EventRouter::removeListener(EventListener* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) {
 	if(!listeners.removeMapping(el,egid,sid,etid))
 		return; //nothing was removed, don't want to clean up or throw an event
 	listeners.clean(egid);
@@ -220,7 +395,7 @@
 		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 /*! Note that since timers are not broadcast, they cannot be trapped.  Only the EventListener which requested the timer will receive that timer. */
-void EventRouter::addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid) {
+void EventRouter::addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid) {
 	bool hadListener=hasListeners(egid);
 	for(unsigned int et=0; et<EventBase::numETIDs; et++)
 		trappers.addMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
@@ -230,7 +405,7 @@
 		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
 /*! Note that since timers are not broadcast, they cannot be trapped.  Only the EventListener which requested the timer will receive that timer. */
-void EventRouter::addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) {
+void EventRouter::addTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) {
 	bool hadListener=hasListeners(egid);
 	trappers.addMapping(el,egid,sid,etid);
 	if(!hadListener)
@@ -264,7 +439,7 @@
 	else
 		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
-void EventRouter::removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid) {
+void EventRouter::removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid) {
 	int removed=0;
 	for(unsigned int et=0; et<EventBase::numETIDs; et++)
 		removed+=trappers.removeMapping(el,egid,sid,(EventBase::EventTypeID_t)et);
@@ -276,7 +451,7 @@
 	else
 		postEvent(EventBase(EventBase::erouterEGID,egid,EventBase::statusETID,0,EventBase::EventGeneratorNames[egid],1));
 }
-void EventRouter::removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) {
+void EventRouter::removeTrapper(EventTrapper* el, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) {
 	if(!trappers.removeMapping(el,egid,sid,etid))
 		return; //nothing was removed, don't want to clean up or throw an event
 	trappers.clean(egid);
@@ -291,12 +466,28 @@
 		removeTrapper(el,(EventBase::EventGeneratorID_t)eg);
 }
 
+void EventRouter::setForwardingAgent(ProcessID::ProcessID_t proc, EventTranslator* trans) {
+	delete forwards[proc];
+	forwards[proc]=trans;
+}
+
 void EventRouter::processEvent(const EventBase& e) {
+	// check for forwarding *before* the lock
+	ProcessID::ProcessID_t pid=ProcessID::getID();
+	if(forwards[pid]!=NULL) {
+		if(forwards[pid]->trapEvent(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<void*>* elv=NULL;
 	if(it==filteredevents[egid][etid]->end()) { // if this is the first subscriber to the source ID
-		std::pair<const unsigned int,std::vector<void*> > p(sid,std::vector<void*>());
+		std::pair<const size_t,std::vector<void*> > p(sid,std::vector<void*>());
 		//		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; et<EventBase::numETIDs; et++) {
@@ -501,7 +692,7 @@
 	return false;
 }
 
-bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const {
+bool EventRouter::EventMapper::hasMapping(EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) const {
 	if(allevents[egid].size()>0)
 		return true;
 	const SIDtoListenerVectorMap_t* mapping=filteredevents[egid][etid];
@@ -532,7 +723,7 @@
 		ls.push_back(static_cast<T*>(*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<void*>* elv=&allevents[egid];
 	for(std::vector<void*>::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<void*>* elv=&allevents[egid];
 	for(std::vector<void*>::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<void*>* elv=&allevents[egid];
 	for(std::vector<void*>::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<EventBase::numETIDs; et++) {
 		SIDtoListenerVectorMap_t* mapping=filteredevents[egid][et];
 		if(mapping!=NULL) {
@@ -690,7 +881,7 @@
 	return false;
 }
 
-unsigned int EventRouter::numListeners(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) {
+unsigned int EventRouter::numListeners(EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) {
 	unsigned int ans=allevents[egid].size();
 	SIDtoListenerVectorMap_t* mapping=filteredevents[egid][etid];
 	if(mapping!=NULL) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Events/EventRouter.h ./Events/EventRouter.h
--- ../Tekkotsu_3.0/Events/EventRouter.h	2006-10-03 17:09:04.000000000 -0400
+++ ./Events/EventRouter.h	2007-11-12 23:16:02.000000000 -0500
@@ -2,16 +2,27 @@
 #ifndef INCLUDED_EventRouter_h
 #define INCLUDED_EventRouter_h
 
+#include <string>
 #include <vector>
 #include <queue>
 #include <map>
+#include <list>
 #include <algorithm>
 #include "EventListener.h"
 #include "EventTrapper.h"
 #include "Shared/get_time.h"
 #include "Shared/debuget.h"
 #include "Shared/attributes.h"
+#include "IPC/ProcessID.h"
 #include <iostream>
+#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 @@
  *  <h3>Event processing examples:</h3>
  *
  *  Posting events:
- *  @code
+ *  @codeEventProxy
  *  //method A: basic event posting (EventBase instance is sent)
  *  erouter->postEvent(EventBase::aiEGID, 1234, EventBase::statusETID);
  *
@@ -148,19 +169,19 @@
  *    - <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/events.shtml">David Touretzky's Events Chapter</a>
  *    - <a href="http://www.cs.cmu.edu/afs/cs/academic/class/15494-s06/www/lectures/behaviors.pdf">CMU's Cognitive Robotics course slides</a>
  */
-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<EventProxy *> proxies;
+
+	std::map<int, RemoteRouter *> 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(); //!<removes empty data structures for all event generators
 		void clean(EventBase::EventGeneratorID_t egid); //!< removes empty data structures associated with a single event generator
@@ -354,8 +432,8 @@
 			  ... if Vision sees a ball in an image, and there's no listeners, does it make an event? ;) \n
 			  @return true if it has any listeners, false otherwise */
 		bool hasMapping(EventBase::EventGeneratorID_t egid) const;
-		bool hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid) const;
-		bool hasMapping(EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const;
+		bool hasMapping(EventBase::EventGeneratorID_t egid, size_t sid) const;
+		bool hasMapping(EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) const;
 		//@}
 
 		//! builds a list of all listeners which should receive the event, templated to typecast the pointers for you
@@ -377,7 +455,7 @@
 		 *  that no other listeners have been modified - one listener could cause another
 		 *  to turn off.  If that has happened, we shouldn't send the event, even if it
 		 *  was in the queue originally. */
-		bool verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid, EventBase::EventTypeID_t etid) const;
+		bool verifyMapping(void * listener, EventBase::EventGeneratorID_t egid, size_t sid, EventBase::EventTypeID_t etid) const;
 
 		//! Needed to complete EventRouter::isListening suite
 		/*! Only checks #allevents */
@@ -388,15 +466,15 @@
 
 		//! Needed to complete EventRouter::isListening suite
 		/*! Checks both #allevents and #filteredevents, must be found in all */
-		bool verifyMappingAll(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const;
+		bool verifyMappingAll(void * listener, EventBase::EventGeneratorID_t egid, size_t sid) const;
 		//! Needed to complete EventRouter::isListening suite
 		/*! Checks both #allevents and #filteredevents, can be found in either */
-		bool verifyMappingAny(void * listener, EventBase::EventGeneratorID_t egid, unsigned int sid) const;
+		bool verifyMappingAny(void * listener, EventBase::EventGeneratorID_t egid, size_t sid) const;
 
 	protected:
-		//! a mapping from source IDs (unsigned ints), each to a vector of pointers to listeners
+		//! a mapping from source IDs (size_t's), each to a vector of pointers to listeners
 		/*! main use in filteredevents @see filteredevents */
-		typedef std::map<unsigned int,std::vector<void*>,std::less<unsigned int> > SIDtoListenerVectorMap_t;
+		typedef std::map<size_t,std::vector<void*>,std::less<size_t> > SIDtoListenerVectorMap_t;
 		
 		//! an array of vectors of pointers to listeners... in other words, a vector of listener pointers for each generator
 		std::vector<void*> allevents[EventBase::numEGIDs];
@@ -431,6 +509,22 @@
 		const EventBase& e; //!< the event being processed
 	};
 	std::queue<PostingStatus*> 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<EventBase*>((*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 <map>
 
 //! 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<class EB>
-	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<EB>;
-		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<unsigned int,FactoryBase*> 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<EventBase>::Factory<FilterBankEvent>;
 };
 
 /*! @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 <sstream>
 #include <libxml/tree.h>
-
 #include <iostream>
+
 using namespace std;
 
+const EventBase::classTypeID_t LocomotionEvent::autoRegisterLocomotionEvent=getTypeRegistry().registerType<LocomotionEvent>(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<LookoutPointAtEvent>(makeClassTypeID("LOLA"));
+const EventBase::classTypeID_t LookoutSketchEvent::autoRegisterLookoutSketchEvent=getTypeRegistry().registerType<LookoutSketchEvent>(makeClassTypeID("LSKC"));
+const EventBase::classTypeID_t LookoutIREvent::autoRegisterLookoutIREvent=getTypeRegistry().registerType<LookoutIREvent>(makeClassTypeID("LOIR"));
+const EventBase::classTypeID_t LookoutScanEvent::autoRegisterLookoutScanEvent=getTypeRegistry().registerType<LookoutScanEvent>(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<DualCoding::uchar> *img; // pointer to sketch existing inside lookout's requests queue
+  DualCoding::Sketch<DualCoding::uchar> img; // sketch returned by the Lookout
   
 public:
   virtual LookoutEventType_t getLookoutEventType() const { return sketch; }
-  LookoutSketchEvent(DualCoding::Sketch<DualCoding::uchar>& _img, const NEWMAT::Matrix& mat)
-    : LookoutPointAtEvent(mat), img(&_img) {}
-  LookoutSketchEvent(DualCoding::Sketch<DualCoding::uchar>& _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<DualCoding::uchar>& _img, const NEWMAT::Matrix& mat, 
-		     EventGeneratorID_t gid, unsigned int sid, 
+  LookoutSketchEvent() : LookoutPointAtEvent(), img() {}
+  LookoutSketchEvent(bool _success, DualCoding::Sketch<DualCoding::uchar>& _img, const NEWMAT::Matrix& mat)
+    : LookoutPointAtEvent(_success,mat), img(_img) {}
+  LookoutSketchEvent(bool _success, DualCoding::Sketch<DualCoding::uchar>& _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<DualCoding::uchar>& _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<DualCoding::uchar>& getSketch() const { return *img; }
+  const DualCoding::Sketch<DualCoding::uchar>& 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<ScanRequest::Task*> *tasks;
+  std::vector<DualCoding::LookoutScanRequest::Task*> *tasks;
 public:
   virtual LookoutEventType_t getLookoutEventType() const { return scan; }
-  LookoutScanEvent(vector<ScanRequest::Task*>& _tasks) : LookoutEvent(), tasks(&_tasks) {}
-  LookoutScanEvent(vector<ScanRequest::Task*>& _tasks, EventGeneratorID_t gid, 
-		   unsigned int sid, EventTypeID_t tid, unsigned int dur=0) 
-    : LookoutEvent(gid,sid,tid,dur), tasks(&_tasks) {}
-  LookoutScanEvent(vector<ScanRequest::Task*>& _tasks, EventGeneratorID_t gid, unsigned int sid, 
+  LookoutScanEvent() : LookoutEvent(), tasks() {}
+  LookoutScanEvent(std::vector<DualCoding::LookoutScanRequest::Task*>& _tasks) : LookoutEvent(), tasks(&_tasks) {}
+  LookoutScanEvent(std::vector<DualCoding::LookoutScanRequest::Task*>& _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<DualCoding::LookoutScanRequest::Task*>& _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<ScanRequest::Task*>& getTasks() const { return *tasks; }
+  const std::vector<DualCoding::LookoutScanRequest::Task*>& 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 <class T> 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<int>(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 <sstream>
 #include <libxml/tree.h>
 
-//better to put this here instead of the header
 using namespace std; 
 
+const EventBase::classTypeID_t PitchEvent::autoRegisterPitchEvent=getTypeRegistry().registerType<PitchEvent>(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 <vector>
+#include <string>
+
+
+/*! 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<char> 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<char> &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 <string>
+#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 <vector>
+#include <list>
+
+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<RemoteRequest> 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<char>& 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<const char*, unsigned int, __gnu_cxx::hash<const char*>, 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<EventBase>::Factory<SegmentedColorFilterBankEvent>;
 };
 
 /*! @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 <sstream>
 #include <libxml/tree.h>
 
+const EventBase::classTypeID_t TextMsgEvent::autoRegisterTextMsgEvent=getTypeRegistry().registerType<TextMsgEvent>(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 <sstream>
 #include <libxml/tree.h>
 
-//better to put this here instead of the header
 using namespace std; 
 
+const EventBase::classTypeID_t TimerEvent::autoRegisterTimerEvent=getTypeRegistry().registerType<TimerEvent>(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 <sstream>
 #include <libxml/tree.h>
 
-// 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<VisionObjectEvent>(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; } //!<returns true if no objects are in use
 
-	inline T& operator[](unsigned int x) { return *reinterpret_cast<T*>(entries[x].data); } //!<allows direct access to elements - be careful, can access 'free' elements this way
-	inline const T& operator[](unsigned int x) const { return *reinterpret_cast<const T*>(entries[x].data); } //!<allows direct access to elements - be careful, can access 'free' elements this way
+	// the funny '(T*)(void*)foo' double-casts below are to avoid gcc warnings
+	// regarding 'dereferencing type-punned pointer will break strict-aliasing rules'
+	
+	inline T& operator[](unsigned int x) { return *(T*)(void*)(entries[x].data); } //!<allows direct access to elements - be careful, can access 'free' elements this way
+	inline const T& operator[](unsigned int x) const { return *(const T*)(const void*)(entries[x].data); } //!<allows direct access to elements - be careful, can access 'free' elements this way
 
 	inline index_t begin() const { return activeBegin; } //!<returns index of first used entry
-	T& front() { return *reinterpret_cast<T*>(entries[activeBegin].data); } //!< returns reference to first used entry
-	const T& front() const { return *reinterpret_cast<const T*>(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; } //!<returns the one-past-end index
-	T& back() { return *reinterpret_cast<T*>(entries[activeBack].data); } //!<returns reference to last used entry
-	const T& back() const { return *reinterpret_cast<const T*>(entries[activeBack].data); } //!<returns const reference to last used entry
+	T& back() { return *(T*)(void*)(entries[activeBack].data); } //!<returns reference to last used entry
+	const T& back() const { return *(const T*)(const void*)(entries[activeBack].data); } //!<returns const reference to last used entry
 
 	index_t new_front(); //!<pushes a 'blank' entry on the front of the used list
 	index_t push_front(const T& data) { index_t tmp=new_front(); if(tmp!=end()) operator[](tmp)=data; return tmp; } //!<pushes an entry on the front of the used chain and assigns @a data to it
@@ -83,7 +86,7 @@
 		index_t next; //!<The next element in the used or free chain
 		index_t prev; //!<The previous element in the used chain, invalid if in the free chain
 	};
-	entry_t entries[MAX_ENTRIES]; //!<the main block of data
+	entry_t entries[MAX_ENTRIES==0?1:MAX_ENTRIES]; //!<the main block of data; must have at least 1 element due to limitation of older compilers
 	index_t activeBegin; //!<beginning of used chain
 	index_t activeBack; //!<end of used chain
 	index_t freeBegin; //!<beginning of free chain
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/MessageQueue.h ./IPC/MessageQueue.h
--- ../Tekkotsu_3.0/IPC/MessageQueue.h	2006-09-19 18:52:01.000000000 -0400
+++ ./IPC/MessageQueue.h	2007-11-10 17:58:08.000000000 -0500
@@ -8,12 +8,13 @@
 
 #include "ListMemBuf.h"
 #include "RCRegion.h"
+#include "SemaphoreManager.h"
+#include "MutexLock.h"
 #include "Shared/MarkScope.h"
 #include "Shared/attributes.h"
 #include <exception>
 
 #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<StatusListener*>::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 <typeinfo>
 
 #ifndef PLATFORM_APERIOS
-#  include <unistd.h>
 #  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 <unistd.h>
+#  include <pthread.h>
 #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<unsigned int num_doors>
+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<unsigned>(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<unsigned>(id)) {
+		if(owner_index!=static_cast<unsigned>(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()<delay) {
 		sleepSpec=delay-startTime.Age();
@@ -56,6 +42,7 @@
 				perror("PollThread::run(): initial nanosleep");
 				break;
 			}
+			testCancel();
 			//interrupted() may have changed delay to indicate remaining sleep time
 			if(delay<1L || delay<startTime.Age())
 				break;
@@ -101,6 +88,7 @@
 					perror("PollThread::run(): periodic nanosleep");
 					break;
 				}
+				testCancel();
 				//interrupted() should have changed delay and/or period to indicate remaining sleep time
 				if(delay<1L || delay<startTime.Age())
 					break;
@@ -122,19 +110,6 @@
 	//signal(SIGALRM,SIG_DFL);
 //}
 
-void PollThread::handleInterrupt(int /*signal*/) {
-	if(signal(SIGALRM,SIG_DFL)==SIG_ERR)
-		perror("PollThread::handleInterrupt(): could not re-enable signal");
-	PollThread * cur=dynamic_cast<PollThread*>(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 <sys/stat.h>
 #include <errno.h>
 
-#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; i<ProcessID::NumProcesses+1; i++)
-			cerr << ' ' << references[i];
-		cerr << endl;
-		return;
-	}
-	bool wasLastProcRef=(--references[ProcessID::getID()] == 0);
-	bool wasLastAnyRef=(--references[ProcessID::NumProcesses] == 0);
-	ASSERT(wasLastProcRef || !wasLastAnyRef,"global reference decremented beyond process reference");
-	//if(MutexLockBase::getSemaphoreManager()!=NULL)
-	/*if(isFaultShutdown) {
-		cerr << "Process " << ProcessID::getID() << " dereferenced " << id.key << ".  Counts are now:";
-		for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
-			cerr << ' ' << references[i];
-		cerr << endl;
-	}*/
 	ThreadNS::Lock * old=NULL;
-	if(!wasLastProcRef) {
-		lock->unlock();
-	} else {
+	{
 		MarkScope l(getStaticLock());
-		//cout << " detach";
-		if(wasLastAnyRef)
-			lock->~MutexLock<ProcessID::NumProcesses>();
-		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<ProcessID::NumProcesses+1; i++)
+				cerr << ' ' << references[i];
+			cerr << endl;
+			return;
 		}
+		bool wasLastProcRef=(--references[ProcessID::getID()] == 0);
+		bool wasLastAnyRef=(--references[ProcessID::NumProcesses] == 0);
+		ASSERT(wasLastProcRef || !wasLastAnyRef,"global reference decremented beyond process reference");
+#if TEKKOTSU_SHM_STYLE==NO_SHM
+		wasLastProcRef=wasLastAnyRef;
+#else
+		if(!multiprocess)
+			wasLastProcRef=wasLastAnyRef;
+#endif
+		/*if(isFaultShutdown) {
+			cerr << "Process " << ProcessID::getID() << " dereferenced " << id.key << ".  Counts are now:";
+			for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
+				cerr << ' ' << references[i];
+			cerr << endl;
+		}*/
+		if(wasLastProcRef) {
+			//cout << " detach";
+#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");
+			}
 #elif TEKKOTSU_SHM_STYLE==POSIX_SHM
-		if(munmap(base,calcRealSize(id.size))<0) {
-			perror("Warning: Shared memory unmap (munmap)");
-		}
-		base=NULL;
-		references=NULL;
-		if(wasLastAnyRef) {
-			//cout << " delete" << endl;
-			if(!unlinkRegion()) {
-				int err=errno;
-				if(isFaultShutdown && (err==EINVAL || err==ENOENT))
-					//On a fault shutdown, we initially try to unlink everything right away,
-					// so an error now is just confirmation that it worked
-					cerr << "Region " << id.key << " appears to have been successfully unlinked" << endl;
-				else {
-					cerr << "Warning: Shared memory unlink of region " << id.key << " returned " << strerror(err);
-					if(err==EINVAL || err==ENOENT)
-						cerr << "\n         May have already been unlinked by a dying process.";
-					cerr << endl;
-				}
-			} else if(isFaultShutdown)
-				//That shouldn't have succeeded on a faultShutdown...
-				cerr << "Region " << id.key << " appears to have been successfully unlinked (nonstandard)" << endl;
-		}
+			if(munmap(base,calcRealSize(id.size))<0) {
+				perror("Warning: Shared memory unmap (munmap)");
+			}
+			base=NULL;
+			references=NULL;
+			if(wasLastAnyRef) {
+				//cout << " delete" << endl;
+				if(!unlinkRegion()) {
+					int err=errno;
+					if(isFaultShutdown && (err==EINVAL || err==ENOENT))
+						//On a fault shutdown, we initially try to unlink everything right away,
+						// so an error now is just confirmation that it worked
+						cerr << "Region " << id.key << " appears to have been successfully unlinked" << endl;
+					else {
+						cerr << "Warning: Shared memory unlink of region " << id.key << " returned " << strerror(err);
+						if(err==EINVAL || err==ENOENT)
+							cerr << "\n         May have already been unlinked by a dying process.";
+						cerr << endl;
+					}
+				} else if(isFaultShutdown)
+					//That shouldn't have succeeded on a faultShutdown...
+					cerr << "Region " << id.key << " appears to have been successfully unlinked (nonstandard)" << endl;
+			}
+#elif TEKKOTSU_SHM_STYLE==NO_SHM
+			delete base;
+			base=NULL;
+			references=NULL;
 #else
 #  error "Unknown TEKKOTSU_SHM_STYLE setting"
 #endif
-		delete this;
-		if(attachedRegions.size()==0 && !isFaultShutdown) {
-			//was last attached region, clean up lock for good measure
-			old=staticLock;
-			staticLock=NULL;
+			delete this;
+			if(attachedRegions.size()==0 && !isFaultShutdown) {
+				//was last attached region, clean up lock for good measure
+				old=staticLock;
+				staticLock=NULL;
+			}
 		}
 	}
 	delete old;
@@ -161,7 +167,7 @@
 }
 
 void RCRegion::AddSharedReference() {
-	AutoLock autolock(*lock);
+	MarkScope l(getStaticLock());
 	//cout << "AddSharedReference " << id.shmid << ' ' << ProcessID::getID();
 	references[ProcessID::NumProcesses]++;
 	//cout << " counts are now:";
@@ -171,7 +177,7 @@
 }
 
 void RCRegion::RemoveSharedReference() {
-	AutoLock autolock(*lock);
+	MarkScope l(getStaticLock());
 	//cout << "RemoveSharedReference " << id.shmid << ' ' << ProcessID::getID();
 	if(references[ProcessID::NumProcesses]==0) {
 		cerr << "Warning: RCRegion shared reference count underflow on " << id.key << " by " << ProcessID::getID() << "!  ";
@@ -287,14 +293,14 @@
 
 ThreadNS::Lock& RCRegion::getStaticLock() {
 	if(staticLock==NULL)
-		staticLock=new ThreadNS::Lock();
+		staticLock=new ThreadNS::Lock;
 	return *staticLock;
 }
 
 #if TEKKOTSU_SHM_STYLE==SYSV_SHM
 
 void RCRegion::init(size_t sz, key_t sug_key, bool create) {
-	ThreadNS::Lock l(getStaticLock());
+	MarkScope l(getStaticLock());
 	id.size=sz;
 	sz=calcRealSize(sz);
 	if(create) {
@@ -362,11 +368,8 @@
 			perror("Region delete");
 		exit(EXIT_FAILURE);
 	}
-	lock=reinterpret_cast<MutexLock<ProcessID::NumProcesses>*>(base+sz-sizeof(MutexLock<ProcessID::NumProcesses>));
 	references=reinterpret_cast<unsigned int*>(base+sz-extra);
 	if(create) {
-		new (lock) MutexLock<ProcessID::NumProcesses>;
-		AutoLock autolock(*lock,ProcessID::getID());
 		for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
 			references[i]=0;
 	}
@@ -520,11 +523,8 @@
 	if(close(fd)<0) {
 		perror("Warning: Closing temporary file descriptor from shm_open");
 	}
-	lock=reinterpret_cast<MutexLock<ProcessID::NumProcesses>*>(base+sz-sizeof(MutexLock<ProcessID::NumProcesses>));
 	references=reinterpret_cast<unsigned int*>(base+sz-extra);
 	if(create) {
-		new (lock) MutexLock<ProcessID::NumProcesses>;
-		AutoLock autolock(*lock);
 		for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
 			references[i]=0;
 	}
@@ -532,6 +532,78 @@
 	attachedRegions[id.key]=this;
 }
 
+#elif TEKKOTSU_SHM_STYLE==NO_SHM
+
+void RCRegion::init(size_t sz, const std::string& name, bool create) {
+	MarkScope l(getStaticLock());
+	id.size=sz; //size of requested region
+	sz=calcRealSize(sz); //add some additional space for region lock and reference counts
+	if(name.size()>=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<unsigned int*>(base+sz-extra);
+	if(create) {
+		for(unsigned int i=0; i<ProcessID::NumProcesses+1; i++)
+			references[i]=0;
+	}
+	AddReference();
+	attachedRegions[id.key]=this;
+}
+
+
 #else
 #  error "Unknown TEKKOTSU_SHM_STYLE setting"
 #endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/RCRegion.h ./IPC/RCRegion.h
--- ../Tekkotsu_3.0/IPC/RCRegion.h	2006-08-23 15:24:20.000000000 -0400
+++ ./IPC/RCRegion.h	2007-11-13 11:17:46.000000000 -0500
@@ -6,27 +6,49 @@
 #  define INCLUDED_RCRegion_h_
 
 #include "Shared/ReferenceCounter.h"
-#include "MutexLock.h"
 #include "ProcessID.h"
 #include "Shared/plist.h"
 #include <sys/types.h>
 #include <map>
 #include <exception>
 
-//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<std::string> shmRoot; //!< determines location of the file backing within file system
-#  endif
+#    endif
 	static plist::Primitive<bool> 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<unsigned int>(++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<key_t,RCRegion*> 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<std::string,RCRegion*> 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<ProcessID::NumProcesses>& 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<ProcessID::NumProcesses>);
+	//! 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<ProcessID::NumProcesses> * 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<unsigned int MAX_REGIONS, unsigned int NAME_LEN=0>
+template<unsigned int MAX_REGIONS, unsigned int NAME_LEN>
 class RegionRegistry {
 protected:
+	//! makes sure we only have one registration in progress at a time
 	mutable MutexLock<ProcessID::NumProcesses> 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<entry,MAX_REGIONS> registry_t;
-	registry_t avail;
+	typedef ListMemBuf<entry,MAX_REGIONS> 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("<<name<<") is too long, max is " << NAME_LEN << std::endl;
 		for(index_t it=begin(); it!=end(); it=next(it))
@@ -54,8 +58,10 @@
 		return avail.end();
 	}
 
+	//! Registers a region, returns the index of the region if successful, or end() if out of space or conflicting registration is found.
+	/*! You can re-register the same region under the same name, it simply returns the same index again. */
 	index_t registerRegion(const std::string& name, const RCRegion * region) {
-		AutoLock autolock(lock,ProcessID::getID());
+		MarkScope autolock(lock,ProcessID::getID());
 		index_t it=findRegion(name);
 		if(it!=end()) { //found, already registered
 			if(avail[it].regions[ProcessID::getID()]==region)
@@ -66,8 +72,10 @@
 		return avail.push_back(entry(name.c_str(),region));
 	}
 	
+	//! Creates and registers a new region of the specified size Ñ if the region is already registered, the previous one is returned.
+	/*! No checking is done on the size of the region... if it was already registered as a different size, that is ignored. */
 	RCRegion * registerRegion(const std::string& name, size_t size) {
-		AutoLock autolock(lock);
+		MarkScope autolock(lock);
 		index_t it=findRegion(name);
 		if(it!=end()) {
 			//found, already registered
@@ -80,25 +88,27 @@
 		}
 	}
 	
+	//! Access a region by index
 	RCRegion * operator[](index_t it) const {
-		AutoLock autolock(lock,ProcessID::getID());
+		MarkScope autolock(lock,ProcessID::getID());
 		if(it==end())
 			return NULL;
 		return RCRegion::attach(avail[it].id);
 	}
 	
+	//! Erases the registration, but doesn't dereference the region (the registry doesn't claim references on the regions...)
 	void erase(index_t it) {
-		AutoLock autolock(lock,ProcessID::getID());
+		MarkScope autolock(lock,ProcessID::getID());
 		avail.erase(it);
 	}
 	
-	index_t begin() const { return avail.begin(); }
-	index_t next(index_t it) const { return avail.next(it); }
-	index_t end() const { return avail.end(); }
+	index_t begin() const { return avail.begin(); } //!< provides iteration through the entries, be sure to use next(), the index_t is not a 'proper' iterator (no ++ to increment)
+	index_t next(index_t it) const { return avail.next(it); } //!< provides the index of the next entry
+	index_t end() const { return avail.end(); } //!< one-past-end marker
 };
 
 /*! @file
- * @brief 
+ * @brief Defines RegionRegistry, which keeps track of currently available shared memory regions
  * @author ejt (Creator)
  *
  * $Author: ejt $
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/IPC/SemaphoreManager.cc ./IPC/SemaphoreManager.cc
--- ../Tekkotsu_3.0/IPC/SemaphoreManager.cc	2006-08-11 14:44:16.000000000 -0400
+++ ./IPC/SemaphoreManager.cc	2007-11-10 17:58:08.000000000 -0500
@@ -8,17 +8,22 @@
 #include <exception>
 #include <stdexcept>
 #include <iostream>
+#include <sys/types.h>
+#include <sys/sem.h>
 
-//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 <sys/sem.h> */
+#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 <sys/types.h>
-#include <sys/sem.h>
 
 #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 <signal.h>
 #include <unistd.h>
 #include <cassert>
+#include <errno.h>
+#ifdef __APPLE__
+#	include <AvailabilityMacros.h>
+#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("<<pt->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("<<sig<<"): " << strerror(err) << endl;
+		cerr << "Thread sendSignal(), pthread_kill("<<sig<<"): " << strerror(err) << endl;
 }
 
 void * Thread::join() {
@@ -162,6 +202,7 @@
 	++(cur->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<Thread*>(th)->cancelled();
-			static_cast<Thread*>(th)->running=false;
+			static_cast<Thread*>(th)->started=static_cast<Thread*>(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<Thread*>(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 <stddef.h>
 
+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.
+
+    <one line to give the library's name and a brief idea of what it does.>
+    Copyright (C) <year>  <name of author>
+
+    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.
+
+  <signature of Ty Coon>, 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; i<NumPIDJoints; i++)
 		piddutyavgs[i]=0;
-	if(state->robotDesign&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<<red),period,1,0,period/2);
+		ledengine.cycle((1<<blue),period,1);
+	} else if(RobotName == ERS220Info::TargetName) {
+		int tl=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::TailLeftLEDOffset]) - LEDOffset;
+		int tc=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::TailCenterLEDOffset]) - LEDOffset;
+		int tr=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::TailRightLEDOffset]) - LEDOffset;
+		int bl1=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackLeft1LEDOffset]) - LEDOffset;
+		int bl2=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackLeft2LEDOffset]) - LEDOffset;
+		int bl3=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackLeft3LEDOffset]) - LEDOffset;
+		int br1=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackRight1LEDOffset]) - LEDOffset;
+		int br2=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackRight2LEDOffset]) - LEDOffset;
+		int br3=capabilities.getOutputOffset(ERS220Info::outputNames[ERS220Info::BackRight3LEDOffset]) - LEDOffset;
+		ledengine.cycle((1<<tc), period, 2.0f, -.5f, (int)(period * 0/5.5));
+		ledengine.cycle((1<<tl)|(1<<tr),   period, 2.0f, -.5f, (int)(period * 1/5.5));
+		ledengine.cycle((1<<bl3)|(1<<br1), period, 2.0f, -.5f, (int)(period * 2/5.5));
+		ledengine.cycle((1<<bl2)|(1<<br2), period, 2.0f, -.5f, (int)(period * 3/5.5));
+		ledengine.cycle((1<<bl1)|(1<<br3), period, 2.0f, -.5f, (int)(period * 4/5.5));
+	} else if(RobotName == ERS7Info::TargetName) {
+		int mb=capabilities.getOutputOffset(ERS7Info::outputNames[ERS7Info::MdBackColorLEDOffset]) - LEDOffset;
+		ledengine.cycle((1<<mb),2*period/3,.15,.15/2-.5,0);
 	} else {
-		serr->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; i<LEDOffset+NumLEDs; i++)
 				motman->setOutput(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<float>(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=(curt<timeoflastrelease);
@@ -146,12 +170,12 @@
 				freezeJoints();
 				if(sound)
 					sndman->playFile(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; i<NumPIDJoints; i++)
 		piddutyavgs[i]=0; //or: state->pidduties[i];
+#ifdef TGT_HAS_WHEELS
+	//Wheels need to be set to 0 in e-stop mode
+	for(unsigned int i=WheelOffset; i<WheelOffset+NumWheels; i++) {
+	  cmds[i].value = 0.0;
+	  curPositions[i] = 0;
+	}
+#endif
+#ifndef TGT_HAS_LEDS
+	// no LEDs, just go all the way through in one pass...
+	for(unsigned int i=0; i<NumOutputs; i++)
+		cmds[i].weight=1;
+#else
 	for(unsigned int i=0; i<LEDOffset; i++)
 		cmds[i].weight=1;
 	for(unsigned int i=LEDOffset; i<LEDOffset+NumLEDs; i++)
 		cmds[i].unset(); // let other commands' LEDs "show through"
 	for(unsigned int i=LEDOffset+NumLEDs; i<NumOutputs; i++)
 		cmds[i].weight=1;
-	if(state->robotDesign&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 <math.h>
-
 #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 <math.h>
 
 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; i<NumHeadJoints; i++)
 		headTargets[i]=headCmds[i].value;
 	dirty=false;
+#endif
 }
 
 void HeadPointerMC::takeSnapshot() {
+#ifdef TGT_HAS_HEAD
 	for(unsigned int i=0; i<NumHeadJoints; i++)
 		headTargets[i]=headCmds[i].value=state->outputs[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; x<NumHeadJoints; x++)
 		headCmds[x].weight=w;
 	markDirty();
+#endif
 }
 
-void HeadPointerMC::setJoints(float j1, float j2, float j3) {
-	headTargets[TiltOffset]=clipAngularRange(HeadOffset+TiltOffset,j1);
-	headTargets[PanOffset]=clipAngularRange(HeadOffset+PanOffset,j2);
-	headTargets[RollOffset]=clipAngularRange(HeadOffset+RollOffset,j3);
+void HeadPointerMC::setJoints(float tilt1, float pan, float tilt2) {
+#ifdef TGT_HAS_HEAD
+#ifdef TGT_IS_AIBO
+	headTargets[TiltOffset]=clipAngularRange(HeadOffset+TiltOffset,tilt1);
+	headTargets[PanOffset]=clipAngularRange(HeadOffset+PanOffset,pan);
+	headTargets[NodOffset]=clipAngularRange(HeadOffset+NodOffset,tilt2);
+#else
+	const char* n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::TiltOffset];
+	unsigned int i = capabilities.findOutputOffset(n);
+	if(i!=-1U)
+		headTargets[i-HeadOffset]=clipAngularRange(i,tilt1);
+	n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::PanOffset];
+	i = capabilities.findOutputOffset(n);
+	if(i!=-1U)
+		headTargets[i-HeadOffset]=clipAngularRange(i,pan);
+	n = ERS7Info::outputNames[ERS7Info::HeadOffset+ERS7Info::NodOffset];
+	i = capabilities.findOutputOffset(n);
+	if(i!=-1U)
+		headTargets[i-HeadOffset]=clipAngularRange(i,tilt2);
+#endif
 	markDirty();
+#endif
 }
 
 bool HeadPointerMC::lookAtPoint(float x, float y, float z) {
+#ifndef TGT_HAS_HEAD
+	return false;
+#else
 	NEWMAT::ColumnVector Pobj(4),Plink(4);
 	Pobj(1)=x; Pobj(2)=y; Pobj(3)=z; Pobj(4)=1;
 	Plink=0; Plink(3)=1;
@@ -80,9 +122,13 @@
 	//	float theta2 = acos(poE2(3)/sqrt(poE2(1)*poE2(1)+poE2(2)*poE2(2)+poE2(3)*poE2(3)));
 	//	cout << " theta2: " << mathutils::rad2deg(theta2) << " degrees\n";
 	return isReachable(Pobj);
+#endif
 }
 	
 bool HeadPointerMC::lookAtPoint(float x, float y, float z, float d) {
+#ifndef TGT_HAS_HEAD
+	return false;
+#else
 	NEWMAT::ColumnVector Pobj(4),Plink(4);
 	Pobj(1)=x; Pobj(2)=y; Pobj(3)=z; Pobj(4)=1;
 	Plink=0; Plink(3)=d; Plink(4)=1;
@@ -92,9 +138,13 @@
 		setJointValue(i,headkin.get_q(2+i));
 	//	return conv;
 	return isReachable(Pobj);
+#endif
 }
 	
 bool HeadPointerMC::lookInDirection(float x, float y, float z) {
+#ifndef TGT_HAS_HEAD
+	return false;
+#else
 	NEWMAT::ColumnVector Pobj(4),Plink(4);
 	Pobj(1)=x; Pobj(2)=y; Pobj(3)=z; Pobj(4)=0;
 	Plink=0; Plink(3)=1;
@@ -104,6 +154,7 @@
 		setJointValue(i,headkin.get_q(2+i));
 	//	return conv;
 	return isReachable(Pobj);
+#endif
 }
 
 
@@ -111,6 +162,7 @@
 	int tmp=isDirty();
 	if(tmp || hold) {
 		dirty=false;
+#ifdef TGT_HAS_HEAD
 		for(unsigned int i=0; i<NumHeadJoints; i++) {
 			if(maxSpeed[i]<=0) {
 				headCmds[i].value=headTargets[i];
@@ -135,6 +187,7 @@
 					dirty=true;
 			}
 		}
+#endif
 		if(!dirty && !targetReached) {
 			postEvent(EventBase(EventBase::motmanEGID,getID(),EventBase::statusETID));
 			targetReached=true;
@@ -145,6 +198,9 @@
 }
 
 int HeadPointerMC::isAlive() {
+#ifndef TGT_HAS_HEAD
+	return false;
+#else
 	if(dirty || !targetReached)
 		return true;
 	if(targetReached && (!hold || get_time()-targetTimestamp>timeout)) { //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; i<NumHeadJoints; i++)
 		headCmds[i].value=motman->getOutputCmd(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<NumHeadJoints)
 		return true;
 	if(i>=HeadOffset && i<HeadOffset+NumHeadJoints) {
@@ -182,6 +244,7 @@
 	serr->printf("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 <cmath>
+
+//! 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.
+ *  <table cellspacing=0 cellpadding=0 width="434" class="figures" align="center" border="0"><tr>
+ *  <td class="figure"><img src="MotionModel.png"><div style="padding:10px;">
+ *  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.
+ *  </div></td></tr></table>
+ *  
+ *  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<typename ParticleT>
+class HolonomicMotionModel : public ParticleFilter<ParticleT>::MotionModel {
+public:
+	typedef typename ParticleFilter<ParticleT>::MotionModel::particle_collection particle_collection;
+	
+	//! constructor, with default noise parameters (xvar=yvar=50, avar=0.15f)
+	HolonomicMotionModel()
+		: ParticleFilter<ParticleT>::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<ParticleT>::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("<<xv<<','<<yv<<','<<av<<','<<curtime<<')'<<std::endl;
+		// first update current position
+		float dt = (curtime - prevtime)/1000.f;
+		computeHolonomicMotion(xvel,yvel,avel,dt, posx,posy,posa);
+		// now store specified velocity
+		xvel = xv; // forward velocity
+		yvel = yv; // sideways speed
+		avel = av; // turning speed
+		prevtime = curtime;  // time of last event
+
+		//cout << "Posx: " << posx << " Posy: " << posy << " Posangle: " << posa << endl;
+		//cout << "PrevX: " << xvel << endl;
+		//cout << "PrevY: " << yvel << endl;
+		//cout << "PrevTime: " << prevtime << endl;
+	}
+	
+	//! allows you to change the variance parameters (#xvar, #yvar, #avar)
+	void setVariance(float xv, float yv, float av) {
+		xvar=xv; yvar=yv; avar=av;
+	}
+	//! allows you to change the cross-variance parameters (#crossAxis, #crossAngle)
+	void setCrossVariance(float axis, float angle) {
+		crossAxis=axis;
+		crossAngle=angle;
+	}
+	
+	float getXVariance() const { return xvar; } //!< accessor for #xvar
+	float getYVariance() const { return yvar; } //!< accessor for #yvar
+	float getAVariance() const { return avar; } //!< accessor for #avar
+	float getAxisCrossVariance() const { return crossAxis; } //!< accessor for crossAxis
+	float getAngleCrossVariance() const { return crossAngle; } //!< accessor for crossAngle
+
+protected:
+	float xvel; //!< current x velocity
+	float yvel; //!< current y velocity
+	float avel; //!< current angular velocity
+	unsigned int prevtime; //!< time (in milliseconds) that the position was last set
+	
+	float posx; //!< x position at which #prevtime was set
+	float posy; //!< y position at which #prevtime was set
+	float posa; //!< orientation at which #prevtime was set
+	
+	float xvar; //!< variance of x velocities as ratio of x speed, used when updating particle list (updateMotion())
+	float yvar; //!< variance of y velocities as ratio of y speed, used when updating particle list (updateMotion())
+	float avar; //!< variance of angular velocities as ratio of angular speed, used when updating particle list (updateMotion())
+	float crossAxis; //!< cross variance of x speed on y speed and vice versa
+	float crossAngle; //!< cross variance of x,y speed on angular speed
+};
+
+/*! @file
+ * @brief Defines HolonomicMotionModel, which can model the path of a holonomic robot
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.5 $
+ * $State: Exp $
+ * $Date: 2007/11/10 22:58:09 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/Kinematics.cc ./Motion/Kinematics.cc
--- ../Tekkotsu_3.0/Motion/Kinematics.cc	2006-09-09 00:32:53.000000000 -0400
+++ ./Motion/Kinematics.cc	2007-09-26 19:12:05.000000000 -0400
@@ -64,6 +64,7 @@
 				roconfig->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<const string,InterestPoint,hashstring> InterestPointMap;
+	typedef __gnu_cxx::hash_map<const std::string,InterestPoint,hashstring> 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<NumLEDs; i++)
 		if((mask>>i)&1)
 			for(unsigned int f=0; f<NumFrames; f++)
 				motman->setOutput(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; i<NumLEDs; i++)
       if(cmds[i][0].weight!=0)
 				motman->setOutput(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<NumLEDs; i++)
       if((leds>>i)&1)
 	for(unsigned int f=0; f<NumFrames; f++)
 	  cmds[i][f].weight=weight;
+#endif
   }
 
 protected:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/MotionCommand.cc ./Motion/MotionCommand.cc
--- ../Tekkotsu_3.0/Motion/MotionCommand.cc	2006-09-11 19:05:11.000000000 -0400
+++ ./Motion/MotionCommand.cc	2007-11-15 16:31:18.000000000 -0500
@@ -1,4 +1,5 @@
 #include "MotionCommand.h"
+#include "MotionManager.h"
 #include "Events/EventTranslator.h"
 #include "Events/EventRouter.h"
 #include <iostream>
@@ -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 <list>
 
 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; i<numAcc; i++) {
@@ -107,13 +104,13 @@
 #ifdef PLATFORM_APERIOS
 			int refs=1;
 #else
-			int refs=cmdlist[mc_id].rcr[_MMaccID]->NumberOfLocalReference();
+			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; i<refs; ++i)
-				cmdlist[mc_id].rcr[_MMaccID]->RemoveReference();
-			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<numAcc; i++)
 				if(cmdlist[mc_id].rcr[i]!=NULL)
-					cout << "MC " << mc_id << " was still referenced by InitAccess caller #" << _MMaccID << endl;
+					cout << "MC " << mc_id << " was still referenced by InitAccess caller #" << getAccID() << endl;
 			push_free(mc_id);
 		}
 		func_end();
@@ -194,7 +191,7 @@
 	if(output >= 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; frame<NumFrames; frame++)
+	for(uint frame=0; frame<NumFrames; frame++) {
 		for(uint output=0; output<NumOutputs; output++) {
 			cmdstatelist_t& curstatelist=cmdstates[output];
 			float alpha=1;
 			OutputCmd sumcmd;
+			/*if(curstatelist.size()>1) {
+				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; output<NumOutputs; output++)
 		cmdSums[output]=outputs[NumFrames-1][output];
+
+	for (uint frame_idx = 0; frame_idx < NumFrames; frame_idx++) {
+		for(uint output=PIDJointOffset; output<PIDJointOffset+NumPIDJoints; output++)
+			outputs[frame_idx][output] = (outputs[frame_idx][output] + config->motion.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; output<PIDJointOffset+NumPIDJoints; output++) {
@@ -509,33 +523,6 @@
 	//if(state && state->buttons[LFrPawOffset]) cout << "getAngles-done." << flush;
 }
 
-void
-MotionManager::updateWorldState() {
-	//cout << "updateWorldState" << endl;
-	for(uint output=LEDOffset; output<LEDOffset+NumLEDs; output++)
-		state->outputs[output]=cmdSums[output];
-	for(uint output=BinJointOffset; output<BinJointOffset+NumBinJoints; output++)
-		state->outputs[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; output<NumPIDJoints; output++)
-			if(!ERS210Info::IsRealERS210[output])
-				state->outputs[output]=cmdSums[output];
-	} else if(state->robotDesign & WorldState::ERS220Mask) {
-		for(uint output=0; output<NumPIDJoints; output++)
-			if(!ERS220Info::IsRealERS220[output])
-				state->outputs[output]=cmdSums[output];
-	} else if(state->robotDesign & WorldState::ERS7Mask) {
-		for(uint output=0; output<NumPIDJoints; output++)
-			if(!ERS7Info::IsRealERS7[output])
-				state->outputs[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<MotionManagerMsg*>(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<MotionCommand*>(mminfo) << ")" << endl;
-				cmdlist[mc_id].baseaddrs[_MMaccID]=static_cast<MotionCommand*>(mminfo);
+				cmdlist[mc_id].baseaddrs[getAccID()]=static_cast<MotionCommand*>(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<MotionCommand*>(mminfo),"Baseaddr changed!");
+				ASSERT(cmdlist[mc_id].lastAccessor==(accID_t)-1 || cmdlist[mc_id].baseaddrs[getAccID()]==static_cast<MotionCommand*>(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=="<<mc_id << "..." << flush;
 			ASSERT(cmdlist[mc_id].lastAccessor==(accID_t)-1,"delete motion message for motion command not marked for deletion");
-			if(cmdlist[mc_id].rcr[_MMaccID]==NULL) {
+			if(cmdlist[mc_id].rcr[getAccID()]==NULL) {
 #ifndef PLATFORM_APERIOS
 				// on non-aperios, we get an echo of the remove request, so don't report an error, just ignore it
 				if(mminfo->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; i<numAcc; i++) {
 					if(cmdlist[mc_id].rcr[i]!=NULL) {
@@ -727,9 +714,9 @@
 					}
 					cmdlist[mc_id].lastAccessor=(accID_t)-1; // reset inaccessiblity
 				}
-				cmdlist[mc_id].rcr[_MMaccID]->RemoveReference();
-				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<MotionCommand*>(reinterpret_cast<MotionManagerMsg*>(sm.data()));
+	MotionCommand * mc = dynamic_cast<MotionCommand*>(static_cast<MotionManagerMsg*>(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("<<i++<<")==" << subjs[_MMaccID]->RemainBuffer(*it) << endl;
+		for(ObserverConstIterator it=subjs[getAccID()]->begin();it!=subjs[getAccID()]->end();it++) {
+			cout << "RemainBuffer("<<i++<<")==" << subjs[getAccID()]->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="<<mcid<<" process=" << ProcessID::getIDStr() << endl;
 		stacktrace::displayCurrentStackTrace();
 		func_end();
 		return;
 	}
-	cmdlist[mcid].lock.lock(_MMaccID);
+	cmdlist[mcid].lock.lock(getAccID());
 	if(ProcessID::getID()==ProcessID::MotionProcess) {
 		MotionCommand * mc=checkoutMotion(mcid,true);
 		try {
@@ -916,9 +909,9 @@
 		checkinMotion(mcid);
 	}
 	cmdlist[mcid].lastAccessor=(accID_t)-1;
-	cmdlist[mcid].rcr[_MMaccID]->RemoveReference();
-	cmdlist[mcid].rcr[_MMaccID]=NULL;
-	cmdlist[mcid].baseaddrs[_MMaccID]=NULL;
+	cmdlist[mcid].rcr[getAccID()]->RemoveReference();
+	cmdlist[mcid].rcr[getAccID()]=NULL;
+	cmdlist[mcid].baseaddrs[getAccID()]=NULL;
 	cmdlist[mcid].lock.unlock();
 	if(ProcessID::getID()==ProcessID::MainProcess) {
 		try {
@@ -933,15 +926,15 @@
 	MotionManagerMsg dmsg;
 	dmsg.setDelete(mcid);
 	//cout << "Remove at " << get_time() << flush;
-	subjs[_MMaccID]->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<MotionManagerMsg> 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<YourMC>([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<class T> 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;          //!<Stores the accessor for the current process
+	static int getAccID() { return _MMaccID[ProcessID::getID()]; }
+	static int _MMaccID[ProcessID::NumProcesses]; //!<Stores the accessor id assigned in InitAccess() for each process
 	static EventTranslator* etrans; //!< EventTranslator for sending events to Main -- each process will set the correct value for calls within that process.
 
 private:
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/MotionSequenceEngine.cc ./Motion/MotionSequenceEngine.cc
--- ../Tekkotsu_3.0/Motion/MotionSequenceEngine.cc	2006-09-23 15:51:11.000000000 -0400
+++ ./Motion/MotionSequenceEngine.cc	2007-09-26 19:16:49.000000000 -0400
@@ -8,11 +8,11 @@
 using std::cout;
 using std::endl;
 
-MotionSequenceEngine::Move_idx_t MotionSequenceEngine::invalid_move=-1U;
+MotionSequenceEngine::Move_idx_t MotionSequenceEngine::invalid_move=(MotionSequenceEngine::Move_idx_t)-1;
 
 MotionSequenceEngine::MotionSequenceEngine()
 : LoadSave(), playtime(1), lasttime(0), endtime(0), playspeed(1.0),
-playing(true), hold(true), loadSaveMode(M_PI/180)
+playing(true), hold(true), loadSaveMode(1)
 {
 	for(unsigned int i=0; i<NumOutputs; i++)
 		curstamps[i]=-1U;
@@ -135,7 +135,7 @@
 			}
 		}
 		written=-1;
-		const unsigned int cmdlen=16, arglen=32;
+		const unsigned int cmdlen=64, arglen=32;
 		char command[cmdlen];
 		char arg1[arglen];
 		char arg2[arglen];
@@ -187,7 +187,8 @@
 			} else
 				cout << "*** WARNING could not read file " << arg1 << " for load (loadExplicit only accepts posture files) - line " << linenum << endl;
 		} else if(strcasecmp(command,"degrees")==0) {
-			setSaveDegrees();
+			cout << "*** WARNING 'degrees' is deprecated, please specify all angles as radians" << endl;
+			loadSaveMode=M_PI/180; //setSaveDegrees();
 		} else if(strcasecmp(command,"radians")==0) {
 			setSaveRadians();
 		} else {
@@ -315,6 +316,9 @@
 	return LoadSave::saveFile(config->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(idx<NumOutputs) {
 		unsigned int startidx=idx;
 		for(;idx<NumOutputs;idx++)
-			if(strcmp(name,outputNames[idx])==0)
+			if(strncmp(name,outputNames[idx],n)==0)
 				return idx;
 		for(idx=0;idx<startidx;idx++)
-			if(strcmp(name,outputNames[idx])==0)
+			if(strncmp(name,outputNames[idx],n)==0)
 				return idx;
 		return NumOutputs;
 	} else {
 		for(idx=0;idx<NumOutputs;idx++)
-			if(strcmp(name,outputNames[idx])==0)
+			if(strncmp(name,outputNames[idx],n)==0)
 				return idx;
 		return idx;
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/MotionSequenceEngine.h ./Motion/MotionSequenceEngine.h
--- ../Tekkotsu_3.0/Motion/MotionSequenceEngine.h	2006-10-03 19:01:28.000000000 -0400
+++ ./Motion/MotionSequenceEngine.h	2007-09-26 18:32:55.000000000 -0400
@@ -5,6 +5,7 @@
 #include "Shared/LoadSave.h"
 #include "IPC/ListMemBuf.h"
 #include "PostureEngine.h"
+#include "Shared/attributes.h"
 
 //! A handy class for storing a sequence of keyframed movements
 /*! Each outputs is handled independently.  It's easy to add keyframes
@@ -49,8 +50,6 @@
  *    - '<i>outputname</i><tt> </tt><i>value</i><tt> </tt>[<i>weight</i>]' - 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[])
  *    - '<tt>load </tt><i>filename</i>' - file can be a posture or another motion sequence (if MS, leaves playhead at end of the motion sequence); see setPose() and overlayMotion()
  *    - '<tt>loadExplicit </tt><i>filename</i>' - file must be a posture, sets position for all outputs, including zero-weighted ones; see setExplicitPose()
- *    - '<tt>degrees</tt>' - all following <i>value</i>s will be interpreted as degrees [default]
- *    - '<tt>radians</tt>' - all following <i>value</i>s will be interpreted as radians
  *    - '<tt>#</tt><i>comment</i>' - a comment line
  *  - Last line: '<tt>\#END</tt>'
  *  
@@ -60,21 +59,20 @@
  *  Example 1: This motion sequence will straighten out the head, panning from right to left.\n
 <table align="center"><tr><td align=left><pre>
 \#MSq 
-degrees 
 
 <i>\# Straighten head</i>
 advanceTime  50 
-NECK:tilt       15 
+NECK:tilt       0.262
 NECK:nod       0 
 
 <i>\# Pan right</i>
 advanceTime  850 
-NECK:pan~       -45 
+NECK:pan~       -0.785 
 
 <i>\# Pan left</i>
 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
 <table align="center"><tr><td align=left><pre>
 \#MSq
-degrees
 
 <i>\# Bring head and tail to neural positions</i>
 advanceTime 50
@@ -103,10 +100,10 @@
 
 <i>\# Pan left</i>
 advanceTime 1000
-NECK:pan~ 90
+NECK:pan~ 1.571
 <i>\# Pan right</i>
 advanceTime 1000
-NECK:pan~ -90
+NECK:pan~ -1.571
 
 <i>\# Center head</i>
 <i>\# Update tail time index</i>
@@ -117,10 +114,10 @@
 
 <i>\# Wag left</i>
 advanceTime 500
-TAIL:pan~ 90
+TAIL:pan~ 1.571
 <i>\# Wag right</i>
 advanceTime 500
-TAIL:pan~ -90
+TAIL:pan~ -1.571
 
 \#END 
 </pre></td></tr></table>
@@ -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 <math.h>
-#include "Shared/Config.h"
-
-OldHeadPointerMC::OldHeadPointerMC() :
-  MotionCommand(), dirty(true), active(true), targetReached(false) {
-  setWeight(1);
-  defaultMaxSpeed();
-  for(unsigned int i=0; i<NumHeadJoints; i++) {
-    headModes[i]=BodyRelative;
-    headTargets[i]=0;
-    headCmds[i].value=state->outputs[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; x<NumHeadJoints; x++)
-    headCmds[x].weight=w;
-  dirty=true; targetReached=false;
-}
-
-void OldHeadPointerMC::defaultMaxSpeed() {
-  maxSpeed[TiltOffset]=config->motion.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; x<NumHeadJoints; x++)
-    setJointMode((RobotInfo::TPROffset_t)x,m,conv);
-}
-
-void OldHeadPointerMC::setJointMode(RobotInfo::TPROffset_t i, CoordFrame_t m, bool conv) {
-  if(conv)
-    headTargets[i]=OldHeadPointerMC::convert(i,headTargets[i],headModes[i],m);
-  headModes[i]=m;
-  dirty=true; targetReached=false;
-}
-
-int OldHeadPointerMC::updateOutputs() {
-  int tmp=isDirty();
-  if(tmp) {
-    dirty=false;
-    for(unsigned int i=0; i<NumHeadJoints; i++) {
-      float value;
-      if(headModes[i]!=BodyRelative) {
-	value=convToBodyRelative((RobotInfo::TPROffset_t)i,headTargets[i],headModes[i]);
-	dirty=true;
-      } else
-	value=headTargets[i];
-      if(maxSpeed[i]<=0)
-	headCmds[i].value=value;
-      if(value==headCmds[i].value) {
-	motman->setOutput(this,i+HeadOffset,headCmds[i]);
-      } else { // we may be trying to exceeded maxSpeed
-	unsigned int f=0;
-	while(value>headCmds[i].value+maxSpeed[i] && f<NumFrames) {
-	  headCmds[i].value+=maxSpeed[i];
-	  motman->setOutput(this,i+HeadOffset,headCmds[i],f);
-	  f++;
-	}
-	while(value<headCmds[i].value-maxSpeed[i] && f<NumFrames) {
-	  headCmds[i].value-=maxSpeed[i];
-	  motman->setOutput(this,i+HeadOffset,headCmds[i],f);
-	  f++;
-	}
-	if(f<NumFrames) { //we reached target value, fill in rest of frames
-	  headCmds[i].value=value;
-	  for(;f<NumFrames;f++)
-	    motman->setOutput(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; i<NumHeadJoints; i++) {
-      float diff=(state->outputs[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(i<NumHeadJoints && getActive())
-    return headCmds[i];
-  else
-    return OutputCmd::unused;
-}
-
-/*! @todo this is perhaps a bit amateurish - could be more accurate */
-double OldHeadPointerMC::convToBodyRelative(TPROffset_t i, double v, CoordFrame_t mode) const {
-  switch(mode) {
-  default:
-    ASSERT(false,"Passed bad mode "<<mode);
-  case BodyRelative:
-    return v;
-  case GravityRelative: {
-    double bacc=state->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 "<<i<<" (use RobotInfo::TPROffset_t!)");
-      return v;
-    }
-  }
-  }
-}
-
-/*! @todo this is perhaps a bit amateurish - could be more accurate */
-double OldHeadPointerMC::convFromBodyRelative(TPROffset_t i, double v, CoordFrame_t mode) const {
-  switch(mode) {
-  default:
-    ASSERT(false,"Passed bad mode "<<mode);
-  case BodyRelative:
-    return v;
-  case GravityRelative: {
-    double bacc=state->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 "<<i<<" (use RobotInfo::TPROffset_t!)");
-      return v;
-    }
-  }
-  }
-}
-
-
-/*! @file
- * @brief Implements OldHeadPointerMC, a class for various ways to control where the head is looking
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2004/10/14 20:23:50 $
- */
-
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/OldHeadPointerMC.h ./Motion/OldHeadPointerMC.h
--- ../Tekkotsu_3.0/Motion/OldHeadPointerMC.h	2005-08-07 00:11:03.000000000 -0400
+++ ./Motion/OldHeadPointerMC.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,126 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_OldHeadPointerMC_h
-#define INCLUDED_OldHeadPointerMC_h
-
-#include "MotionCommand.h"
-#include "OutputCmd.h"
-#include "Shared/RobotInfo.h"
-
-//! This class gives some quick and easy functions to point the head at things
-class OldHeadPointerMC : public MotionCommand {
-public:
-  //! constructor, defaults to active, BodyRelative, all joints at 0
-  OldHeadPointerMC();
-
-  //! destructor
-  virtual ~OldHeadPointerMC() {}
-
-  //! Various modes the head can be in.  In the future may want to add ability to explicitly track an object or point in the world model
-  enum CoordFrame_t {
-    BodyRelative,    //!<holds neck at a specified position, like a PostureEngine, but neck specific
-    GravityRelative  //!<uses accelerometers to keep a level head, doesn't apply for pan joint, but in future could use localization for pan
-  };
-
-  void   setWeight(double w);                               //!< sets the weight values for all the neck joints
-
-  //! set a specific head joint weight, pass one of RobotInfo::TPROffset_t, not a full offset!
-  void setWeight(RobotInfo::TPROffset_t i, double weight) {
-    dirty=true; targetReached=false; headCmds[i].weight=weight; }
-
-  void   setActive(bool a) { active=a; } //!< sets #active flag; see isDirty()
-  bool   getActive() const { return active; } //!< returns #active flag, see isDirty()
-
-  //! sets #maxSpeed to 0 (no maximum)
-  void noMaxSpeed() { for(unsigned int i=0; i<NumHeadJoints; i++) maxSpeed[i]=0; }
-
-  void defaultMaxSpeed(); //!< restores #maxSpeed to default settings from Config::Motion_Config
-
-  void setMaxSpeed(TPROffset_t i, float x) { maxSpeed[i]=x*FrameTime/1000; } //!< sets #maxSpeed in rad/sec
-  float getMaxSpeed(TPROffset_t i) { return maxSpeed[i]*1000/FrameTime; } //!< returns #maxSpeed in rad/sec
-
-  //! converts a value @a v in @a srcmode to a value in @a tgtmode that would leave the joint angle for joint @a i constant (you probably won't need to call this directly)
-  double convert(RobotInfo::TPROffset_t i, double v, CoordFrame_t srcmode, CoordFrame_t tgtmode) const {
-    return (srcmode==tgtmode)?v:convFromBodyRelative(i,convToBodyRelative(i, v, srcmode),tgtmode);
-  }
-
-  //!Note that none of these are @c virtual, so you don't have to checkout to use them, you @e should be able to use MotionManager::peekMotion()
-  //!@name Joint Accessors
-
-  //! Directly sets the neck values (radians), uses current mode
-  void setJoints(double tilt, double pan, double roll);
-
-  //! sets all the joints to the given mode, will convert the values to the new mode if @a convert is true
-  void setMode(CoordFrame_t m, bool convert=true); 
-
-    //! sets a specific head joint's mode; will convert from previous mode's value to next mode's value if convert is true.  Pass one of RobotInfo::TPROffset_t, not a full offset!
-  void setJointMode(RobotInfo::TPROffset_t i, CoordFrame_t m, bool convert=true);
-
-  //! set a specific head joint's value (in radians, for whatever mode it's in), pass one of RobotInfo::TPROffset_t, not a full offset!
-  void setJointValue(RobotInfo::TPROffset_t i, double value)
-	{ dirty=true; targetReached=false; headTargets[i]=(headModes[i]==BodyRelative)?clipAngularRange(i+HeadOffset,value):value; }
-
-  //! set a specific head joint (in radians), pass one of RobotInfo::TPROffset_t, not a full offset!
-  void setJointValueAndMode(RobotInfo::TPROffset_t i, double value, CoordFrame_t m)
-  { dirty=true; targetReached=false; headTargets[i]=(m==BodyRelative)?clipAngularRange(i+HeadOffset,value):value; headModes[i]=m; }
-
-  //! set a specific head joint (in radians) auto converting @a value from mode @a m to the current mode, pass one of RobotInfo::TPROffset_t, not a full offset!
-  void setJointValueFromMode(RobotInfo::TPROffset_t i, double value, CoordFrame_t m)
-  { dirty=true; targetReached=false; headTargets[i]=convert(i,value,m,headModes[i]); }
-
-  //! returns the current mode for joint @a i (use RobotInfo::TPROffset_t, not global offset)
-  CoordFrame_t getJointMode(RobotInfo::TPROffset_t i) const { return headModes[i]; }
-
-  //! returns the target value (relative to the current mode) of joint @a i.  Use getOutputCmd() if you want to know the current @b commanded joint value; To get the current joint @b position, look in WorldState
-  double getJointValue(RobotInfo::TPROffset_t i) const { return headTargets[i]; }
-  //@}
-
-
-  //!@name Inherited:
-  virtual int updateOutputs(); //!< Updates where the head is looking
-  virtual const OutputCmd& getOutputCmd(unsigned int i);  //!< returns one of the #headCmds entries or ::unusedJoint if not a head joint
-  virtual int isDirty() { return ((dirty || !targetReached) && active)?1:0; } //!< true if a change has been made since the last updateJointCmds() and we're active
-  virtual int isAlive() { return true; }
-  virtual void DoStart() { MotionCommand::DoStart(); dirty=true; targetReached=false; }
-  //@}
-
- protected:
-  double convToBodyRelative(TPROffset_t i, double v, CoordFrame_t mode) const;   //!< converts to a body relative measurement for joint @a i
-  double convFromBodyRelative(TPROffset_t i, double v, CoordFrame_t mode) const; //!< converts from a body relative measurement for joint @a i
-	static float normalizeAngle(float x) { return x-rint(x/(2*M_PI))*(2*M_PI); } //!< puts x in the range (-pi,pi)
-	//! if @a x is outside of the range of joint @a i, it is set to either the min or the max, whichever is closer
-	static float clipAngularRange(unsigned int i, float x) {
-		float min=outputRanges[i][MinRange];
-		float max=outputRanges[i][MaxRange];
-		if(x<min || x>max) {
-			float mn_dist=fabs(normalizeAngle(min-x));
-			float mx_dist=fabs(normalizeAngle(max-x));
-			if(mn_dist<mx_dist)
-				return min;
-			else
-				return max;
-		} else
-			return x;
-	}
-
-  bool dirty;                            //!< true if a change has been made since last call to updateJointCmds()
-  bool active;                           //!< set by accessor functions, defaults to true
-  bool targetReached;                  //!< false if the head is still moving towards its target
-  OutputCmd headCmds[NumHeadJoints] ;  //!< stores the last values we sent from updateOutputs
-  float headTargets[NumHeadJoints];       //!< stores the target value of each joint, relative to #headModes
-  CoordFrame_t headModes[NumHeadJoints]; //!< stores the current mode of each joint, for instance so tilt can be GravityRelative while pan is static
-  float maxSpeed[NumHeadJoints];         //!< initialized from Config::motion_config, but can be overridden by setMaxSpeed(); rad per frame
-};
-
-/*! @file
- * @brief Describes OldHeadPointerMC, a class for various ways to control where the head is looking
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.2 $
- * $State: Exp $
- * $Date: 2005/08/07 04:11:03 $
- */
-
-#endif
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/OldKinematics.cc ./Motion/OldKinematics.cc
--- ../Tekkotsu_3.0/Motion/OldKinematics.cc	2006-10-03 22:41:52.000000000 -0400
+++ ./Motion/OldKinematics.cc	2007-06-26 00:27:45.000000000 -0400
@@ -36,7 +36,7 @@
 
 #include "OldKinematics.h"
 //#include "Wireless/Socket.h"
-#include "Shared/ERS7Info.h"
+#include "Shared/RobotInfo.h"
 
 // #define DEBUG
 
@@ -404,11 +404,11 @@
 	//but should use tilt too if out of range of nod
 
 	//if we can't pan far enough, change the tilt
-	if(angles[1]<ERS7Info::outputRanges[ERS7Info::HeadOffset+PanOffset][MinRange] || 
-		 angles[1]>ERS7Info::outputRanges[ERS7Info::HeadOffset+PanOffset][MaxRange]
+	if(angles[1]<outputRanges[HeadOffset+PanOffset][MinRange] || 
+		 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][MinRange] || 
-		 angles[2]>ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MaxRange]
+	if(angles[2]<outputRanges[HeadOffset+NodOffset][MinRange] || 
+		 angles[2]>outputRanges[HeadOffset+NodOffset][MaxRange]
 		 ) {
 		double nod;
-		if(angles[2]<ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MinRange])
-			nod=ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MinRange];
+		if(angles[2]<outputRanges[HeadOffset+NodOffset][MinRange])
+			nod=outputRanges[HeadOffset+NodOffset][MinRange];
 		else
-			nod=ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MaxRange];
+			nod=outputRanges[HeadOffset+NodOffset][MaxRange];
 		double rad=hypot(target.x,target.z); // aka 'r'
 		double slope=tan(nod);
 		double intcpt=neck_to_nod.z+nod_to_camera.z/cos(nod); // aka 'h'
 		double A=target.y-neck_to_nod.y;
 		double B=A*slope;
 		double yval;
-		if(angles[2]<ERS7Info::outputRanges[ERS7Info::HeadOffset+NodOffset][MinRange])
+		if(angles[2]<outputRanges[HeadOffset+NodOffset][MinRange])
 			// too low: use the '-' solution so we get the lower intercept:
 			yval = ( A*A*intcpt - sqrt(B*B*(A*A*A*A+B*B*rad*rad+A*A*(B*B-intcpt*intcpt+rad*rad))) ) / (A*A+B*B);
 		else
 			// too high: use the '+' solution so we get the upper intercept:
 			yval = ( A*A*intcpt + sqrt(B*B*(A*A*A*A+B*B*rad*rad+A*A*(B*B-intcpt*intcpt+rad*rad))) ) / (A*A+B*B);
 		angles[0]=atan2(target.z,target.x)-asin(yval/rad);
-		if(angles[0]<ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MinRange])
-			angles[0]=ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MinRange];
-		else if(angles[0]>ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MaxRange])
-			angles[0]=ERS7Info::outputRanges[ERS7Info::HeadOffset+TiltOffset][MaxRange];
+		if(angles[0]<outputRanges[HeadOffset+TiltOffset][MinRange])
+			angles[0]=outputRanges[HeadOffset+TiltOffset][MinRange];
+		else 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 <stdio.h>
 #include <iostream>
+#include <regex.h>
+#include <map>
+
+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,"<meta-info>\n  timestamp\t%u\n  framenumber\t%u\n</meta-info>\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber);
+			written+=snprintf(buf,len,"<meta-info>\n	timestamp\t%u\n	 framenumber\t%u\n</meta-info>\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber);
 		for(unsigned int i=0; i<NumOutputs; i++)
 			if(cmds[i].weight>0) {
-				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,"<buttons>\n");
 			for(unsigned int i=0; i<NumButtons; i++) {
-				written+=snprintf(buf,len,"  %s\t% .4f\t\n",buttonNames[i],loadSaveSensors->buttons[i]);
+				written+=snprintf(buf,len,"	 %s\t% .4f\t\n",buttonNames[i],loadSaveSensors->buttons[i]);
 			}
 			written+=snprintf(buf,len,"</buttons><sensors>\n");
 			for(unsigned int i=0; i<NumSensors; i++) {
-				written+=snprintf(buf,len,"  %s\t% .4f\t\n",sensorNames[i],loadSaveSensors->sensors[i]);
+				written+=snprintf(buf,len,"	 %s\t% .4f\t\n",sensorNames[i],loadSaveSensors->sensors[i]);
 			}
 			written+=snprintf(buf,len,"</sensors><pidduties>\n");
 			for(unsigned int i=0; i<NumPIDJoints; i++) {
-				written+=snprintf(buf,len,"  duty-%s\t% .4f\t\n",outputNames[i],loadSaveSensors->pidduties[i]);
+				written+=snprintf(buf,len,"	 duty-%s\t% .4f\t\n",outputNames[i],loadSaveSensors->pidduties[i]);
 			}
 			written+=snprintf(buf,len,"</pidduties>\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<const void*>(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; i<NumOutputs; i++)
-	cmds[i].unset();
-      /*} else if(strncmp(buf,"verbose",strlen("verbose"))==0) {
-	written=strlen("verbose");
-	if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0;
-	saveFormatCondensed=false;*/
-    } else {
-      if(saveFormatCondensed) {
-	const unsigned int sectionLen=64;
-	char section[sectionLen];
-	written=0; sscanf(buf,"%64s = %n",section,&written);
-	if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0;
-	if(strncmp(section,"outputs",sectionLen)==0) {
-	  for(unsigned int i=0; i<NumOutputs; i++) {
-	    float val;
-	    written=0; sscanf(buf,"%g%n",&val,&written);
-	    if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0;
-	    cmds[i].set(val);
-	  }
-	} else if(strncmp(section,"weights",sectionLen)==0) {
-	  for(unsigned int i=0; i<NumOutputs; i++) {
-	    written=0; sscanf(buf,"%g%n",&cmds[i].weight,&written);
-	    if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0;
-	  }
-	} else if(strncmp(section,"buttons",sectionLen)==0) {
-	  for(unsigned int i=0; i<NumButtons; i++) {
-	    written=0; sscanf(buf,"%g%n",&loadSaveSensors->buttons[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; i<NumSensors; i++) {
-	    written=0; sscanf(buf,"%g%n",&loadSaveSensors->sensors[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; i<NumPIDJoints; i++) {
-	    written=0; sscanf(buf,"%g%n",&loadSaveSensors->pidduties[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,"<meta-info>",strlen("<meta-info>"))==0) {
-	  written=0; sscanf(buf,"<meta-info>%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 <meta-info> - 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,"</meta-info>",strlen("</meta-info>"))==0) {
-	  written=0; sscanf(buf,"</meta-info>%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 </meta-info> 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,"<buttons>",strlen("<buttons>"))==0) {
-	  written=0; sscanf(buf,"<buttons>%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 <buttons> - 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,"</buttons>",strlen("</buttons>"))==0) {
-	  written=0; sscanf(buf,"</buttons>%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 </buttons> 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,"<sensors>",strlen("<sensors>"))==0) {
-	  written=0; sscanf(buf,"<sensors>%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 <sensors> - 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,"</sensors>",strlen("</sensors>"))==0) {
-	  written=0; sscanf(buf,"</sensors>%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 </sensors> 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,"<pidduties>",strlen("<pidduties>"))==0) {
-	  written=0; sscanf(buf,"<pidduties>%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 <pidduties> - 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,"</pidduties>",strlen("</pidduties>"))==0) {
-	  written=0; sscanf(buf,"</pidduties>%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 </pidduties> 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(;idx<NumButtons;idx++)
-	      if(strncmp(name,buttonNames[idx],nameLen)==0) {
-		loadSaveSensors->buttons[idx]=fval;
-		break;
-	      }
-	    if(idx==NumButtons) { //not found following startidx, look from beginning
-	      for(idx=0;idx<startidx;idx++)
-		if(strncmp(name,buttonNames[idx],nameLen)==0) {
-		  loadSaveSensors->buttons[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<string,section_t> 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; lineend<len; ++lineend) {
+			bool isreturn = (buf[lineend]=='\r');
+			if(isreturn || buf[lineend]=='\n') {
+				line.assign(buf,lineend);
+				++linenum;
+				++lineend;
+				buf+=lineend;
+				len-=lineend;
+				if(len==0) // end of buffer, don't check for \n
+					break;
+				if(isreturn && buf[0]=='\n') { // indicates an \r\n
+					++buf;
+					--len;
+				}
+				break;
+			}
 		}
-	      if(idx==startidx && strcmp(name,buttonNames[idx])!=0) //not found at all
-		std::cout << "*** WARNING '" << name << "' is not a valid button on this model. (ignoring line " << linenum << ")" << std::endl;
-	    }
-	  } else if(curSection==SECTION_SENSORS) {
-	    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(;idx<NumSensors;idx++)
-	      if(strncmp(name,sensorNames[idx],nameLen)==0) {
-		loadSaveSensors->sensors[idx]=fval;
-		break;
-	      }
-	    if(idx==NumSensors) { //not found following startidx, look from beginning
-	      for(idx=0;idx<startidx;idx++)
-		if(strncmp(name,sensorNames[idx],nameLen)==0) {
-		  loadSaveSensors->sensors[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(;idx<NumPIDJoints;idx++)
-	      if(strncmp(name,outputNames[idx],nameLen)==0) {
-		loadSaveSensors->pidduties[PIDJointOffset+idx]=fval;
-		break;
-	      }
-	    if(idx==NumPIDJoints) { //not found following startidx, look from beginning
-	      for(idx=0;idx<startidx;idx++)
-		if(strncmp(name,outputNames[idx],nameLen)==0) {
-		  loadSaveSensors->pidduties[PIDJointOffset+idx]=fval;
-		  break;
+		
+		// tokenize
+		// whitespace and '=' are used as delimiters
+		vector<string> words;
+		for(unsigned int i=0; i<line.size(); ++i) {
+			if(isspace(line[i]) || line[i]=='=')
+				continue;
+			unsigned int j=i+1;
+			while(j<line.size() && !isspace(line[j]) && line[j]!='=')
+				++j;
+			words.push_back(line.substr(i,j-i));
+			i=j;
 		}
-	      if(idx==startidx && strcmp(name,outputNames[idx])!=0) //not found at all
-		std::cout << "*** WARNING '" << name << "' is not a valid PID joint on this model. (ignoring line " << linenum << ")" << std::endl;
-	    }
-	  } else { //general joint specification
-	    jname[0]='\0';
-	    written=0; sscanf(buf,formatstring,jname,&fval,&fwht,&written);
-	    if(!checkInc(written,buf,len,"*** ERROR PostureEngine load corrupted - line %d\n",linenum)) return 0;
-	    //std::cout << '"' << jname << "\"\t" << (float)fval << '\t' << (float)fwht << std::endl;
-	    // we continue the search in order from where we left off - these are often
-	    // going to go in order, so might as well save a little time
-	    unsigned int startidx=idx;
-	    for(;idx<NumOutputs;idx++)
-	      if(strncmp(jname,outputNames[idx],outputNameLen+1)==0) {
-		cmds[idx].set(fval,fwht);
-		break;
-	      }
-	    if(idx==NumOutputs) { //not found following startidx, look from beginning
-	      for(idx=0;idx<startidx;idx++)
-		if(strncmp(jname,outputNames[idx],outputNameLen+1)==0) {
-		  cmds[idx].set(fval,fwht);
-		  break;
+		if(words.size()==0)
+			continue;
+		
+		// debugging output
+		/*cout << "LINE " << linenum << endl;
+		for(unsigned int i=0; i<words.size(); ++i)
+			cout << '\t' << words[i] << endl;*/
+		
+		// process the line!
+		if(!loadLine(linenum,sectionMap,words,curSection,caps,filtered))
+			return 0;
+		
+	} // end of process-line loop 'while'
+		
+	// shouldn't get here, proper file ends with '#END', which will trigger a 'return' within the loop
+	std::cout << "*** WARNING PostureEngine load missing #END" << std::endl;
+	return origlen-len;
+}
+
+bool PostureEngine::loadLine(unsigned int linenum, const std::map<std::string,section_t>& sectionMap, std::vector<std::string>& 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;idx<NumOutputs;idx++) {
-					if(strncmp(tname,outputNames[idx],outputNameLen+1)==0) {
-						lidx=idx;
-						break;
+		
+	} else if(words[0]=="condensed") {
+		if(words.size()>2)
+			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<string,section_t>::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<string,section_t>::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; i<words.size(); ++i)
+						cmds[i-1].weight = atof(words[i].c_str());
+				} else {
+					// we're using another target, map to the host
+					for(unsigned int i=1; i<words.size(); ++i) {
+						const char * name = caps->getOutputName(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;idx<NumOutputs;idx++) {
-					if(strncmp(tname,outputNames[idx],outputNameLen+1)==0) {
-						ridx=idx;
+			} else {
+				// line is not a section declaration -- is it an 'verbose' output/sensor/button/etc. name within the current section??
+				if(words.size()<2) {
+					cerr << "*** ERROR line " << linenum << ", no value supplied for " << words[0] << endl;
+					return false;
+				}
+				switch(curSection) {
+					case SECTION_METAINFO: {
+						if(words[0]=="timestamp") {
+							if(loadSaveSensors!=NULL)
+								loadSaveSensors->lastSensorUpdateTime = 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 || 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; i<size; ++i)
+							cmds[i-1].set(atof(words[i].c_str()));
+					} else {
+						// we're using another target, map to the host
+						for(unsigned int i=1; i<size; ++i) {
+							const char * name = caps->getOutputName(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; i<size; ++i)
+							loadSaveSensors->buttons[i-1] = atof(words[i].c_str());
+					} else {
+						// we're using another target, map to the host
+						for(unsigned int i=1; i<size; ++i) {
+							const char * name = caps->getButtonName(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; i<size; ++i)
+							loadSaveSensors->sensors[i-1] = atof(words[i].c_str());
+					} else {
+						// we're using another target, map to the host
+						for(unsigned int i=1; i<size; ++i) {
+							const char * name = caps->getSensorName(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; i<size; ++i)
+							loadSaveSensors->pidduties[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; i<size; ++i) {
+							const char * name = caps->getOutputName(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 || 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,"<meta-info>\n  timestamp\t%u\n  framenumber\t%u\n</meta-info>\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber);
+			written=snprintf(buf,len,"<meta-info>\n	 timestamp\t%u\n	framenumber\t%u\n</meta-info>\n",loadSaveSensors->lastSensorUpdateTime,loadSaveSensors->frameNumber);
 			if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor begin save failed\n")) return 0;
 		}
-		for(unsigned int i=0; i<NumOutputs; i++)
+		for(unsigned int i=0; i<NumOutputs; i++) {
 			if(cmds[i].weight>0) {
-				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,"<buttons>\n");
 			if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor begin save failed\n")) return 0;
 			for(unsigned int i=0; i<NumButtons; i++) {
-				written=snprintf(buf,len,"  %s\t% .4f\t\n",buttonNames[i],loadSaveSensors->buttons[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,"</buttons><sensors>\n");
 			if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor end save failed\n")) return 0;
 			for(unsigned int i=0; i<NumSensors; i++) {
-				written=snprintf(buf,len,"  %s\t% .4f\t\n",sensorNames[i],loadSaveSensors->sensors[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,"</sensors><pidduties>\n");
 			if(!checkInc(written,buf,len,"*** ERROR PostureEngine sensor end save failed\n")) return 0;
 			for(unsigned int i=0; i<NumPIDJoints; i++) {
-				written=snprintf(buf,len,"  %s\t% .4f\t\n",outputNames[i],loadSaveSensors->pidduties[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,"</pidduties>\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<<ROBOOP::fourbyfourident;
-		A.Release(); return A;
-	}
-	update(c,l);
-	NEWMAT::Matrix R;
-	NEWMAT::ColumnVector p;
-	chains[c]->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<<ROBOOP::fourbyfourident;
-		A.Release(); return A;
-	}
-	update(c,l);
-	NEWMAT::Matrix R;
-	NEWMAT::ColumnVector p;
-	chains[c]->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<<ROBOOP::fourbyfourident;
+		 A.Release(); return A;
+	 }
+	 update(c,l);
+	 NEWMAT::Matrix R;
+	 NEWMAT::ColumnVector p;
+	 chains[c]->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<<ROBOOP::fourbyfourident;
+		 A.Release(); return A;
+	 }
+	 update(c,l);
+	 NEWMAT::Matrix R;
+	 NEWMAT::ColumnVector p;
+	 chains[c]->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: '<tt>\#POS</tt>'
+ *  - Followed by a series of:
+ *    - '<tt>specialize </tt><i>[regex]</i>' - 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 '<tt>specialize&nbsp;.*</tt>')
+ *    - '<tt>condensed </tt><i>model</i>' - specifies model name for which condensed specifications will be
+ *      interpreted
+ *    - '<tt>verbose</tt>' - switches the load/save format back to "verbose" style, where each output/sensor
+ *      value is listed individually
+ *    - '<tt>&lt;</tt><i>section</i><tt>&gt;</tt> ... <tt>&lt;/</tt><i>section</i><tt>&gt;</tt>' - specifies a
+ *      section for following "verbose" style lines (valid <i>section</i> values listed below)
+ *    - '<i>section</i> <i>value1</i> <i>value2</i> <i>value3</i> ...' - specify all values for a section in
+ *      one line, "condensed" style (valid <i>section</i> values listed below).  Must have a value for every
+ *      item in the section (no extra or missing values)
+ *    - '<i>output-name</i> <i>value</i> <i>[weight]</i>' - specifies an output value, with optional weighting
+ *      value (if no weight specified, '1' is assumed)
+ *  - Last line: '<tt>\#END</tt>'
+ *  
+ *  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:
+ *  - <tt>meta-info</tt> - only recognizes two fields: <tt>timestamp</tt> and <tt>framenumber</tt>
+ *  - <tt>outputs</tt> - supports all output names (e.g. ERS7Info::outputNames)
+ *  - <tt>buttons</tt> - supports all button names (e.g. ERS7Info::buttonNames)
+ *  - <tt>sensors</tt> - supports all sensor names (e.g. ERS7Info::sensorNames)
+ *  - <tt>pidduties</tt> - 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
+<table><tr><td align=left><pre>
+\#POS 
+NECK:tilt	0
+NECK:pan	0
+NECK:nod	0.2
+\#END
+</pre></td></tr></table>
+ *  All other, unspecified, joints will be set to weight=0.
+ *
+ *  Example 2: Logged sensor data from an ERS-7 robot
+<table><tr><td align=left><tt>
+\#POS<br>
+condensed ERS-7<br>
+meta-info = 1439041 178803<br>
+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<br>
+buttons = 0 0 0 0 0 0 0 0 0 1<br>
+sensors = 500 860.139 425 -2.06456 -0.516139 -8.94642 0.99 30.63 2200 8.265 0<br>
+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<br>
+\#END<br>
+</tt></td></tr></table>
+ *  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 <tt>condensed</tt> command to the current host.
+ *
  *  @see PostureMC
  *  @see <a href="http://www.cs.cmu.edu/~tekkotsu/Kinematics.html">Tekkotsu's Kinematics page</a>
  *  @see <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/postures.shtml">David Touretzky's "Postures and Motion Sequences" Chapter</a>
@@ -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<std::string,section_t>& sectionMap, std::vector<std::string>& 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; i<NumOutputs; i++)
 		maxSpeeds[i]=MaxOutputSpeed[i]*FrameTime*x; //MaxOutputsSpeed is rad/ms
 	//respect the config values for the neck joints (which are stored as rad/sec)
+#ifdef TGT_IS_AIBO
 	maxSpeeds[HeadOffset+TiltOffset]=config->motion.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; i<NumPIDJoints; i++) cmds[i]=0.0f;
-  }
+public:
+	//! constructor, defaults all joints at 0
+	RemoteControllerMC() : MotionCommand() {}
 	//! destructor
 	virtual ~RemoteControllerMC() {}
-
-	//!@name Inherited:
-  //! Updates all PIDJoint values
+	
+	//! Updates all of the outputs to their current positions, every time
+	/*! Any outputs which we don't set would be marked unused and be moved by a lower-priority motion command */
 	virtual int updateOutputs() {
-    int tmp=isDirty();
-    if (isDirty())
-      for (unsigned int i=0; i<NumPIDJoints; i++)
-        motman->setOutput(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; i<NumOutputs; i++)
+			motman->setOutput(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; i<NumFrames; i++) {
 			float new_pan = sin((2*M_PI*(get_time()+offset+i*FrameTime))/period)*magnitude; //bug fix thanks L.A.Olsson AT herts ac uk
@@ -53,7 +67,8 @@
 			last_pan = new_pan;
 		}
 		motman->setOutput(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<unsigned int>((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; i<NumLegs; ++i) {
+	for(unsigned int i=0; i<4; ++i) {
 		if(!decodeInc(wp.leg[i].neutral.x,buf,len)) return 0;
 		if(!decodeInc(wp.leg[i].neutral.y,buf,len)) return 0;
 		if(!decodeInc(wp.leg[i].neutral.z,buf,len)) return 0;
@@ -211,7 +218,7 @@
 	unsigned int origlen=len;
 	// Leg parameters
 	if(!saveCreatorInc("WalkMC-2.2",buf,len)) return 0;
-	for(unsigned int i=0; i<NumLegs; ++i) {
+	for(unsigned int i=0; i<4; ++i) {
 		if(!encodeInc(wp.leg[i].neutral.x,buf,len)) return 0;
 		if(!encodeInc(wp.leg[i].neutral.y,buf,len)) return 0;
 		if(!encodeInc(wp.leg[i].neutral.z,buf,len)) return 0;
@@ -269,6 +276,7 @@
 #endif
 
   target_vel_xya.set(dx,dy,da);
+	//std::cout << "set " << dx << ' ' << dy << ' ' << da << std::endl;
 	// we just modified the target velocity, but we'll hold off on generating
 	// an event until the changes are actually picked up by the motion system
 
@@ -305,11 +313,6 @@
 	if(!isDirty())
 		return 0;
 
-	if(vel_xya.sqlength()==0) {
-		// we had been stopped - better check someone else didn't move the legs while we weren't using them...
-		resetLegPos(); 
-	}
-
 	unsigned int curT=get_time();
 	if(last_target_vel_xya!=target_vel_xya) {
 		last_target_vel_xya=target_vel_xya;
@@ -320,7 +323,14 @@
 		travelTime=curT;
 	}
 	
-  float tm = TimeStep * slowmo / 1000;
+#if defined(TGT_HAS_LEGS)
+	
+	if(vel_xya.sqlength()==0) {
+		// we had been stopped - better check someone else didn't move the legs while we weren't using them...
+		resetLegPos(); 
+	}
+	
+	float tm = TimeStep * slowmo / 1000;
 
 	vector3d cal_target_vel_xya(target_vel_xya);
 	if(target_vel_xya.x<0)
@@ -561,15 +571,40 @@
 	
 	for(unsigned int joint=LegOffset; joint<LegOffset+NumLegJoints; joint++)
 		motman->setOutput(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<NumFrames; frame++) {
+		cmds[LWheelOffset][frame]=left;
+		cmds[RWheelOffset][frame]=right;
+	}
+	//std::cout << "update " << vel_xya.x << ' ' << vel_xya.y << ' ' << vel_xya.z << " -> " << left << ' ' << right << std::endl;
+	
+	for(unsigned int w=WheelOffset; w<WheelOffset+NumWheels; w++)
+		motman->setOutput(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<NumLegs; i++) {
 		double tmp[JointsPerLeg];
 		for(unsigned int j=0; j<JointsPerLeg; j++)
@@ -581,6 +616,7 @@
 			cout << "  ->  " << 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 <sstream>
 #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<string,string>* 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<string,string>* 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<string, map<string, string> > confdata_t;
+	typedef std::map<std::string, std::map<std::string, std::string> > 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 <fstream>
+
+using namespace std;
 
 #ifdef use_namespace
 namespace ROBOOP {
@@ -358,7 +361,7 @@
 }
 
 
-short IO_matrix_file::write(const vector<Matrix> & data, const vector<string> & title)
+short IO_matrix_file::write(const std::vector<Matrix> & data, const std::vector<std::string> & title)
 /*!
   @brief Write data on disk.
   @param data: Data.
@@ -467,7 +470,7 @@
 }
 
 
-short IO_matrix_file::read(vector<Matrix> & data, vector<string> & data_title)
+short IO_matrix_file::read(std::vector<Matrix> & data, std::vector<std::string> & data_title)
 //! @brief Read one sequence of data per call.
 {
    /*
@@ -537,7 +540,7 @@
 }
 
 
-short IO_matrix_file::read_all(vector<Matrix> & data, vector<string> & data_title)
+short IO_matrix_file::read_all(std::vector<Matrix> & data, std::vector<std::string> & 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 vector<char *>label, int type, const Matrix &xdata, const Matrix &ydata,
-                 const vector<int> & data_select);
+                 const std::vector<char *>label, int type, const Matrix &xdata, const Matrix &ydata,
+                 const std::vector<int> & 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<Matrix> & data);
-   short write(const vector<Matrix> & data, const vector<string> & title);
-   short read(vector<Matrix> & data);
-   short read(vector<Matrix> & data, vector<string> & title);
-   short read_all(vector<Matrix> & data, vector<string> & data_title);
+   IO_matrix_file(const std::string & filename);
+   short write(const std::vector<Matrix> & data);
+   short write(const std::vector<Matrix> & data, const std::vector<std::string> & title);
+   short read(std::vector<Matrix> & data);
+   short read(std::vector<Matrix> & data, std::vector<std::string> & title);
+   short read_all(std::vector<Matrix> & data, std::vector<std::string> & 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<Matrix> data_from_file;  //!< Data file.
-   vector<string> data_title;      //!< Data file title.
+   std::vector<Matrix> data_from_file;  //!< Data file.
+   std::vector<std::string> 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 <sstream>
 
+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 <sstream>
 #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<min?min:x); }
@@ -364,6 +364,9 @@
        ERS_LEG,       //!< AIBO leg
        ERS2XX_HEAD,   //!< AIBO 200 series camera chain (210, 220)
        ERS7_HEAD,     //!< AIBO 7 model camera chain
+       PANTILT,	      //!< PanTilt Camera
+       GOOSENECK,	  //!<GooseNeck
+       CRABARM,	  //!CrabArm
    };
    EnumRobotType robotType; //!< Robot type.
    int dof,                 //!< Degree of freedom.
@@ -389,8 +392,8 @@
    explicit Robot(const Matrix & initrobot);
    explicit Robot(const Matrix & initrobot, const Matrix & initmotor);
    Robot(const Robot & x);
-   explicit Robot(const string & filename, const string & robotName);
-   explicit Robot(const Config & robData, const string & robotName);
+   explicit Robot(const std::string & filename, const std::string & robotName);
+   explicit Robot(const Config & robData, const std::string & robotName);
    ~Robot(){}   //!< Destructor.
    Robot & operator=(const Robot & x);
    virtual void robotType_inv_kin();
@@ -405,6 +408,10 @@
    virtual ReturnMatrix inv_kin_puma(const Matrix & Tobj, bool & converge);
 
    virtual ReturnMatrix inv_kin_ers_pos(const ColumnVector & Pobj, const int endlink, const ColumnVector& Plink, bool & converge);
+   virtual ReturnMatrix inv_kin_pan_tilt(const ColumnVector & Pobj, bool & converge);
+   virtual ReturnMatrix inv_kin_goose_neck(const Matrix & Tobj);
+   virtual ReturnMatrix inv_kin_goose_neck_pos(const ColumnVector & Pobj);
+   virtual ReturnMatrix goose_neck_angles(const ColumnVector & Pobj, Real phi);
 
    virtual ReturnMatrix jacobian(const int ref=0)const { return jacobian(dof,ref); } //!< Jacobian of mobile links expressed at frame ref.
    virtual ReturnMatrix jacobian(const int endlink, const int ref)const;
@@ -451,8 +458,8 @@
    explicit mRobot(const Matrix & initrobot_motor);
    explicit mRobot(const Matrix & initrobot, const Matrix & initmotor);
    mRobot(const mRobot & x);
-   explicit mRobot(const string & filename, const string & robotName);
-   explicit mRobot(const Config & robData, const string & robotName);
+   explicit mRobot(const std::string & filename, const std::string & robotName);
+   explicit mRobot(const Config & robData, const std::string & robotName);
    ~mRobot(){}    //!< Destructor.
    mRobot & operator=(const mRobot & x);
    virtual void robotType_inv_kin();
@@ -504,8 +511,8 @@
    explicit mRobot_min_para(const Matrix & dhinit);
    explicit mRobot_min_para(const Matrix & initrobot, const Matrix & initmotor);
    mRobot_min_para(const mRobot_min_para & x);
-   explicit mRobot_min_para(const string & filename, const string & robotName);
-   explicit mRobot_min_para(const Config & robData, const string & robotName);
+   explicit mRobot_min_para(const std::string & filename, const std::string & robotName);
+   explicit mRobot_min_para(const Config & robData, const std::string & robotName);
    ~mRobot_min_para(){}    //!< Destructor.
    mRobot_min_para & operator=(const mRobot_min_para & x);
    virtual void robotType_inv_kin();
@@ -552,8 +559,11 @@
 bool ERS_Leg_DH(const Robot_basic *robot);
 bool ERS2xx_Head_DH(const Robot_basic *robot);
 bool ERS7_Head_DH(const Robot_basic *robot);
+bool PanTilt_DH(const Robot_basic *robot);
 bool Puma_mDH(const Robot_basic *robot);
 bool Rhino_mDH(const Robot_basic *robot);
+bool Goose_Neck_DH(const Robot_basic *robot);
+bool Crab_Arm_DH(const Robot_basic *robot);
 
 #ifdef use_namespace
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Motion/roboop/trajectory.cpp ./Motion/roboop/trajectory.cpp
--- ../Tekkotsu_3.0/Motion/roboop/trajectory.cpp	2005-07-25 23:22:08.000000000 -0400
+++ ./Motion/roboop/trajectory.cpp	2007-11-11 18:57:25.000000000 -0500
@@ -37,6 +37,9 @@
 */
 
 #include "trajectory.h"
+#include <fstream>
+
+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 <iomanip>
 
+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<const char*&>(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 <math.h>
+#ifndef PLATFORM_APERIOS
+typedef unsigned short word; //!< otherwise defined in Types.h
+#else
+#include <Types.h>
+#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 <map>
+#include <set>
+#include <string>
+#include <stdexcept>
+
 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<numOutputs ? outputs[i] : NULL; }
+		//! look up the name corresponding to an offset, returns NULL if not found/available
+		inline const char * getButtonName(unsigned int i) const { return i<numButtons ? buttons[i] : NULL; }
+		//! look up the name corresponding to an offset, returns NULL if not found/available
+		inline const char * getSensorName(unsigned int i) const { return i<numSensors ? sensors[i] : NULL; }
+		
+		//! Look up the offset corresponding to a output name, throws std::invalid_argument if not found
+		/*! Identical to findOutputOffset(), except throws an exception instead of returning an invalid value.
+		 *  Use this if you expect that the output is available, and want a noisy fail-fast if something's wrong (e.g. typo in name?) */
+		inline unsigned int getOutputOffset(const char* out) const { return lookupT("output",outputToIndex,out); }
+		//! look up the offset corresponding to a button name, throws std::invalid_argument if not found
+		/*! Identical to findButtonOffset(), except throws an exception instead of returning an invalid value.
+		 *  Use this if you expect that the output is available, and want a noisy fail-fast if something's wrong (e.g. typo in name?) */
+		inline unsigned int getButtonOffset(const char* but) const { return lookupT("button",buttonToIndex,but); }
+		//! look up the offset corresponding to a sensor name, throws std::invalid_argument if not found
+		/*! Identical to findSensorOffset(), except throws an exception instead of returning an invalid value.
+		 *  Use this if you expect that the output is available, and want a noisy fail-fast if something's wrong (e.g. typo in name?) */
+		inline unsigned int getSensorOffset(const char* sen) const { return lookupT("sensor",sensorToIndex,sen); }
+		
+		//! look up the offset corresponding to a output name, returns -1U if not found/available
+		/*! Identical to getOutputOffset(), except returns an invalid value instead of throwing an exception.
+		 *  Use this if you are testing to see if a capability exists, and don't want to incur exception handling if it isn't (say you're doing a lot of testing) */ 
+		inline unsigned int findOutputOffset(const char* out) const { return lookup(outputToIndex,out); }
+		//! look up the offset corresponding to a button name, returns -1U if not found/available
+		/*! Identical to getButtonOffset(), except returns an invalid value instead of throwing an exception.
+		 *  Use this if you are testing to see if a capability exists, and don't want to incur exception handling if it isn't (say you're doing a lot of testing) */ 
+		inline unsigned int findButtonOffset(const char* but) const { return lookup(buttonToIndex,but); }
+		//! look up the offset corresponding to a sensor name, returns -1U if not found/available
+		/*! Identical to getSensorOffset(), except returns an invalid value instead of throwing an exception.
+		 *  Use this if you are testing to see if a capability exists, and don't want to incur exception handling if it isn't (say you're doing a lot of testing) */ 
+		inline unsigned int findSensorOffset(const char* sen) const { return lookup(sensorToIndex,sen); }
+		
+		inline unsigned int getPIDJointOffset() const { return pidJointOffset; } //!< returns the offset of the block of 'PID' joints in an output array
+		inline unsigned int getNumPIDJoints() const { return numPIDJoints; } //!< returns the number of 'PID' joints
+		inline unsigned int getLEDOffset() const { return ledOffset; } //!< returns the offset of the block of LEDs in an output array
+		inline unsigned int getNumLEDs() const { return numLEDs; } //!< returns the number of LEDs
+		
+		//! returns the offsets of "fake" outputs, see #fakeOutputs
+		inline const std::set<unsigned int>& 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<std::string,unsigned int>& nameToIndex, const char * capname) const {
+			std::map<std::string,unsigned int>::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<std::string,unsigned int>& nameToIndex, const char * capname) const {
+			std::map<std::string,unsigned int>::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<std::string,unsigned int> outputToIndex; //!< maps output names to offset values
+		std::map<std::string,unsigned int> buttonToIndex; //!< maps button names to offset values
+		std::map<std::string,unsigned int> 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<unsigned int> 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<std::string, class Capabilities*>& 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 <stdio.h>
-#include <string>
+#include "Config.h"
+#include <libxml/xmlmemory.h>
+#include <libxml/parser.h>
+#include <iostream>
+#include <fstream>
+#include <cstdio>
+#include <cerrno>
 #include <cstring>
-#include <ctype.h>
-#include "Wireless/Socket.h"
+#include <cctype>
+#include <string>
 #ifdef PLATFORM_APERIOS
-#  include <OPENR/OPrimitiveControl.h>
 #  include <OPENR/OPENRAPI.h>
 #else
 #include <sys/param.h>
 #include <unistd.h>
-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="<?xml version";
+const char * Config::xmlIntro2="<!DOCTYPE ";
+const char * Config::xmlIntro3="<plist";
+
+const char * Config::transport_names[] = { "UDP", "TCP", "" };
+
+const char * Config::vision_config::dct_method_names[4] = { "islow", "ifast", "float", "" };
+const char * Config::vision_config::RawCamConfig::encoding_names[Config::vision_config::RawCamConfig::NUM_ENCODINGS+1] = { "color", "grayscale", "" };
+const char * Config::vision_config::RawCamConfig::compression_names[Config::vision_config::RawCamConfig::NUM_COMPRESSIONS+1] = { "none", "jpeg", "" };
+const char * Config::vision_config::SegCamConfig::compression_names[Config::vision_config::SegCamConfig::NUM_COMPRESSIONS+1] = { "none", "rle", "" };
+
+const char * Config::main_config::consoleModeNames[Config::main_config::NUM_CONSOLE_MODES+1] = { "controller", "textmsg", "auto", "" };
+
+bool ConfigDictionary::loadXMLNode(const std::string& key, xmlNode* val, const std::string& comment) {
+	// if not a model specific key, just load it normally
+	if(key.substr(0,msPrefix.size())!=msPrefix)
+		return plist::Dictionary::loadXMLNode(key,val,comment);
+	
+	//otherwise, strip off enumeration serial number (if any)
+	//std::string k=key.substr(0,key.find(msNum));
+	const std::string& k=key;
+	
+	//see if additional parameters in the key
+	if(k.size()<=msPrefix.size() || k.substr(msPrefix.size(),msSep.size())!=msSep) {
+		// not a valid model specific string, treat as normal key
+		return plist::Dictionary::loadXMLNode(key,val,comment);
+	}
+	
+	//prefix plus pattern (at least) -- check pattern
+	std::string::size_type patStart=msPrefix.size()+msSep.size();
+	std::string::size_type patEnd=k.find(msSep,patStart);
+	std::string pattern=k.substr(patStart,patEnd-patStart);
+	if(!matchNoCase(curModel,pattern))
+		return false; //doesn't apply to the current model
+	if(patEnd==std::string::npos) {
+		// prefix plus pattern only -- load subnodes
+		loadXML(val);
+		return true;
+	} else {
+		// prefix plus pattern plus single item -- load it
+		return plist::Dictionary::loadXMLNode(k.substr(patEnd+1),val,comment);
+	}
+}
+bool ConfigDictionary::saveOverXMLNode(xmlNode* k, xmlNode* val, const std::string& key, std::string comment, const std::string& indentStr, std::set<std::string>& 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<std::string>& 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; i<PIDJointOffset+NumPIDJoints; i++)
-					if(strncasecmp(&key[10],outputNames[i],outputNameLen+1)==0) { //+1 to ensure full match
-						motion.calibration[i-PIDJointOffset] = atof(value);
-						return &motion.calibration[i];
-					}
-						std::cout << "WARNING: Could not match '" << (strlen(key)>10?&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<plist::Primitive<float> >::const_iterator it = motion.calibration_scale.findEntry(keyval);
+			plist::Primitive<float>* prim = NULL;
+			if(it!=motion.calibration_scale.end())
+				prim = dynamic_cast<plist::Primitive<float> *>(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<plist::Collection*>(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<plist::PrimitiveBase*>(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<plist::ArrayBase::StringConversion*>(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<std::string> modelStack;
 	bool ignoring=false;
-	
-	std::vector<std::string> 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<len && (used=sscanf(&buf[numRead],"%255[^\n]\n", line))!=(unsigned int)EOF) {
+		numRead+=used;
+		parseLine(line,++lineno,modelStack,ignoring,section);
 	}
-#else
-#  if TGT_ERS7
-	char rdStr[]="ERS-7";
-#  elif TGT_ERS210
-	char rdStr[]="ERS-210";
-#  elif TGT_ERS220
-	char rdStr[]="ERS-220";
-#  elif TGT_ERS2xx
-#    warning "TGT_2xx is not specific for simulation purposes - defaulting to ERS210"
-	char rdStr[]="ERS-210";
-#  else
-#    warning "TGT_<model> 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; i<curmodel.size(); i++)
-					if(!matchNoCase(rdStr,curmodel[i])) {
-						ignoring=true;
-						break;
-					}
-						//printf("ignoring==%d\n",ignoring);
-						
-			} else {
-				curmodel.push_back(key);
-				//printf("entering section %s\n",curmodel.back().c_str());
-				ignoring=ignoring || !matchNoCase(rdStr,key);
-				//printf("ignoring==%d\n",ignoring);
-			}
-		} else if(!ignoring) {
-			if (sscanf(buf,"[%29[^]]]",key)>0) {
-				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<std::string> 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<std::string>& 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; i<modelStack.size(); i++)
+				if(!matchNoCase(curModel,modelStack[i])) {
+					ignoring=true;
+					break;
+				}
+					//printf("ignoring==%d\n",ignoring);
+					
+		} else {
+			modelStack.push_back(key);
+			//printf("entering section %s\n",modelStack.back().c_str());
+			ignoring=ignoring || !matchNoCase(curModel,key);
+			//printf("ignoring==%d\n",ignoring);
+		}
+	} else if(!ignoring) {
+		if (sscanf(buf,"[%29[^]]]",key)>0) {
+			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<plist::Collection*>(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 <vector>
-#include <string>
-#include "RobotInfo.h"
+#include "Shared/plist.h"
+#include "Shared/RobotInfo.h"
 extern "C" {
 #include <jpeglib.h>
 }
+#ifdef PLATFORM_APERIOS
+#  include <OPENR/OPrimitiveControl.h>
+#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 <vector>
+#include <string>
 
-//!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<std::string>& 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<typename T>
+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<numOutputsToStore; ++i)
+			addEntry(outputNames[i+firstOffset],outputs[i]);
+	}
+	//! strips trailing '~' characters from name before doing usual lookup
+	virtual ObjectBase& getEntry(const std::string& name) {
+		std::string::size_type n = name.find_last_not_of('~')+1;
+		return ConfigDictionary::getEntry((n==name.size()) ? name : name.substr(0,n));
+	}
+	//! return the value at position @a index, which must exist (no range checking)
+	T& getEntry(size_t index) { return outputs[index]; }
+	//! return the value at position @a index, which must exist (no range checking, equivalent to getEntry(index))
+	T& operator[](size_t index) { return outputs[index]; }
+	using ConfigDictionary::operator[];
+	
+	//! small trick -- override to save outputs in indexed order instead of alphabetical order
+	void saveXML(xmlNode* node, bool onlyOverwrite, std::set<std::string>& 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<T> 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<unsigned int> flash_bytes; //!< how many bytes of the IP to flash
+		plist::Primitive<bool> 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<int> 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<bool> seed_rng;     //!< if true, will call srand with timestamp data, mangled by current sensor data
+		plist::Primitive<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.
+		};
+		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_t> consoleMode; 
+		plist::Primitive<int> stderr_port;   //!< port to send error information to
+		plist::Primitive<int> wsjoints_port; //!< port to send joint positions on
+		plist::Primitive<int> wspids_port;   //!< port to send pid info on
+		plist::Primitive<int> headControl_port;	   //!< port for receiving head commands
+		plist::Primitive<int> walkControl_port;	   //!< port for receiving walk commands
+		plist::Primitive<int> estopControl_port;	   //!< port for receiving walk commands
+		plist::Primitive<int> stewart_port;  //!< port for running a stewart platform style of control
+		plist::Primitive<int> aibo3d_port;   //!< port for send/receive of joint positions from Aibo 3D GUI
+		plist::Primitive<int> wmmonitor_port; //!< port for monitoring Watchable Memory
+		plist::Primitive<bool> use_VT100;    //!< if true, enables VT100 console codes (currently only in Controller menus - 1.3)
+		plist::Primitive<unsigned int> 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<std::string> 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<int> gui_port;        //!< port to listen for the GUI to connect to aibo on
+		plist::Primitive<std::string> select_snd; //!< sound file to use for "select" action
+		plist::Primitive<std::string> next_snd;   //!< sound file to use for "next" action
+		plist::Primitive<std::string> prev_snd;   //!< sound file to use for "prev" action
+		plist::Primitive<std::string> read_snd;   //!< sound file to use for "read from std-in" action
+		plist::Primitive<std::string> cancel_snd; //!< sound file to use for "cancel" action
+		plist::Primitive<std::string> 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_levels> 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_levels> 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_speeds> shutter_speed; //!< slower shutter will brighten image, but increases motion blur
+		
+		plist::Primitive<int> 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<plist::Primitive<std::string> > thresh;      //!< threshold file names
+		plist::Primitive<std::string> colors;      //!< colors definition (.col) file
+		plist::Primitive<bool> restore_image;   //!< if true, replaces pixels holding image info with actual image pixels (as much as possible anyway)
+		plist::Primitive<bool> 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<J_DCT_METHOD> jpeg_dct_method;  //!< pick between dct methods for jpeg compression
+		plist::Primitive<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)
+		plist::Primitive<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)
+		plist::Primitive<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)
+		
+		//! 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<int> port;
+			plist::NamedEnumeration<Config::transports> transport;
+			plist::Primitive<unsigned int> 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_t> encoding; //!< holds whether to send color or single channel
+			plist::Primitive<int> 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_t> compression;//!< holds whether to send jpeg compression
+
+			plist::Primitive<int> compress_quality;//!< 0-100, compression quality (currently only used by jpeg)
+			plist::Primitive<int> y_skip;     //!< resolution level to transmit y channel at
+			plist::Primitive<int> 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<int> skip;       //!< resolution level to transmit segmented images at
+			plist::Primitive<int> 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_t> 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<int> 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<float> focal_len_x; //!< focal length of camera, in pixels, K11
+			plist::Primitive<float> focal_len_y; //!< focal length of camera, in pixels, K22
+			plist::Primitive<float> principle_point_x; //!< center of optical projection, K13
+			plist::Primitive<float> principle_point_y; //!< center of optical projection, K23
+			plist::Primitive<float> skew; //!< CCD skew, K12 = skew*focal_len_x
+			plist::Primitive<float> kc1_r2; //!< r-squared radial distortion
+			plist::Primitive<float> kc2_r4; //!< r to the 4 radial distortion
+			plist::Primitive<float> kc5_r6; //!< r to the 6 radial distortion
+			plist::Primitive<float> kc3_tan1; //!< first tangential correction term
+			plist::Primitive<float> kc4_tan2; //!< second tangential correctiont term
+			plist::Primitive<unsigned int> calibration_res_x; //!< x resolution of images used during calibration
+			plist::Primitive<unsigned int> 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;  //!<pointer back to the containing config object
-		std::string root;       //!< path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
-		std::string walk;       //!< the walk parameter file to load by default for new WalkMC's
-		std::string kinematics;  //!< the kinematics description file to load
-		std::vector<std::string> 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<NumPIDJoints; i++)
-				calibration[i]=1;
-		}
+		
+		Config* thisconfig;  //!<pointer back to the containing config object
+		plist::Primitive<std::string> root;       //!< path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
+		plist::Primitive<std::string> walk;       //!< the walk parameter file to load by default for new WalkMC's
+		plist::Primitive<std::string> kinematics;  //!< the kinematics description file to load
+		plist::ArrayOf<plist::Primitive<std::string> > kinematic_chains; //!< list of chain names to load from #kinematics
+		OutputConfig<plist::Primitive<float> > calibration_scale; //!< Multiplier from desired position to command for each PID joint, applied after calibration_offset.
+		OutputConfig<plist::Primitive<float> > 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<std::string> estop_on_snd;  //!< sound file to use when e-stop turned on
+		plist::Primitive<std::string> estop_off_snd; //!< sound file to use when e-stop turned off
+		plist::Primitive<float> max_head_tilt_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s
+		plist::Primitive<float> max_head_pan_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s
+		plist::Primitive<float> max_head_roll_speed; //!< max speed for the head joints, used by HeadPointerMC; rad/s
+		plist::Primitive<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
+		plist::Primitive<int> console_port;  //!< port to send/receive "console" information on (separate from system console)
+		plist::Primitive<int> stderr_port;   //!< port to send error information to
+#ifdef TGT_HAS_WHEELS
+		plist::Primitive<float> wheelBaseWidth; //!< distance between left and right wheel, in millimeters
+		plist::Primitive<float> 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;  //!<pointer back to the containing config object
-		std::string root;         //!< path to sound clips
-		unsigned int volume;      //!< volume in decibels - the value is interpreted as a signed short, where 0 is full volume, 0x8000 is mute
-		unsigned int sample_rate; //!< sample rate to send to system, currently only 8000 or 16000 supported
-		unsigned int sample_bits; //!< sample bit depth, either 8 or 16
-		std::vector<std::string> 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;  //!<pointer back to the containing config object
+		plist::Primitive<std::string> 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_levels> volume;      //!< volume in decibels - the value is interpreted as a signed short, where 0 is full volume, 0x8000 is mute
+		
+		plist::Primitive<unsigned int> sample_rate; //!< sample rate to send to system, currently only 8000 or 16000 supported
+		plist::Primitive<unsigned int> sample_bits; //!< sample bit depth, either 8 or 16
+		plist::ArrayOf<plist::Primitive<std::string> > preload; //!< list of sounds to preload at boot
+		plist::Primitive<float> 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<unsigned int> mic_port;        //!< port for streaming microphone samples
+			plist::Primitive<unsigned int> mic_sample_rate; //!< sample rate from the microphone
+			plist::Primitive<unsigned int> mic_sample_bits; //!< sample bit depth from the microphone (either 8 or 16)
+			plist::Primitive<bool> mic_stereo; //!< whether to stream stereo or mono from the microphone
+			
+			plist::Primitive<unsigned int> speaker_port;    //!< port for streaming speaker samples
+			plist::Primitive<unsigned int> speaker_frame_length; //!< length of frame sent to the speaker (ms)
+			plist::Primitive<unsigned int> 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<std::string>& 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<std::string>& 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<typename T>
+void OutputConfig<T>::saveXML(xmlNode* node, bool onlyOverwrite, std::set<std::string>& 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<outputs.size(); ++i) {
+			if(seen.find(outputNames[i+offset])==seen.end())
+				saveXMLNode(node,outputNames[i+offset],&outputs[i],indentStr);
+		}
+		std::string parentIndent;
+		if(indentStr.size()>=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 <cmath>
+#include <stdlib.h>
+#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 <b>not</b> 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 <math.h>
-#ifndef PLATFORM_APERIOS
-typedef unsigned short word; //!< otherwise defined in Types.h
-#else
-#include <Types.h>
-#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 <math.h>
-#ifndef PLATFORM_APERIOS
-typedef unsigned short word; //!< otherwise defined in Types.h
-#else
-#include <Types.h>
-#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 <math.h>
-#ifndef PLATFORM_APERIOS
-typedef unsigned short word; //!< otherwise defined in Types.h
-#else
-#include <Types.h>
-#endif
+#include "CommonERSInfo.h"
+#include "ERS210Info.h"
+#include "ERS220Info.h"
+#include <iostream>
 
-#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<TailOffset+NumTailJoints; ++i)
+					fakeOutputs.insert(i);
+				for(unsigned int i=MouthOffset; i<MouthOffset+NumMouthJoints; ++i)
+					fakeOutputs.insert(i);
+				fakeOutputs.insert(TlBluLEDOffset);
+				fakeOutputs.insert(TlRedLEDOffset);
+				for(unsigned int i=EarOffset; i<EarOffset+NumEarJoints; ++i)
+					fakeOutputs.insert(i);
+			} else {
+				std::cerr << "ERS2xxCapabilities running on unknown model!" << std::endl;
+			}
+#endif
+		}
+	};
+	//! allocation declared in RobotInfo.cc
+	extern ERS2xxCapabilities 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
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/ERS7Info.h ./Shared/ERS7Info.h
--- ../Tekkotsu_3.0/Shared/ERS7Info.h	2006-10-03 22:41:51.000000000 -0400
+++ ./Shared/ERS7Info.h	2007-11-09 14:01:14.000000000 -0500
@@ -2,15 +2,14 @@
 #ifndef INCLUDED_ERS7Info_h
 #define INCLUDED_ERS7Info_h
 
-#include <math.h>
-#ifndef PLATFORM_APERIOS
-typedef unsigned short word; //!< otherwise defined in Types.h
-#else
-#include <Types.h>
-#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 <code>1&lt;&lt;(fooLEDOffset-LEDOffset)</code>.
@@ -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<typename=void>
+struct FactoryInvalidT {
+	//! concrete class for not doing anything
+	template<class U> 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<class U> struct Factory;
+};
+//! implementation of concrete class for not doing anything
+template<class U> 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<class Base>
+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<class T> 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<class Base, class S1, S1 s1>
+struct Factory0Arg1Static : public Factory0Arg<Base> {
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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<class Base, class M1>
+struct Factory0Arg1Member : public Factory0Arg<Base> {
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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<class Base, class S1, S1 s1, class S2, S2 s2>
+struct Factory0Arg2Static : public Factory0Arg<Base> {
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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<class A1>
+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<class Base, class A1>
+struct Factory1Arg : public Factory1ArgBase<A1> {
+	//! 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<class T> 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<class Base, class A1, class S1, S1 s1>
+struct Factory1Arg1Static : public Factory1Arg<Base,A1> {
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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<class Base, class S1, S1 s1, class A1>
+struct Factory1Static1Arg : public Factory1Arg<Base,A1> {
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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<class Base, class A1>
+struct Factory0_1Arg : public virtual Factory0Arg<Base>, public virtual Factory1Arg<Base,A1> {
+	using Factory0Arg<Base>::operator();
+	using Factory1Arg<Base,A1>::operator();
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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<class Base, class S1, S1 s1, class A1>
+struct Factory1Static_1Arg : public Factory0_1Arg<Base,A1> {
+	//! concrete class for constructing products of a specified subtype of Base
+	template<class T> 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 <string>
+#include <map>
+#include <set>
+#include <iostream>
+
+//! 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<class FamilyT, typename NameT=std::string, class FactoryBaseT=Factory0Arg<FamilyT>, template<class U> 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<class T> struct FactoryType : FactoryT<T> {};
+	
+	//! 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<NameT>& 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<typename T> const NameT& registerType(const NameT& type) { return registerFactory(type,new FactoryT<T>); }
+	
+	//! 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<typename A1>
+	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<typename A1, typename A2>
+	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<typename A1, typename A2, typename A3>
+	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<NameT,FactoryBaseT*> factories_t;
+	factories_t factories; //!< storage for type identifier to factory mapping
+};
+
+template<class FamilyT, typename NameT, class FactoryBaseT, template<class U> class FactoryT>
+void FamilyFactory<FamilyT,NameT,FactoryBaseT,FactoryT>::getTypeNames(std::set<NameT>& types) const {
+	types.clear();
+	for(typename factories_t::const_iterator it=factories.begin(); it!=factories.end(); ++it)
+		types.insert(it->first);
+}
+
+template<class FamilyT, typename NameT, class FactoryBaseT, template<class U> class FactoryT>
+const NameT& FamilyFactory<FamilyT,NameT,FactoryBaseT,FactoryT>::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 FamilyT, typename NameT, class FactoryBaseT, template<class U> class FactoryT>
+FactoryBaseT* FamilyFactory<FamilyT,NameT,FactoryBaseT,FactoryT>::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 <sys/types.h>
+#include <sys/stat.h>
+#include <errno.h>
+#include <iostream>
+#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 <fcntl.h>
+#  include <errno.h>
+#  include <sys/types.h>
+#  include <sys/mman.h>
+#  include <sys/stat.h>
+#endif
+
+#include <png.h>
+extern "C" {
+#include <jpeglib.h>
+}
+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<char*>(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; i<remain; i++)
+			rows[i]=rows[i-1]+row_stride;
+		JSAMPROW* curpos=rows;
+		//JSAMPARRAY buffer = (*cinfo.mem->alloc_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<png_bytep>(data->Base()+FULL_HEADER_SIZE);
+		for(unsigned int h=1; h<height; ++h)
+			row_pointers[h]=row_pointers[h-1]+rowbytes;
+		png_read_image(png_ptr, row_pointers);*/
+		png_bytep row=reinterpret_cast<png_bytep>(outbuf);
+		for(unsigned int h=0; h<height; ++h) {
+			if(row+rowbytes>reinterpret_cast<png_bytep>(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<JOCTET*>(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(inbufSize<row_stride) {
+						cerr << "image_util ran out of input buffer during JPEG grayscale compression" << endl;
+						break;
+					}
+					for(unsigned int x=0; x<width; x++) // copy over a row into temporary space
+						row_pointer[0][x] = inbuf[x*inbufChannels];
+					jpeg_write_scanlines(&cinfo, row_pointer, 1); // pass that row to libjpeg
+					inbuf+=row_stride;
+					inbufSize-=row_stride;
+				}
+				jpeg_finish_compress(&cinfo);
+				delete [] row_pointer[0];
+				
+			} 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(yskip>uvskip) {
+						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<JSAMPROW>(reinterpret_cast<JSAMPLE*>(inbuf)) };
+				while (cinfo.next_scanline < cinfo.image_height) {
+					if(inbufSize<row_stride) {
+						cerr << "image_util ran out of input buffer during JPEG compression" << endl;
+						break;
+					}
+					jpeg_write_scanlines(&cinfo, row_pointer, 1);
+					row_pointer[0]+=row_stride;
+					inbufSize-=row_stride;
+				}
+				jpeg_finish_compress(&cinfo);
+			}
+			
+			// results
+			return jpeg_mem_size(&cinfo);
+		} catch(const std::exception& ex) {
+			std::cerr << "image_util Exception while compressing JPEG: " << ex.what() << std::endl; //really, can only be bad_alloc
+			jpeg_finish_compress(&cinfo);
+		}
+		return 0;
+	}
+
+	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) {
+		// check destination buffer
+		if(outbuf==NULL) {
+			outbufSize=width*height*outbufChannels;
+			outbuf=new char[outbufSize];
+		}
+		
+		// setup state structures
+		png_structp  png_ptr = png_create_write_struct(PNG_LIBPNG_VER_STRING, NULL, NULL, NULL);
+		if (!png_ptr) {
+			cerr << "image_util::encodePNG(): png_create_write_struct failed" << endl;
+			return 0;
+		}
+		png_infop  info_ptr = png_create_info_struct(png_ptr);
+		if (!info_ptr) {
+			png_destroy_write_struct(&png_ptr, NULL);
+			cerr << "image_util::encodePNG(): png_create_info_struct failed" << endl;
+			return 0;
+		}
+		
+		png_write_mem_status write_status;
+		write_status.buf=reinterpret_cast<png_byte*>(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<png_bytep>(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<png_bytep>(row+inbufSize);
+		for(unsigned int h=0; h<height; ++h) {
+			if(row+row_stride>endp) {
+				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 <string>
+
+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 <string>
+
+//! 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<class FamilyT, typename ClassNameT=std::string, class FactoryBaseT=Factory1Arg<FamilyT,std::string>, template<class U> class FactoryT=FactoryBaseT::template Factory>
+class InstanceTracker : public plist::Dictionary, protected FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT> {
+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<class T> struct FactoryType : FactoryT<T> {};
+	
+	//! constructor
+	InstanceTracker() : plist::Dictionary(), FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT>() {}
+	
+	using FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::getTypeNames;
+	using FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::getNumTypes;
+	using FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::registerType;
+	using FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::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<class T> 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<class T> 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<class T> 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<class T> 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 FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+template<class T>
+bool InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::registerInstance(const std::string& name, T& inst) {
+	if(findEntry(name)!=end())
+		return false; // already have instance by that name
+	plist::Dictionary* dinst=dynamic_cast<plist::Dictionary*>(&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 FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+template<class T>
+bool InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::registerInstance(const std::string& name, T* inst) {
+	if(findEntry(name)!=end())
+		return false; // already have instance by that name
+	plist::Dictionary* dinst=dynamic_cast<plist::Dictionary*>(inst);
+	if(dinst==NULL)
+		dinst=new InstanceEntry(inst); // create a wrapper for the non-Dictionary type
+	addEntry(name,dinst);
+	return true;
+}
+template<class FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+template<class T>
+bool InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::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<plist::Dictionary*>(&inst);
+	if(dinst!=NULL) {
+		if(type.size()>0)
+			dinst->addEntry(".type",new plist::Primitive<ClassNameT>(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<ClassNameT>(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 FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+template<class T>
+bool InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::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<plist::Dictionary*>(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<ClassNameT>(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 FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+FamilyT* InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::create(const ClassNameT& type, const std::string& name) {
+	if(findEntry(name)!=end())
+		return NULL; // already have instance by that name
+	FamilyT* inst=FamilyFactory<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::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 FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+FamilyT* InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::getInstance(const std::string& name) {
+	const_iterator it=findEntry(name);
+	if(it==end())
+		return NULL; // doesn't exit
+	if(InstanceEntry* inst=dynamic_cast<InstanceEntry*>(it->second))
+		return &inst->instance; // was a wrapper because FamilyT isn't a Dictionary, extract actual instance
+	return dynamic_cast<FamilyT*>(it->second); // otherwise this is our instance right here
+}
+
+template<class FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+bool InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::destroy(const std::string& name) {
+	const_iterator it=findEntry(name);
+	if(it==end())
+		return false;
+	removeEntry(name);
+	return true;
+}		
+
+template<class FamilyT, typename ClassNameT, class FactoryBaseT, template<class U> class FactoryT>
+void InstanceTracker<FamilyT,ClassNameT,FactoryBaseT,FactoryT>::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<plist::Dictionary*>(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<plist::Dictionary*>(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 <sys/param.h>
 #include <stdexcept>
 #include <stdarg.h>
-#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<unsigned long long>(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<void*>(tmp); return used; }
 	
-	inline static unsigned int encode(const std::string& x, char buf[], unsigned int cap) throw() { if(cap<sizeof(unsigned int)+x.size()+1) return 0; memcpy(buf+encode(x.size(),buf,cap),x.c_str(),x.size()+1); return x.size()+stringpad; }
+	inline static unsigned int encode(const std::string& x, char buf[], unsigned int cap) throw() { if(cap<sizeof(unsigned int)+x.size()+1) return 0; memcpy(buf+encode(static_cast<unsigned int>(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<sizeof(unsigned int)) return 0; unsigned int sz=0; decode(sz,buf,cap); if(cap<sizeof(unsigned int)+sz+1) return 0; x.assign(buf+sizeof(unsigned int),sz); return x.size()+stringpad; }
-	inline static unsigned int encode(const std::string& x, FILE* f) throw()                 { encode(x.size(),f); return sizeof(unsigned int)+fwrite(x.c_str(),1,sizeof(x)+1,f); }
+	inline static unsigned int encode(const std::string& x, FILE* f) throw()                 { encode(static_cast<unsigned int>(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<sizeof(unsigned int)+sz+1) return 0; memcpy(buf+encode(sz,buf,cap),x,sz+1); return sz+stringpad; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/LocalizationParticle.h ./Shared/LocalizationParticle.h
--- ../Tekkotsu_3.0/Shared/LocalizationParticle.h	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/LocalizationParticle.h	2007-03-02 18:59:20.000000000 -0500
@@ -0,0 +1,105 @@
+#ifndef INCLUDED_LocalizationParticle_h
+#define INCLUDED_LocalizationParticle_h
+
+#include "ParticleFilter.h"
+#include "Shared/Measures.h"
+#include "zignor.h"
+#include <iostream>
+#include <cmath>
+
+template<typename ParticleT> 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<LocalizationParticle> 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<typename ParticleT> float sumSqErr(const ParticleT& lp) const {
+		//const LocalizationParticle& lp = static_cast<const LocalizationParticle&>(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<typename ParticleT>
+class LocalizationParticleDistributionPolicy : public ParticleFilter<ParticleT>::DistributionPolicy {
+public:
+	typedef ParticleT particle_type;  //!< just for convenience
+	typedef typename ParticleFilter<ParticleT>::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 <cmath>
+#include <cstdlib>
+#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 <b>not</b> 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 <cmath>
+
+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 <vector>
+#include <algorithm>
+#include <iostream>
+#include <cfloat>
+#include <cmath>
+
+//! 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<typename ParticleT> 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<typename ParticleT>
+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_type> 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_type> 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_type> 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_type> 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_type> 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<LowVarianceResamplingPolicy*>(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<LowVarianceResamplingPolicy*>(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<LowVarianceResamplingPolicy*>(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<LowVarianceResamplingPolicy*>(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<particle_type*> sorted(particles.size());
+			for(unsigned int i=0; i<particles.size(); ++i)
+				sorted[i]=&particles[i];
+			std::sort(sorted.begin(),sorted.end(),weightLess);
+			particle_collection newParticles;
+			newParticles.reserve(numParticles);
+			for(unsigned int i=sorted.size()-numParticles-1; i<sorted.size(); ++i)
+				newParticles.push_back(*sorted[i]);
+			particles.swap(newParticles);
+		}
+	}
+	
+protected:
+	//!< used for sorting particles in resizeParticles() to drop the least weighted particles first
+	static bool weightLess(const particle_type* a, const particle_type* b) { return a->weight < 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<typename ParticleT>
+void ParticleFilter<ParticleT>::LowVarianceResamplingPolicy::resample(particle_collection& particles, index_t& bestIndex) {
+	if(resampleCount++<resampleDelay)
+		return;
+	resampleCount=0;
+	//std::cerr << "RESAMPLE UNDERWAY" << std::endl;
+	//std::cerr << "Best particle is " << bestIndex << " @ " << particles[bestIndex].weight << std::endl;
+	
+	// we reuse newParticles each time, doing an STL O(1) swap to quickly exchange contents
+	// have to make sure it's still the right size though...
+	if(newParticles.size()<particles.size() || newParticles.size()>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(bestWeight<min) {
+				redistributeRatio = (bestWeight-min)/min;
+				if(redistributeRatio>1)
+					redistributeRatio=1;
+			}
+		}
+	} else {
+		if(bestWeight<=0)
+			redistributeRatio=1;
+		else {
+			float min=std::pow(minAcceptableWeight,(float)(resampleDelay+1));
+			if(bestWeight<min)
+				redistributeRatio = (1-bestWeight/min);
+		}
+	}
+	unsigned int numRedistribute = (unsigned int)(particles.size() * redistributeRatio * maxRedistribute);
+	
+	
+	// now do resampling, writing into newParticles
+	const unsigned int numResample=newParticles.size()-numRedistribute;
+	//std::cerr << "best " << bestIndex << " @ " << bestWeight << " numRedist. " << numRedistribute << " of " << particles.size() << std::endl;
+	bestIndex=0;
+	if(numResample>0) {
+		// add up the cumulative weights for each particle...
+		std::vector<float> 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 <cmath>
+#include <stdlib.h>
+#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 <b>not</b> 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 <cmath>
+#include <stdlib.h>
+#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 <b>not</b> 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 <stdlib.h>
+#include <cmath>
+#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; //!<Left and Right Wheels
+	
+	const unsigned JointsPerArm   =  6;//!< Base, Shoulder, Elbow, Wrist (Yaw, Roll), Gripper
+	const unsigned NumArms        =  1;
+	const unsigned NumArmJoints   =  JointsPerArm*NumArms;
+	
+	const unsigned JointsPerLeg   =  0; 
+	const unsigned NumLegs        =  0; 
+	const unsigned NumLegJoints   =  JointsPerLeg*NumLegs;
+	const unsigned NumHeadJoints  =  4;   // Goose neck
+	const unsigned NumTailJoints  =  0; 
+	const unsigned NumMouthJoints =  0; 
+	const unsigned NumEarJoints   =  0; 
+	const unsigned NumButtons     =  0; 
+	const unsigned NumSensors     =  0;  
+	const unsigned NumLEDs        =  0; 
+	const unsigned NumFacePanelLEDs = 0; 
+	
+	const unsigned NumPIDJoints   = NumWheels+NumArmJoints+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 NumOutputs     = NumPIDJoints + NumBinJoints + 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; //!< beginning of wheel velocities, don't need to add anything, just use WheelOffset_t entries directly
+	const unsigned ArmOffset   = WheelOffset+NumWheels;  //!< beginning of arm joints, don't add anything, just use ArmOffset_t entries directly
+	const unsigned HeadOffset  = ArmOffset+NumArmJoints;   //!< 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 BinJointOffset = LEDOffset + NumLEDs;   //!< The beginning of the binary joints
+	const unsigned EarOffset   = BinJointOffset;           //!< the offset of the beginning of the ear joints - note that ears aren't sensed.  They can be flicked by the environment and you won't know.
+
+	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 (add appropriate LegOrder_t to specify which paw)
+	const unsigned CameraFrameOffset = GripperFrameOffset+NumArms; //!< Use with kinematics to refer to camera reference frame
+
+	enum WheelOffset_t {
+		LWheelOffset=WheelOffset,
+		RWheelOffset
+	};
+	
+	//! these are all 'absolute' offsets -- no need to add to HeadOffset
+	enum HeadOffset_t {
+		HeadBaseOffset = HeadOffset,
+		HeadPanOffset = HeadBaseOffset, // alias HeadPanOffset
+		HeadShoulderOffset,
+		HeadElbowOffset,
+		HeadTiltOffset = HeadElbowOffset, // alias HeadTiltOffset
+		HeadWristOffset,
+		HeadNodOffset = HeadWristOffset // alias HeadNodOffset
+	};
+	
+	//! these are the traditional sub-offsets, relative to HeadOffset
+	enum TPROffset_t {
+		PanOffset = HeadBaseOffset - HeadOffset, //!< pan/heading (horizontal)
+		TiltOffset = HeadElbowOffset - HeadOffset, //!< tilt/elevation (vertical)
+		NodOffset = HeadWristOffset - HeadOffset //!< replicated tilt (could be left undefined instead...)
+	};
+	
+	enum ArmOffset_t {
+		ArmBaseOffset = ArmOffset,
+		ArmShoulderOffset,
+		ArmElbowOffset,
+		ArmWristOffset,
+		ArmWristRotateOffset,
+		ArmGripperOffset
+	};
+
+	enum LEDOffset_t { };
+	
+	typedef unsigned int LEDBitMask_t;
+	
+	const LEDBitMask_t FaceLEDMask = 0;
+	
+	const LEDBitMask_t AllLEDMask  = (LEDBitMask_t)~0;
+	
+	enum ButtonOffset_t { };
+	
+	const char* const buttonNames[NumButtons + 1] = { NULL };
+	
+	enum SensorOffset_t { };
+	
+	const char* const sensorNames[NumSensors + 1] = { NULL };
+	
+	//! Names for each of the outputs
+	const char* const outputNames[NumOutputs] = {
+		"WHEEL:L",
+		"WHEEL:R",
+		"Arm:Base","Arm:Shldr","Arm:Elbow","Arm:Yaw","Arm:Roll","Arm:Grpr",
+		"GNk:Pan","GNk:Shldr","GNk:Elbow","GNk:Pitch",
+	};
+
+	//! provides polymorphic robot capability detection/mapping
+	class Regis1Capabilities : public Capabilities {
+	public:
+		//! constructor
+		Regis1Capabilities()
+		: Capabilities(TargetName,NumOutputs,outputNames,NumButtons,buttonNames,NumSensors,sensorNames,PIDJointOffset,NumPIDJoints,LEDOffset,NumLEDs)
+		{
+			// alias neck joints
+			outputToIndex["NECK:tilt"]=HeadTiltOffset;
+			outputToIndex["NECK:pan"]=HeadPanOffset;
+			outputToIndex["NECK:nod"]=HeadNodOffset;
+		}
+	};
+	//! allocation declared in RobotInfo.cc
+	extern Regis1Capabilities capabilities;
+	
+	const float DefaultPIDs[NumPIDJoints][3] = {
+		{1,0,0},
+		{1,0,0},
+		{1,0,0},{1,0,0},{1,0,0},{1,0,0},{1,0,0},{1,0,0},
+		{1,0,0},{1,0,0},{1,0,0},{1,0,0}
+	};
+	
+	//! haven't determined safe speeds for regis yet
+	const float MaxOutputSpeed[NumOutputs] = {
+		1e-3,
+		1e-3,
+		1e-3,1e-3,1e-3,1e-3,1e-3,1e-3,
+		1e-3,1e-3,1e-3,1e-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
+	
+	//! the range that can be reached by the joint controller (i.e. the domain of the output commands)
+	const double outputRanges[NumOutputs][2] = {
+			{ -1 , 1 },//Wheels
+			{ -1 , 1 },
+			{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) }, //Arm
+			{ RAD(-100),RAD(100) },{ RAD(-10.0),RAD(190.0) },{ RAD(-140),RAD(60) },{ RAD(-150),RAD(50) }//Goose Neck
+	};
+	
+	//! the range that can be reached by external interaction (i.e. the domain of the output feedback)
+	/*! This is probably identical to #outputRanges, but may differ if the outputs have some built-in safety margin... */
+	const double mechanicalLimits[NumOutputs][2] = {
+			{ -1 , 1 },//Wheels
+			{ -1 , 1 },
+			{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) },{ RAD(-90),RAD(90) }, //Arm
+			{ RAD(-100),RAD(100) },{ RAD(-10.0),RAD(190.0) },{ RAD(-140),RAD(60) },{ RAD(-150),RAD(50) }//Goose Neck
+	};
+
+		
+#ifdef __RI_RAD_FLAG
+#undef RAD
+#undef __RI_RAD_FLAG
+#endif
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/RemoteState.cc ./Shared/RemoteState.cc
--- ../Tekkotsu_3.0/Shared/RemoteState.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./Shared/RemoteState.cc	2007-10-16 13:37:21.000000000 -0400
@@ -0,0 +1,53 @@
+#include "Shared/RemoteState.h"
+#include "Events/RemoteRouter.h"
+#include "Events/EventRouter.h"
+#include "Events/DataEvent.h"
+
+const int RemoteState::sizes[] = {
+    NumOutputs*sizeof(float),
+	NumButtons*sizeof(float),
+	NumSensors*sizeof(float),
+};
+
+RemoteState::RemoteState(const RemoteRouter *p) : parent(p) {
+    unsigned int i = 0;
+    for (i = 0; i < NumOutputs; i++)
+        outputs[i] = 0.0;
+}
+
+RemoteState::~RemoteState() {
+
+}
+
+void RemoteState::update(char *data) {
+    //Get the type of the data, a StateType
+    StateType t = *(StateType *)data;
+    data += sizeof(StateType);
+
+    //Get the size of the data, an int
+    int size = *(int *)data / sizeof(float);
+    data += sizeof(int);
+
+    //Set up the source and destination arrays
+    float *src = (float *)data;
+    float *dest;
+    
+    switch (t) {
+    case OutputState:
+        dest = outputs;
+        break;
+    default:
+        return;
+    }
+
+    //Copy the values
+    int i;
+    for (i = 0; i < size; i++)
+        dest[i] = src[i];
+
+    //Post the event
+	DataEvent<const RemoteState *> 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 <vector>
+
+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 <iostream>
+
+#if defined(TGT_ERS2xx) && defined(PLATFORM_APERIOS)
+#  include <OPENR/OPENRAPI.h>
+#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<numOutputs; ++i)
+			outputToIndex[outputs[i]]=i;
+		for(size_t i=0; i<numButtons; ++i)
+			buttonToIndex[buttons[i]]=i;
+		for(size_t i=0; i<numSensors; ++i)
+			sensorToIndex[sensors[i]]=i;
+		
+		std::map<std::string, class Capabilities*>::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<std::string, class Capabilities*>& Capabilities::getCaps() {
+		static std::map<std::string, class Capabilities*> 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 <map>
+#include <string>
+
+// 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_<model> 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_<model> 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<std::string, class Capabilities*>& caps = Capabilities::getCaps();
+		std::map<std::string, class Capabilities*>::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<size_t*>(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<size_t*>(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<size_t>(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 <OPENR/core_macro.h>
@@ -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: "<<robotDesignStr<<"\nDoing the best I can by assuming ERS-7..."<<endl;
-			robotDesign=ERS7Mask;
-		}
-	}
-#else
-	//This is only compiled if we're targeting the local platform
-	//In other words, if target model is an AIBO, simulation mode
-# if TGT_ERS220
-	robotDesign=ERS220Mask;
-# elif TGT_ERS210
-	robotDesign=ERS210Mask;
-# elif TGT_ERS2xx
-#   warning "TGT_ERS2xx can't be determined on non-Aperios - defaulting to TGT_ERS210"
-	robotDesign=ERS210Mask;
-# elif TGT_ERS7
-	robotDesign=ERS7Mask;
-# else
-#		warning "TGT_<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; i<PowerSourceID::NumPowerSIDs; i++)
+		for(unsigned int i=0; i<PowerSrcID::NumPowerSIDs; i++)
 			powerFlags[i]=lastState->powerFlags[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; i<evtBuf.size(); i++)
-		er->postEvent(evtBuf[i]);
-	
 	
 	//Apply sensor calibrations (currently only joint positions - perhaps IR as well?)
+	/*
 	for(unsigned int i=0; i<NumPIDJoints; i++)
 		outputs[PIDJointOffset+i]*=config->motion.calibration[i];
+	*/
+	applyCalibration();
+
+	for(unsigned int i=0; i<evtBuf.size(); i++)
+		er->postEvent(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; i<PowerSourceID::NumPowerSIDs; i++) {
+	for(unsigned int i=0; i<PowerSrcID::NumPowerSIDs; i++) {
 		if(actmasks[i]) { //now on
 			if(!powerFlags[i]) //was off: activation
 				er->postEvent(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; i<NumOutputs; i++)
-		if(pose(i).weight>0)
-			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; i<NumOutputs; i++) {
+			if (pose(i).weight>0) {
+				if (i>=PIDJointOffset && i<PIDJointOffset+NumPIDJoints) {
+					outputs[i] = pose(i).value / (config->motion.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; i<NumOutputs; i++) {
+			if(pose(i).weight>0) {
+				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; i<PowerSourceID::NumPowerSIDs; i++)
+		for(unsigned int i=0; i<PowerSrcID::NumPowerSIDs; i++)
 			powerFlags[i]=lastState->powerFlags[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; i<evtBuf.size(); i++)
 		er->postEvent(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; i<PIDJointOffset+NumPIDJoints; i++) {
+		outputs[i] = (outputs[i]/ (config->motion.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 <OPENR/core_macro.h>
 #include <OPENR/ObjcommTypes.h>
 #include <OPENR/OPENR.h>
@@ -15,6 +14,7 @@
 
 #include "Shared/RobotInfo.h"
 #include "Events/EventBase.h"
+#include "IPC/ProcessID.h"
 #include <math.h>
 #include <vector>
 
@@ -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<ProcessID::NumProcesses; ++i) ws[i]=NULL; } //!< constructor
+	WorldState*& operator->() { 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<EventBase>& 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="<<motionOverride << endl;
 	
 	static UpdateInfo info; // avoiding heap allocation by using static here, but this means not threadsafe (shouldn't be a problem...)
-	info.payload=LoadFileThread::deserializeHeader(msg.Base(),msg.Size(),&info.verbose,&info.frameNumber,&info.filename,&info.dataInQueue,&info.payloadSize);
+	info.payload=LoadDataThread::deserializeHeader(msg.Base(),msg.Size(),&info.verbose,&info.frameNumber,&info.filename,&info.dataInQueue,&info.payloadSize);
 	if(info.payload==NULL)
 		throw std::runtime_error("deserialization of sensor update header failed");
 	if(info.frameNumber<curFrameNumber) {
@@ -135,15 +136,13 @@
 #endif
 	if(toUse==-1U)
 		return NULL; //error occurred, should already be reported
-	if(info.verbose) {
-		if(info.payloadSize==0)
-			cout << ProcessID::getIDStr() << " received sensor heartbeat at " << get_time() << endl;
-		else
-			cout << ProcessID::getIDStr() << " received sensor data \"" << info.filename << "\" at " << get_time() << endl;
-	}
+	if(info.verbose>=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; i<NumPIDJoints; i++)
+				state->outputs[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; i<NumOutputs; ++i)
-					ASSERT(pose(i).weight>0,"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; i<NumOutputs; ++i)
+				//ASSERT(pose(i).weight>0,"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; i<NumPIDJoints; ++i)
 						if(!isZeroPID(wsw.src,i))
 							pose(i+PIDJointOffset)=feedback->getOutputCmd(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; i<NumPIDJoints; ++i)
 						if(!isZeroPID(wsw.src,i))
 							pose(i+PIDJointOffset).weight=0; // don't apply sensor values to non-zero pids (this will come from feedback later)
-						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");*/
 				}
 			}
 		}
 		state->read(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<unsigned int>(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 && i<PIDJointOffset+NumPIDJoints && s->pids[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 <MCOOP.h>
 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<unsigned int>(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 <jpeglib.h> 
+#include <jerror.h> 
+
+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 <istream>
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+#include <jpeglib.h>
+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 <jpeglib.h>
 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 <math.h>
 
+//! a variety of handy mathematical functions, many of which are templated
 namespace mathutils {
-  template <class num>
-  inline num squareDistance(num x1, num ya, num x2, num yb) {
-    return (x1-x2)*(x1-x2)+(ya-yb)*(ya-yb);
-  }
-
-  template <class num>
-  inline num distance(num x1, num ya, num x2, num yb) {
-    return sqrt(squareDistance(x1, ya, x2, yb));
-  }
-
-  template <class num>
-  inline num limitRange(num n, num low, num high) {
-    if (n<low) n=low;
-    if (n>high) n=high;
-    return n;
-  }
-
-  template <class num>
-  inline num squared(num n) {
-    return n*n;
-  }
-
-  template <class num>
-  inline num abs_t(num n) {
-    return (n>-n)?n:-n;
-  }
-
+	//! euclidean distance of two points (squared), see distance()
+	template <class num>
+	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 <class num>
+	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 <class num>
+	inline num limitRange(num n, num low, num high) {
+		if (n<low) n=low;
+		if (n>high) n=high;
+		return n;
+	}
+	
+	//! returns n*n;
+	template <class num>
+	inline num squared(num n) {
+		return n*n;
+	}
+	
+	//! returns the maximum of n or -n
+	template <class num>
+	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 <class num>
 	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 <class num>
-  inline num deg2rad(num x) {
-    return x*M_PI/180;
-  }
-
-  template <class num>
-  inline num rad2deg(num x) {
-    return x*180/M_PI;
-  }
-
+	
+	//! converts from degrees to radians
+	template <class num>
+	inline num deg2rad(num x) {
+		return x*M_PI/180;
+	}
+	
+	//! converts from radians to degrees
+	template <class num>
+	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 <fstream>
    #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 <iomanip>
 
+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 <iomanip>
 
+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 <limits>
+#include <cmath>
 #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<Real>::digits10 ; }
+      { return std::numeric_limits<Real>::digits10 ; }
 
    static Real Epsilon()         // smallest number such that 1+Eps!=Eps
-      { return numeric_limits<Real>::epsilon(); }
+      { return std::numeric_limits<Real>::epsilon(); }
 
    static int Mantissa()         // bits in mantisa
-      { return numeric_limits<Real>::digits; }
+      { return std::numeric_limits<Real>::digits; }
 
    static Real Maximum()         // maximum value
-      { return numeric_limits<Real>::max(); }
+      { return std::numeric_limits<Real>::max(); }
 
    static int MaximumDecimalExponent()  // maximum decimal exponent
-      { return numeric_limits<Real>::max_exponent10; }
+      { return std::numeric_limits<Real>::max_exponent10; }
 
    static int MaximumExponent()  // maximum binary exponent
-      { return numeric_limits<Real>::max_exponent; }
+      { return std::numeric_limits<Real>::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<Real>::min(); } 
+      { return std::numeric_limits<Real>::min(); } 
 
    static int MinimumDecimalExponent() // minimum decimal exponent
-      { return numeric_limits<Real>::min_exponent10; }
+      { return std::numeric_limits<Real>::min_exponent10; }
 
    static int MinimumExponent()  // minimum binary exponent
-      { return numeric_limits<Real>::min_exponent; }
+      { return std::numeric_limits<Real>::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<Real>::radix; }
+      { return std::numeric_limits<Real>::radix; }
 
    static int Rounds()           // addition rounding (1 = does round)
    {
-	  return numeric_limits<Real>::round_style ==
-		 round_to_nearest ? 1 : 0;
+	  return std::numeric_limits<Real>::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<double>;
-		else if(ObjectBase::xNodeHasName(node,"integer")==0)
+		else if(ObjectBase::xNodeHasName(node,"integer"))
 			obj=new Primitive<long>;
-		else if(ObjectBase::xNodeHasName(node,"string")==0)
+		else if(ObjectBase::xNodeHasName(node,"string"))
 			obj=new Primitive<std::string>;
-		else if(ObjectBase::xNodeHasName(node,"true")==0)
+		else if(ObjectBase::xNodeHasName(node,"true"))
 			obj=new Primitive<bool>;
-		else if(ObjectBase::xNodeHasName(node,"false")==0)
+		else if(ObjectBase::xNodeHasName(node,"false"))
 			obj=new Primitive<bool>;
 		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<T> 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<T> (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 <libxml/xmlmemory.h>
 #include <libxml/parser.h>
 
@@ -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<std::string>& v) { *this = static_cast<const PrimitiveBase&>(v); return *this; }
+	PrimitiveBase& PrimitiveBase::operator=(const std::string& v) { *this=static_cast<const PrimitiveBase&>(Primitive<std::string>(v)); return *this; }
+	PrimitiveBase& PrimitiveBase::operator=(long v) { *this=Primitive<long>(v); return *this; }
+	PrimitiveBase& PrimitiveBase::operator=(unsigned long v) { *this=Primitive<unsigned long>(v); return *this; }
+	PrimitiveBase& PrimitiveBase::operator=(double v) { *this=Primitive<double>(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<PrimitiveListener*>;
-			primitiveListeners->push_back(vl);
+				primitiveListeners=new std::set<PrimitiveListener*>;
+			primitiveListeners->insert(vl);
 		}
 	}
 	void PrimitiveBase::removePrimitiveListener(PrimitiveListener* vl) {
 		if(primitiveListeners==NULL)
 			return;
-		std::list<PrimitiveListener*>::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl);
+		std::set<PrimitiveListener*>::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<PrimitiveListener*>::iterator it=find(primitiveListeners->begin(),primitiveListeners->end(),vl);
+		std::set<PrimitiveListener*>::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<PrimitiveListener*>::const_iterator it=primitiveListeners->begin();
-		while(it!=primitiveListeners->end()) {
-			std::list<PrimitiveListener*>::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<PrimitiveListener*> pls=*primitiveListeners;
+		if(touchOnly) {
+			for(std::set<PrimitiveListener*>::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<PrimitiveListener*>::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 <iostream>
 #include <iomanip>
 #include <sstream>
-#include <list>
+#include <set>
+#include <cctype>
 
 /*
- From: <!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+ From: <!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
  
  <!ENTITY % plistObject "(array | data | date | dict | real | integer | string | true | false )" >
  <!ELEMENT plist %plistObject;>
@@ -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<TEMPL> TYPE* TYPE::clone() const { return RETVAL; }
+#    define PLIST_CLONE_IMPT(TEMPL,TYPE,RETVAL)		template<typename TEMPL> TYPE<TEMPL>* TYPE<TEMPL>::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<typename TEMPL1,typename TEMPL2> TYPE<TEMPL1,TEMPL2>* TYPE<TEMPL1,TEMPL2>::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<typename U, typename V> struct conversion_policy { typedef typename U::template WrapValueConversion<V> 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<typename T> 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<bool>() const { return toLong(); }
+	template<> inline char ObjectBase::to<char>() const { return toLong(); }
+	template<> inline unsigned char ObjectBase::to<unsigned char>() const { return toLong(); }
+	template<> inline short ObjectBase::to<short>() const { return toLong(); }
+	template<> inline unsigned short ObjectBase::to<unsigned short>() const { return toLong(); }
+	template<> inline int ObjectBase::to<int>() const { return toLong(); }
+	template<> inline unsigned int ObjectBase::to<unsigned int>() const { return toLong(); }
+	template<> inline long ObjectBase::to<long>() const { return toLong(); }
+	template<> inline unsigned long ObjectBase::to<unsigned long>() const { return toLong(); }
+	template<> inline long long ObjectBase::to<long long>() const { return toLong(); }
+	template<> inline unsigned long long ObjectBase::to<unsigned long long>() const { return toLong(); }
+	template<> inline float ObjectBase::to<float>() const { return toDouble(); }
+	template<> inline double ObjectBase::to<double>() const { return toDouble(); }
+	template<> inline const char* ObjectBase::to<const char*>() const { return toString().c_str(); }
+	template<> inline std::string ObjectBase::to<std::string>() const { return toString(); }
+	/// @endcond
+	
+	template<typename T> class Primitive; // forward declaration so we can solve string/Primitive<string> 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<string>, solely to resolve ambiguity with this type between operator=(PrimitiveBase) and operator=(std::string)
+		PrimitiveBase& operator=(const Primitive<std::string>& 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<const PrimitiveBase&>(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<PrimitiveListener*>* primitiveListeners;
+		std::set<PrimitiveListener*>* 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<CollectionListener*>;
-			collectionListeners->push_back(l);
+				collectionListeners=new std::set<CollectionListener*>;
+			collectionListeners->insert(l);
 		}
 	}
 		
-	void Collection::removeCollectionListener(CollectionListener* l) {
+	void Collection::removeCollectionListener(CollectionListener* l) const {
 		if(collectionListeners==NULL)
 			return;
-		std::list<CollectionListener*>::iterator it=find(collectionListeners->begin(),collectionListeners->end(),l);
+		std::set<CollectionListener*>::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<CollectionListener*>::iterator it=find(collectionListeners->begin(),collectionListeners->end(),l);
+		std::set<CollectionListener*>::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<CollectionListener*>::iterator it=collectionListeners->begin();
-		while(it!=collectionListeners->end()) {
-			std::list<CollectionListener*>::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<CollectionListener*> pls=*collectionListeners;
+		for(std::set<CollectionListener*>::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<CollectionListener*>::iterator it=collectionListeners->begin();
-		while(it!=collectionListeners->end()) {
-			std::list<CollectionListener*>::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<CollectionListener*> pls=*collectionListeners;
+		for(std::set<CollectionListener*>::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<CollectionListener*>::iterator it=collectionListeners->begin();
-		while(it!=collectionListeners->end()) {
-			std::list<CollectionListener*>::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<CollectionListener*> pls=*collectionListeners;
+		for(std::set<CollectionListener*>::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 ("<<name<<","<<val<<") conflicted with previous entry ("<<name<<","<<(it->second)<<")"<<endl;
-				cerr << "         (use setEntry(...,false) if you expect you might need to overwrite)" << endl;
-			}
-			removeEntry(name);
-			//fall through to add new val
-		} 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<Collection*>(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 ("<<name<<","<<val<<") conflicted with previous entry ("<<name<<","<<(it->second)<<")"<<endl;
-				cerr << "         (use setEntry() if you expect you might need to overwrite)" << endl;
-			}
-			removeEntry(name);
-			//fall through to add new val
-		} 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<Collection*>(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 ("<<name<<","<<val<<") conflicted with previous entry ("<<name<<","<<(it->second)<<")"<<endl;
-				cerr << "         (use setEntry(...,false) if you expect you might need to overwrite)" << endl;
-			}
-			removeEntry(name);
-			//fall through to add new val
-		} 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<Collection*>(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 ("<<name<<","<<val<<") conflicted with previous entry ("<<name<<","<<(it->second)<<")"<<endl;
-				cerr << "         (use setEntry() if you expect you might need to overwrite)" << endl;
-			}
-			removeEntry(name);
-			//fall through to add new val
+	
+	bool DictionaryBase::renameEntry(const std::string& oldname, const std::string& newname) {
+		storage_t::iterator oit=dict.find(oldname);
+		if(oit==dict.end())
+			return false;
+		
+		// check for previous inhabitant of the new name
+		storage_t::iterator nit=dict.find(newname);
+		if(nit!=dict.end()) {
+			// we found exact name match on the new name -- remove previous entry
+			ObjectBase* obj=nit->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<Dictionary*>(it->second)) {
-					d->addEntry(name.substr(p+1),val,comment,warnExists);
-				} else {
-					Collection* c=dynamic_cast<Collection*>(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<Collection*>(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<const Collection*>(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<const Collection*>(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<Collection*>(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<const Collection*>(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 <dict> value, got "+std::string((const char*)xNodeGetName(node)));
+	
 		std::string comment;
-		set<std::string> seen;
+		std::set<std::string> 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<std::string> rem;
+		if((loadPolicy&REMOVALS) && seen.size()!=size()) {
+			std::set<std::string> rem;
 			for(const_iterator it=begin(); it!=end(); ++it) {
 				if(seen.find(it->first)==seen.end())
 					rem.insert(it->first);
 			}
-			for(set<std::string>::const_iterator it=rem.begin(); it!=rem.end(); ++it)
+			for(std::set<std::string>::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<std::string>& 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<Collection*>(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<Collection*>(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<Collection*>(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<unsigned int>(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<Collection*>(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<ObjectBase*> refs=myRef;
+		dict.clear();
+		myRef.clear();
+		comments.clear();
+		if(s>0) //only fire if we had entries to begin with
+			fireEntriesChanged();
+		for(std::set<ObjectBase*>::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<ObjectBase*>::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 "<<index<<" ("<<val<<") conflicted with previous entry "<<index<<" ("<<(*arr[index])<<")"<<endl;
-				cerr << "         (use setEntry(...,false) if you expect you might need to overwrite)" << endl;
+	void DictionaryBase::cloneMyRef() {
+		for(iterator dit=dict.begin(); dit!=dict.end(); ++dit) {
+			std::set<ObjectBase*>::iterator rit=myRef.find(dit->second);
+			if(rit!=myRef.end()) {
+				myRef.erase(rit);
+				myRef.insert(dit->second=dynamic_cast<ObjectBase*>((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<ObjectBase*> ns;
+		for(std::set<ObjectBase*>::iterator it=myRef.begin(); it!=myRef.end(); ++it) {
+			ObjectBase* n=dynamic_cast<ObjectBase*>((*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 "<<index<<" ("<<val<<") conflicted with previous entry "<<index<<" ("<<(*arr[index])<<")"<<endl;
-				cerr << "         (use setEntry(...,false) if you expect you might need to overwrite)" << endl;
+	
+	bool DictionaryBase::saveOverXMLNode(xmlNode* k, xmlNode* val, const std::string& key, std::string comment, const std::string& indentStr, std::set<std::string>& 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<Collection*>(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<ObjectBase*>::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)<KEY_IN_COMMENT_MAX_POS)
+					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;
+				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<const Collection*>(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)<KEY_IN_COMMENT_MAX_POS)
+				comment=cit->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<Collection*>(*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<Collection*>(*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<Collection*>(*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<Collection*>(*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<Collection*>(*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<const Collection*>(*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<size())
 			return &getEntry(index);
-		}
+		std::string::size_type p;
+		const_iterator it=getSubEntry(path,p);
+		if(it==arr.end())
+			throw bad_format(NULL,"Array::resolveEntry(name) was called with an invalid numeric name:" + path);
+		const Collection * d=dynamic_cast<const Collection*>(*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<ObjectBase*> refs=myRef;
+		arr.clear();
+		comments.clear();
+		myRef.clear();
+		if(s>0) //only fire if we had entries to begin with
+			fireEntriesChanged();
+		for(std::set<ObjectBase*>::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<Collection*>(*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<const Collection*>(*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 <array> 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(i<size())
 				removeEntry(size()-1);
 		} 
 	}
 	
-	void Array::saveXML(xmlNode* node) const {
+	void ArrayBase::saveXML(xmlNode* node) const {
 		//check if our node has been set to NULL (invalid or not found)
 		if(node==NULL)
 			return;
@@ -738,19 +618,10 @@
 		xmlNodeSetName(node,(const xmlChar*)"array");
 		
 		//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);
 		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 = (i<arr.size());
 		for(; i<arr.size(); ++i) {
 			comments_t::const_iterator cit=comments.find(i);
@@ -810,7 +692,15 @@
 					comment=buf;
 					comment+=": "+cit->second;
 				}
-				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<const Collection*>(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<size(); ++i) {
-			size_t cur=snprintf(NULL,0,"%lu",static_cast<unsigned long>(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<Collection*>(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<ObjectBase*>::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<unsigned int>(os.width()));
-		unsigned int seplen=Collection::subCollectionSep().size();
-		for(unsigned long i=0; i<d.arr.size(); ++i) {
-			if(Collection* dp=dynamic_cast<Collection*>(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<ObjectBase*>::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<ObjectBase*>::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<ObjectBase*>::iterator rit=myRef.find(dit->second);
-			if(rit!=myRef.end()) {
-				myRef.erase(rit);
-				myRef.insert(dit->second=dynamic_cast<ObjectBase*>((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<ObjectBase*> ns;
-		for(std::set<ObjectBase*>::iterator it=myRef.begin(); it!=myRef.end(); ++it) {
-			ObjectBase* n=dynamic_cast<ObjectBase*>((*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<ObjectBase*>::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<ObjectBase*>::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<ObjectBase*>::iterator rit=myRef.find(*dit);
 			if(rit!=myRef.end()) {
@@ -991,80 +787,72 @@
 				myRef.insert(*dit=dynamic_cast<ObjectBase*>((*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<ObjectBase*> ns;
-		for(std::set<ObjectBase*>::iterator it=myRef.begin(); it!=myRef.end(); ++it) {
-			ObjectBase* n=dynamic_cast<ObjectBase*>((*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(index<size()) {
-			//have 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
-				arr[index]->loadXML(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<const ArrayBase*>(&c)) {
+			unsigned int longest=std::max(a->getLongestKeyLen(reg,depth),static_cast<unsigned int>(os.width()));
+			for(unsigned long i=0; i<a->size(); ++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<Collection*>(&(*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<const DictionaryBase*>(&c)) {
+			unsigned int longest=std::max(d->getLongestKeyLen(reg,depth),static_cast<unsigned int>(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<Collection*>(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 <map>
 #include <vector>
 #include <set>
+#include <regex.h>
+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<typename U, typename V> 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):
+		 *  <table>
+		 *  <tr><td>@b Loading</td><td>SYNC</td><td>INTERSECT</td><td>UNION</td><td>FIXED</td></tr>
+		 *  <tr><td>not in file, in collection</td><td>remove</td><td>remove</td><td>ignore</td><td>ignore</td></tr>
+		 *  <tr><td>in file, not in collection</td><td>add</td><td>ignore</td><td>add</td><td>ignore</td></tr>
+		*  <tr><td>@b Saving</td><td>SYNC</td><td>INTERSECT</td><td>UNION</td><td>FIXED</td></tr>
+		 *  <tr><td>not in file, in collection</td><td>add</td><td>ignore</td><td>add</td><td>ignore</td></tr>
+		 *  <tr><td>in file, not in collection</td><td>remove</td><td>remove</td><td>ignore</td><td>ignore</td></tr>
+		 *  </table>
+		 *  
+		 *  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<CollectionListener*>* collectionListeners;
+		mutable std::set<CollectionListener*>* 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<std::string,ObjectBase*> 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<typename T>
-			void setValue(const std::string& name, const T& val, bool warnExists=false) { setEntry(name,new Primitive<T>(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<typename T>
-			void addValue(const std::string& name, const T& val, const std::string& comment="", bool warnExists=true) { addEntry(name,new Primitive<T>(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<std::string>(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<std::string>(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<std::string>(val),comment,warnExists); }
+		//! Indicates that no value conversions are allowed
+		/*! The actual storage type is still allowed, so technically we could use EntryConstraint<PO>
+		 *  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<typename PO>
+		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<plist::DictionaryBase::StringConversion>, 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<plist::DictionaryBase::IntegerConversion>, 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<plist::DictionaryBase::RealConversion>, 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<typename PO>
+		struct ConversionTo : public StringConversion, public IntegerConversion, public RealConversion, public EntryConstraint<PO> {
+			//! 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<typename T>
+			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<typename PO>
+		struct WrapValueConversion : public StringConversion, public IntegerConversion, public RealConversion, public EntryConstraint<PO> {
+			//! 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<typename T>
+			void addValue(const std::string& name, const T& val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive<T>(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<std::string>(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<std::string>(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<std::string>(val),comment,warnExists); }
+			virtual void addValue(const std::string& name, long val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive<long>(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<unsigned long>(val),comment,warnExists); }
+			virtual void addValue(const std::string& name, double val, const std::string& comment="", bool warnExists=true) { this->addEntry(name,new Primitive<double>(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<std::string> 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<std::string>& 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<std::string>& 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<PO> 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<typename PO, typename Alloc=typename PO::template conversion_policy<DictionaryBase,PO>::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<storage_t::key_type,PO*> 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<const_iterator_category, const_iterator_value, const_iterator_difference> {
+		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<PO*>(it->second)); }
+			const const_iterator_value* operator->() const { tmp=std::make_pair(it->first,dynamic_cast<PO*>(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<const DictionaryBase&>(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<PO&>(*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 \<key, value\> 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<const PO*>(&obj)!=NULL); }
+		
+		//! clone implementation for Dictionary
+		PLIST_CLONE_DEF(DictionaryOf,(new DictionaryOf<PO,Alloc>(*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<PO> 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<ObjectBase> Dictionary;
+	
+	template<typename PO, typename Alloc>
+	void DictionaryOf<PO,Alloc>::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 ("<<name<<","<<val<<") was already added, ignoring duplication..." << std::endl;
+				myRef.erase(&val); // reset reference
+				return; // same val reference already registered
+			}
+			if(warnExists) {
+				std::cerr << "Warning: new entry ("<<name<<","<<val<<") conflicted with previous entry ("<<name<<","<<(*it->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<typename PO, typename Alloc>
+	void DictionaryOf<PO,Alloc>::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 ("<<name<<","<<val<<") was already added, ignoring duplication..." << std::endl;
+				myRef.erase(&val);
+				return; // same val reference already registered
+			}
+			if(warnExists) {
+				std::cerr << "Warning: new entry ("<<name<<","<<val<<") conflicted with previous entry ("<<name<<","<<(*it->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<typename PO, typename Alloc>
+	void DictionaryOf<PO,Alloc>::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 ("<<name<<","<<(*val)<<") was already added, ignoring duplication..." << std::endl;
+				myRef.insert(val);
+				return; // same val reference already registered
+			}
+			if(warnExists) {
+				std::cerr << "Warning: new entry ("<<name<<","<<(*val)<<") conflicted with previous entry ("<<name<<","<<(*it->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<typename PO, typename Alloc>
+	void DictionaryOf<PO,Alloc>::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 ("<<name<<","<<(*val)<<") was already added, ignoring duplication..." << std::endl;
+				myRef.insert(val);
+				return; // same val reference already registered
+			}
+			if(warnExists) {
+				std::cerr << "Warning: new entry ("<<name<<","<<(*val)<<") conflicted with previous entry ("<<name<<","<<(*it->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<PO,Alloc>(*this)));
+	
+	/// @cond INTERNAL
+	template<> inline ObjectBase* DictionaryOf<ObjectBase, ObjectBase::conversion_policy<DictionaryBase,ObjectBase>::value_conversion>::
+	allocatePO() { throw std::runtime_error("plist::Dictionary cannot allocate new generic instances (ObjectBase)"); }
+	template<> inline PrimitiveBase* DictionaryOf<PrimitiveBase, PrimitiveBase::conversion_policy<DictionaryBase,PrimitiveBase>::value_conversion>::
+	allocatePO() { throw std::runtime_error("plist::Dictionary cannot allocate new generic instances (PrimitiveBase)"); }
+	template<> inline Collection* DictionaryOf<Collection, Collection::conversion_policy<DictionaryBase,Collection>::value_conversion>::
+	allocatePO() { throw std::runtime_error("plist::Dictionary cannot allocate new generic instances (Collection)"); }
+	template<> inline void DictionaryOf<ObjectBase, ObjectBase::conversion_policy<DictionaryBase,ObjectBase>::value_conversion>::
+	assignPO(ObjectBase& a, const ObjectBase& b) { a.set(b); }
+	/// @endcond
+	
+	template<typename PO, typename Alloc>
+	bool DictionaryOf<PO,Alloc>::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<Collection*>(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<PO*>(obj);
+		if(cobj==NULL)
+			throw bad_format(val,"Dictionary encountered a value of unexpected type");
+		if(dynamic_cast<Collection*>(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<typename PO, typename Alloc>
+	void DictionaryOf<PO,Alloc>::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<const DictionaryOf*>(&d)) {
+			operator=(*od); // same template type, use faster version!
+			return;
+		}
+		DictionaryBase::operator=(d);
+		
+		std::set<std::string> 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<PO*>(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<PO*>(obj->clone());
+				myRef.insert(obj);
+			}
+			if(dynamic_cast<Collection*>(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<std::string> rem;
+			for(const_iterator it=begin(); it!=end(); ++it) {
+				if(seen.find(it->first)==seen.end())
+					rem.insert(it->first);
+			}
+			for(std::set<std::string>::const_iterator it=rem.begin(); it!=rem.end(); ++it)
+				removeEntry(*it);
+		}
+	}
+	
+	template<typename PO, typename Alloc>
+	DictionaryOf<PO,Alloc>& DictionaryOf<PO,Alloc>::operator=(const DictionaryOf& d) {
+		if(&d==this)
+			return *this;
+		DictionaryBase::operator=(d);
+		
+		std::set<std::string> 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<PO*>(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<PO*>(obj->clone());
+				myRef.insert(obj);
+			}
+			if(dynamic_cast<Collection*>(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<std::string> rem;
+			for(const_iterator it=begin(); it!=end(); ++it) {
+				if(seen.find(it->first)==seen.end())
+					rem.insert(it->first);
+			}
+			for(std::set<std::string>::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<ObjectBase*> 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<PO>
+		 *  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<typename T>
-			void addValue(const T& val, const std::string& comment="") { addEntry(new Primitive<T>(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<std::string>(val)); takeObject(size()-1,arr.back()); fireEntryAdded(*arr.back()); }
+		template<typename PO>
+		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<plist::DictionaryBase::StringConversion>, 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<typename T>
-			void setValue(size_t index, const T& val, bool warnExists=false) { setEntry(index,new Primitive<T>(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<typename T>
-			void addValue(size_t index, const T& val, const std::string& comment="") { addEntry(index,new Primitive<T>(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<std::string>(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<std::string>(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<plist::DictionaryBase::IntegerConversion>, 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<plist::DictionaryBase::RealConversion>, 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<typename T>
-			void setValue(const std::string& name, const T& val,bool warnExists=false) { setEntry(name,new Primitive<T>(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<typename T>
-			void addValue(const std::string& name, const T& val, const std::string& comment="") { addEntry(name,new Primitive<T>(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<std::string>(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<std::string>(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<typename PO>
+		struct ConversionTo : public StringConversion, public EntryConstraint<PO> {
+			//! 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<typename T>
+			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<typename T>
+			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<typename PO>
+		struct WrapValueConversion : public StringConversion, public EntryConstraint<PO> {
+			//! 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<typename T>
+			void addValue(const T& val, const std::string& comment="") { this->addEntry(new Primitive<T>(val),comment); }
+			virtual void addValue(const std::string& val, const std::string& comment="") { this->addEntry(new Primitive<std::string>(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<std::string>(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<std::string>(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<long>(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<unsigned long>(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<double>(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<typename T>
+			void addValue(size_t index, const T& val, const std::string& comment="") { this->addEntry(index,new Primitive<T>(val),comment); }
+			virtual void addValue(size_t index, const std::string& val, const std::string& comment="") { this->addEntry(index,new Primitive<std::string>(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<std::string>(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<std::string>(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<long>(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<unsigned long>(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<double>(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<const_iterator&>(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<const_iterator&>(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<ObjectBase*>(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<ObjectBase*>(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<std::string>(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<std::string>(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<std::string>(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<std::string>(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<PO> 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<typename PO, typename Alloc=typename PO::template conversion_policy<ArrayBase,PO>::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<ObjectBase*>(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<std::string>(val),comment); }
-	//! specialization of Array::addValue() for char* strings
-	template<>
-	inline void Array::addValue(char* const& val, const std::string& comment/*=""*/) { addEntry(new Primitive<std::string>(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<const_iterator_category, const PO*, const_iterator_difference> {
+		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<PO&>(**it); }
+			const value_type* operator->() const { return &dynamic_cast<PO*>(*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<const ArrayBase&>(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<PO&>(*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<PO&>(*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<const PO*>(&obj)!=NULL); }
+		
+		//! clone implementation for Array
+		PLIST_CLONE_DEF(ArrayOf,(new ArrayOf<PO,Alloc>(*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<ObjectBase*>(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<std::string>(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<std::string>(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<ObjectBase*>(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<std::string>(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<std::string>(val),comment); }
+	/*! plist::Array can handle any mixture of types, whereas plist::ArrayOf<PO> 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<ObjectBase> 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<ObjectBase*>(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<std::string>(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<std::string>(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<ObjectBase*>(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<std::string>(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<std::string>(val),comment); }
+
+	template<typename PO, typename Alloc>
+	void ArrayOf<PO,Alloc>::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 "<<index<<" ("<<val<<") conflicted with previous entry "<<index<<" ("<<(*arr[index])<<")"<<std::endl;
+				std::cerr << "         (use setEntry(...,false) if you expect you might need to overwrite)" << std::endl;
+			}
+			arr[index]=&val;
+			fireEntriesChanged();
+		}
+	}
+	template<typename PO, typename Alloc>
+	void ArrayOf<PO,Alloc>::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<typename PO, typename Alloc>
+	void ArrayOf<PO,Alloc>::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 "<<index<<" ("<<val<<") conflicted with previous entry "<<index<<" ("<<(*arr[index])<<")"<<std::endl;
+				std::cerr << "         (use setEntry(...,false) if you expect you might need to overwrite)" << std::endl;
+			}
+			std::set<ObjectBase*>::iterator it=myRef.find(arr[index]);
+			if(it!=myRef.end()) {
+				myRef.erase(*it);
+				delete arr[index];
+			}
+			arr[index]=val;
+			takeObject(index,val);
+			fireEntriesChanged();
+		}
+	}
+	template<typename PO, typename Alloc>
+	void ArrayOf<PO,Alloc>::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<PO,Alloc>(*this)));
+	
+	/// @cond INTERNAL
+	template<> inline ObjectBase* ArrayOf<ObjectBase,ObjectBase::conversion_policy<ArrayBase,ObjectBase>::value_conversion>::
+	allocatePO() { throw std::runtime_error("plist::Array cannot allocate new generic instances (ObjectBase)"); }
+	template<> inline PrimitiveBase* ArrayOf<PrimitiveBase,PrimitiveBase::conversion_policy<ArrayBase,PrimitiveBase>::value_conversion>::
+	allocatePO() { throw std::runtime_error("plist::Array cannot allocate new generic instances (PrimitiveBase)"); }
+	template<> inline Collection* ArrayOf<Collection,Collection::conversion_policy<ArrayBase,Collection>::value_conversion>::
+	allocatePO() { throw std::runtime_error("plist::Array cannot allocate new generic instances (Collection)"); }
+	template<> inline void ArrayOf<ObjectBase,ObjectBase::conversion_policy<ArrayBase,ObjectBase>::value_conversion>::
+	assignPO(ObjectBase& a, const ObjectBase& b) { a.set(b); }
+	/// @endcond
+
+	template<typename PO, typename Alloc>
+	bool ArrayOf<PO,Alloc>::loadXMLNode(size_t index, xmlNode* val, const std::string& comment) {
+		if(index<size()) {
+			//have 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
+				arr[index]->loadXML(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<PO*>(obj);
+		if(cobj==NULL)
+			throw bad_format(val,"Array encountered a value of unexpected type");
+		if(index<size()) {
+			setEntry(index,cobj,false);
+			setComment(index,comment);
+		} else {
+			addEntry(index,cobj,comment);
+		}
+		return true;
+	}
+	
+	template<typename PO, typename Alloc>
+	void ArrayOf<PO,Alloc>::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<const ArrayOf*>(&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; index<a.size(); ++index) {
+			ObjectBase* val = &a[index];
+			const std::string comment = a.getComment(index);
+			if(index<size()) {
+				//have 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
+					arr[index]->set(*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<PO*>(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<PO*>(obj->clone());
+				myRef.insert(obj);
+			}
+			if(index<size()) {
+				setEntry(index,obj,false);
+				setComment(index,comment);
+			} else {
+				addEntry(index,obj,comment);
+			}
+		}
+	}
+
+	template<typename PO, typename Alloc>
+	ArrayOf<PO,Alloc>& ArrayOf<PO,Alloc>::operator=(const ArrayOf& a) {
+		if(&a==this)
+			return *this;
+		ArrayBase::operator=(a);
+		for(unsigned int index=0; index<a.size(); ++index) {
+			PO* val = &a[index];
+			const std::string comment = a.getComment(index);
+			if(index<size()) {
+				//have 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<PO*>(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<PO*>(obj->clone());
+				myRef.insert(obj);
+			}
+			if(index<size()) {
+				setEntry(index,obj,false);
+				setComment(index,comment);
+			} else {
+				addEntry(index,obj,comment);
+			}
+		}
+		return *this;
+	}
+		
+	//! take a regex and maximum depth for display (displays entries whos names match the filter @a sel
+	/*! @param os the ostream to write into
+	 *  @param c the collection to dump
+	 *  @param sel the regular expression in string form
+	 *  @param selType how to interpret @a sel, this is the flags argument to regcomp(), e.g. REG_EXTENDED or REG_BASIC
+	 *  @param depth maximum recursion depth for sub-collections */
+	std::ostream& filteredDisplay(std::ostream& os, const ObjectBase& c, const std::string& sel, int selType, unsigned int depth);
+	
+	//! take a compiled regex and maximum depth for display
+	/*! @param os the ostream to write into
+	 *  @param c the collection to dump
+	 *  @param reg a pre-compiled regular expression, or NULL to match everything
+	 *  @param depth maximum recursion depth for sub-collections */
+	std::ostream& filteredDisplay(std::ostream& os, const ObjectBase& c, const regex_t* reg, unsigned int depth);
+	
+	//! provides textual output
+	inline std::ostream& operator<<(std::ostream& os, const DictionaryBase& d) { return filteredDisplay(os,d,NULL,-1U); }
+	
+	//! provides textual output
+	inline std::ostream& operator<<(std::ostream& os, const ArrayBase& d) { return filteredDisplay(os,d,NULL,-1U); }
 	
 } //namespace plist
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Shared/plistPrimitives.cc ./Shared/plistPrimitives.cc
--- ../Tekkotsu_3.0/Shared/plistPrimitives.cc	2006-09-16 13:32:40.000000000 -0400
+++ ./Shared/plistPrimitives.cc	2007-08-24 15:09:49.000000000 -0400
@@ -6,17 +6,20 @@
 		if(node==NULL)
 			return;
 		if(xNodeHasName(node,"true")) {
+			prevVal=val; 
 			val=true;
-			fireValueChanged(); 
+			fireValueChanged(prevVal && val || !prevVal && !val); 
 		} else if(xNodeHasName(node,"false")) {
+			prevVal=val; 
 			val=false;
-			fireValueChanged(); 
+			fireValueChanged(prevVal && val || !prevVal && !val); 
 		} else if(xNodeHasName(node,"integer") || xNodeHasName(node,"real")) {
+			prevVal=val; 
 			xmlChar * cont=xmlNodeGetContent(node);
 			std::stringstream str((char*)cont);
 			str >> 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<bool>::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<bool>
 	PLIST_CLONE_IMP(Primitive<bool>,new Primitive<bool>(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<char>::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<char>
 	PLIST_CLONE_IMP(Primitive<char>,new Primitive<char>(val));
 	
+	
 	void Primitive<unsigned char>::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<unsigned char>::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<unsigned char>
 	PLIST_CLONE_IMP(Primitive<unsigned char>,new Primitive<unsigned char>(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<T>::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<T>::saveXML(xmlNode* node) const { \
-		if(node==NULL) \
-			return; \
-		xmlNodeSetName(node,(const xmlChar*)PRIM); \
-		std::stringstream str; \
-		str <<std::setprecision(128)<< val; \
-		xmlNodeSetContent(node,(const xmlChar*)str.str().c_str()); \
-	} \
-	void Primitive<T>::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<T>,new Primitive<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
-	
 	
 	void Primitive<std::string>::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<std::string>::saveXML(xmlNode* node) const {
@@ -287,9 +232,45 @@
 		xmlNodeSetName(node,(const xmlChar*)"string");
 		xmlNodeSetContent(node,(const xmlChar*)c_str());
 	}
+	long Primitive<std::string>::toLong() const { std::stringstream s(*this); long v; s >> v; return v; }
+	double Primitive<std::string>::toDouble() const { std::stringstream s(*this); double v; s >> v; return v; }
 	//! implements the clone function for Primitive<std::string>
 	PLIST_CLONE_IMP(Primitive<std::string>,new Primitive<std::string>(get()));
+	
 
+	std::string NamedEnumerationBase::getDescription(bool preferredOnly/*=true*/) {
+		if(preferredOnly) {
+			std::map<int,std::string> valsToNames;
+			getPreferredNames(valsToNames);
+			if(valsToNames.size()==0) return "";
+			std::string ans="Value is one of: { ";
+			std::map<int,std::string>::const_iterator it=valsToNames.begin();
+			ans+=it->second;
+			for(++it; it!=valsToNames.end(); ++it) {
+				ans+=" | ";
+				ans+=it->second;
+			}
+			if(!strictValue)
+				ans+=" | <integer_value>";
+			ans+=" } ";
+			return ans;
+		} else {
+			std::map<std::string,int> namesToVals;
+			getAllNames(namesToVals);
+			if(namesToVals.size()==0) return "";
+			std::string ans="Value is one of: { ";
+			std::map<std::string,int>::const_iterator it=namesToVals.begin();
+			ans+=it->first;
+			for(++it; it!=namesToVals.end(); ++it) {
+				ans+=" | ";
+				ans+=it->first;
+			}
+			if(!strictValue)
+				ans+=" | <integer_value>";
+			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 <map>
 
-//!@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<typename T> const char* getTypeName();
+	/// @cond INTERNAL
+	template<> inline const char* getTypeName<short>() { return "integer"; }
+	template<> inline const char* getTypeName<unsigned short>() { return "integer"; }
+	template<> inline const char* getTypeName<int>() { return "integer"; }
+	template<> inline const char* getTypeName<unsigned int>() { return "integer"; }
+	template<> inline const char* getTypeName<long>() { return "integer"; }
+	template<> inline const char* getTypeName<unsigned long>() { return "integer"; }
+	template<> inline const char* getTypeName<long long>() { return "integer"; }
+	template<> inline const char* getTypeName<unsigned long long>() { return "integer"; }
+	template<> inline const char* getTypeName<float>() { return "real"; }
+	template<> inline const char* getTypeName<double>() { 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<typename T>
 	class Primitive : public PrimitiveBase {
 	public:
+		template<typename U, typename V> struct conversion_policy { typedef typename U::template ConversionTo<V> 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<const Primitive*>(&pb)!=this) operator=(pb.to<T>()); 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 <<std::setprecision(std::numeric_limits<T>::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<long>(val); }
+		virtual double toDouble() const { return static_cast<double>(val); }
 		
 		//! clone definition for Primitive<T>
 		PLIST_CLONE_DEF(Primitive<T>,new Primitive<T>(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<typename T>
+	void Primitive<T>::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<T>() << ", got unknown type " << (const char*)xNodeGetName(node);
+			throw bad_format(node,errstr.str());
+		}
+		if(!xNodeHasName(node,getTypeName<T>()))
+			std::cerr << "Warning: plist expected " << getTypeName<T>() << " 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<typename T>
+	void Primitive<T>::saveXML(xmlNode* node) const {
+		if(node==NULL)
+			return;
+		xmlNodeSetName(node,(const xmlChar*)getTypeName<T>());
+		std::stringstream str;
+		str <<std::setprecision(std::numeric_limits<T>::digits10)<< val;
+		xmlNodeSetContent(node,(const xmlChar*)str.str().c_str());
+	}
+	template<typename T>
+	void Primitive<T>::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<T>(); err+=" value, got '"+str+"'";
+				throw bad_format(NULL,err);
+			}
+			std::cerr << "Warning: expected " << getTypeName<T>() << " value, interpreting '" << str << "' as boolean (value of " << val << ")" << std::endl;
+		}
+		if(sstr.good()) {
+			std::cerr << "Warning: expected " << getTypeName<T>() << " 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<T>
-	PLIST_CLONE_IMPT(class T,Primitive<T>,new Primitive<T>(val));
+	PLIST_CLONE_IMPT(T,Primitive,new Primitive<T>(val));
 
 	
-/*! @cond SHOW_PLIST_OBJECT_SPECIALIZATION */
+/// @cond SHOW_PLIST_OBJECT_SPECIALIZATION
 	
 	//! provides a @c bool specialization of Primitive<T>
 	/*! A @c bool can be treated as either a string or an integer\n
@@ -92,29 +180,39 @@
 	template<>
 	class Primitive<bool> : 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<typename U, typename V> struct conversion_policy { typedef typename U::template ConversionTo<V> 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<const Primitive*>(&pb)!=this) operator=(pb.to<bool>()); 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<long>(val); }
+		virtual double toDouble() const { return static_cast<double>(val); }
+		
 		//! clone definition for Primitive<bool>
 		PLIST_CLONE_DEF(Primitive<bool>,new Primitive<bool>(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<T>, 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<char> : 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<typename U, typename V> struct conversion_policy { typedef typename U::template ConversionTo<V> 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<const Primitive*>(&pb)!=this) operator=(pb.to<char>()); 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<long>(val); }
+		virtual double toDouble() const { return static_cast<double>(val); }
+		
 		//! clone definition for Primitive<char>
 		PLIST_CLONE_DEF(Primitive<char>,new Primitive<char>(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<unsigned char> : 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<typename U, typename V> struct conversion_policy { typedef typename U::template ConversionTo<V> 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<const Primitive*>(&pb)!=this) operator=(pb.to<unsigned char>()); 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<long>(val); }
+		virtual double toDouble() const { return static_cast<double>(val); }
+		
 		//! clone definition for Primitive<unsigned char>
 		PLIST_CLONE_DEF(Primitive<unsigned char>,new Primitive<unsigned char>(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<T> : 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 <<std::setprecision(64)<< val; \
-			return sstr.str(); \
-		} \
-		PLIST_CLONE_DEF(Primitive<T>,new Primitive<T>(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<T>
 	/*! Doesn't need to provide a operator cast because we subclass std::string itself! */
 	template<>
 	class Primitive<std::string> : 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<typename U, typename V> struct conversion_policy { typedef typename U::template ConversionTo<V> 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<const Primitive*>(&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<const std::string&>(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<std::string>
 		PLIST_CLONE_DEF(Primitive<std::string>,new Primitive<std::string>(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<int,std::string>& 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<std::string,int>& 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.
+	 *
+	 *  <b>Binary size and symbol definition</b>: 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<typename T> std::map<std::string,T> plist::NamedEnumeration<T>::namesToVals;
+	 *    template<typename T> std::map<T,std::string> plist::NamedEnumeration<T>::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<std::string,YOUR_T> plist::NamedEnumeration<YOUR_T>::namesToVals = std::map<std::string,YOUR_T>();
+	 *    template<> std::map<YOUR_T,std::string> plist::NamedEnumeration<YOUR_T>::valsToNames = std::map<YOUR_T,std::string>();
+	 *    @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<typename T> 
-	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<typename U, typename V> struct conversion_policy { typedef typename U::template ConversionTo<V> 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<T>& 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<T,std::string>& getPreferredNames() { return valsToNames; } //!< returns mapping from numeric value to "preferred" name (one-to-one)
+		static const std::map<std::string,T>& 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<const NamedEnumeration*>(&pb)==this)
+				return *this;
+			if(const std::string* str = dynamic_cast<const std::string*>(&pb))
+				set(*str);
+			else {
+				T tv=static_cast<T>(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<T>(i);
 				std::cerr << "Warning: plist NamedEnumeration should use <string>" << name << "</string>, 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<max) {
+			std::string name;
+			if(getNameForVal(val,name)) {
 				xmlNodeSetName(node,(const xmlChar*)"string");
 			} else {
 				xmlNodeSetName(node,(const xmlChar*)"integer");
 			}
-			xmlNodeSetContent(node,(const xmlChar*)get().c_str());
+			xmlNodeSetContent(node,(const xmlChar*)name.c_str());
 		}
 		void set(const std::string& str) {
-			unsigned int i=findName(str.c_str());
-			if(i==-1U) {
-				if(sscanf(str.c_str(),"%d",&i)==0)
-					throw bad_format(NULL,"Error: plist NamedEnumeration must be numeric or valid string");
-			}
-			val=static_cast<T>(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<max)
-				return names[val];
-			std::stringstream str;
-			str << val;
-			return str.str();
+			std::string name;
+			getNameForVal(val,name);
+			return name;
 		}
+		virtual long toLong() const { return static_cast<long>(val); }
+		virtual double toDouble() const { return static_cast<double>(val); }
+		
 		//! implements the clone function for NamedEnumeration<T>
 		PLIST_CLONE_DEF(NamedEnumeration<T>,new NamedEnumeration<T>(*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<max; i++)
-				if(names[i] && strcmp(name,names[i])==0)
-					return i;
-			//but allow case insensitive if exact match not found
-			for(unsigned int i=0; i<max; i++)
-				if(names[i] && strcasecmp(name,names[i])==0)
-					return i;
-			return -1U;
+		//! 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 getPreferredNames(std::map<int,std::string>& 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<std::string,int>& 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<std::string,T>::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<T>(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<T,std::string>::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<std::string,T> 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<T,std::string> valsToNames;
 	};
 	//! implements the clone function for NamedEnumeration<T>
-	PLIST_CLONE_IMPT(class T,NamedEnumeration<T>,new NamedEnumeration<T>(*this));
+	PLIST_CLONE_IMPT(T,NamedEnumeration,new NamedEnumeration<T>(*this));
 
+#ifdef USE_GLOBAL_PLIST_STATICS
+	template<typename T> std::map<std::string,T> plist::NamedEnumeration<T>::namesToVals;
+	template<typename T> std::map<T,std::string> plist::NamedEnumeration<T>::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<typename T> std::map<std::string,T> plist::NamedEnumeration<T>::namesToVals; \
+	template<typename T> std::map<T,std::string> plist::NamedEnumeration<T>::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<std::string,T> plist::NamedEnumeration<T>::namesToVals = std::map<std::string,T>(); \
+	template<> std::map<T,std::string> plist::NamedEnumeration<T>::valsToNames = std::map<T,std::string>();
+	
+	template<typename T> void NamedEnumeration<T>::setNames(const char *  const* enumnames) {
+		clearNames();
+		for(unsigned int i=0; *enumnames[i]!='\0'; ++i) {
+			std::string name=enumnames[i];
+			valsToNames[static_cast<T>(i)]=name;
+			std::transform(name.begin(), name.end(), name.begin(), (int(*)(int)) std::toupper);
+			namesToVals[name]=static_cast<T>(i);
+		}
+	}
+	template<typename T> void NamedEnumeration<T>::clearNames() {
+		namesToVals.clear();
+		valsToNames.clear();
+	}
+	template<typename T> void NamedEnumeration<T>::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<typename T> void NamedEnumeration<T>::setPreferredNameForVal(const std::string& enumname, const T& val) {
+		valsToNames[val]=enumname;
+	}
+		
+	template<typename T> void NamedEnumeration<T>::getPreferredNames(std::map<int,std::string>& names) const {
+		names.clear();
+		for(typename std::map<T,std::string>::const_iterator it=valsToNames.begin(); it!=valsToNames.end(); ++it)
+			names.insert(std::pair<int,std::string>(it->first,it->second));
+	}
+	template<typename T> void NamedEnumeration<T>::getAllNames(std::map<std::string,int>& names) const {
+		names.clear();
+		for(typename std::map<std::string,T>::const_iterator it=namesToVals.begin(); it!=namesToVals.end(); ++it)
+			names.insert(std::pair<std::string,int>(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 <ctype.h>
+#include <cctype>
+#include <locale>
 #include <pwd.h>
 #include <stdlib.h>
+#include <regex.h>
 
 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 <limits.h>
+#include <math.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <string.h>
+
+#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 <limits.h>
+#include <math.h>
+#include <stdio.h>
+#include <string.h>
+
+#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<size_t>(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<size_t>(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<size_t>(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 <a href="http://www.cs.cmu.edu/~dst/Tekkotsu/Tutorial/sound.shtml">David Touretzky's "Playing Sounds" Chapter</a>
  */
 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; i<numLayers; i++) {
 		//s is the scaling factor -- 2 means *double* size
 		unsigned int s=(1<<(i-imgsrc.layer));
@@ -301,6 +311,7 @@
 		heights[i]=imgsrc.height*s;
 		//stride is same as width (set above) -- we allocate these layers, don't skip rows
 		skips[i]=0;
+		increments[i]=1;
 	}
 }
 void BufferedImageGenerator::destruct() {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/Vision/CDTGenerator.cc ./Vision/CDTGenerator.cc
--- ../Tekkotsu_3.0/Vision/CDTGenerator.cc	2006-09-11 19:05:19.000000000 -0400
+++ ./Vision/CDTGenerator.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"
@@ -68,7 +69,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]);
 				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<char*>(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<char*&>(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; x<src->getWidth(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<JSAMPROW>(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<void*>(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 <jpeglib.h>
 }
@@ -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<char*>(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<png_bytep>(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<char*&>(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<png_bytep>(row+row_stride*heights[layer]);
-	for(unsigned int h=0; h<heights[layer]; ++h) {
-		if(row+row_stride>endp) {
-			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 <png.h>
-
-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 <a href="../gpl-2.0.txt">GNU GPL version 2</a>
+*
+* $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 <class color_class_state_t>
-int LoadColorInformation(color_class_state_t *color,int max,const char *filename, hash_map<const char*, unsigned int, hash<const char*>, hashcmp_eqstr> &color_names)
+int LoadColorInformation(color_class_state_t *color,int max,const char *filename, __gnu_cxx::hash_map<const char*, unsigned int, __gnu_cxx::hash<const char*>, 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 <a href="../gpl-2.0.txt">GNU GPL version 2</a>
+*
+* $Author: ejt $
+* $Name: tekkotsu-4_0 $
+* $Revision: 1.9 $
+* $State: Exp $
+* $Date: 2007/08/14 18:24:07 $
+*/
+
 #include <stdio.h>
 #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 <a href="../gpl-2.0.txt">GNU GPL version 2</a>
+*
+* $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 <a href="../gpl-2.0.txt">GNU General Public License,
+ version 2</a>.  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 <stdlib.h>
 #include <string.h>
 #include <stdio.h>
 
-//#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 <a href="../gpl-2.0.txt">GNU GPL version 2</a>
+*
+* $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 <a href="../gpl-2.0.txt">GNU GPL version 2</a>
+*
+* $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 <iostream>
+#include <string>
+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 <iostream>
 #include <fstream>
 #include <sys/stat.h>
 #include <sys/fcntl.h>
 #include <unistd.h>
 
-#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 <typename T> 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 <ant.h>
 #  include <Types.h>
 #else
+#  include <sys/types.h>
 #  include <sys/socket.h>
+typedef unsigned char byte;
 #endif
 #include <stdarg.h>
 #include <stdlib.h>
 #include <string>
 
-//! 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 <cstring>
 #include "Shared/ProjectInterface.h"
 
+#include "SocketListener.h"
+
 Wireless *wireless=NULL;
 
 #ifdef PLATFORM_APERIOS
@@ -14,7 +16,6 @@
 #  include <UDPEndpointMsg.h>
 #  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]->sentSize<sockets[sock]->sendSize) {
@@ -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 <stdint.h>
+typedef uint32_t uint32;
 #endif
 #include "Socket.h"
 #include "DummySocket.h"
 #include <list>
 
-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 <iostream>
+
+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 <cstdio>
+#include <cstring>
+#include <iostream>
+#include <iosfwd>
+#include <stdio.h>
+#include <stdlib.h>
+#include <ctype.h>
+#include <unistd.h>
+#include <stdexcept>
+
+#include <errno.h>
+#include <signal.h>
+//#include <sys/time.h>
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <netdb.h>
+#include <cstring>
+#include <string>
+#include <poll.h>
+
+#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 charT, class traits=std::char_traits<charT> >
+class basic_netbuf : public std::basic_streambuf<charT,traits> {
+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<charT,traits>::eback;
+	using std::basic_streambuf<charT,traits>::gptr;
+	using std::basic_streambuf<charT,traits>::egptr;
+	using std::basic_streambuf<charT,traits>::gbump;
+	using std::basic_streambuf<charT,traits>::pbase;
+	using std::basic_streambuf<charT,traits>::pptr;
+	using std::basic_streambuf<charT,traits>::epptr;
+	using std::basic_streambuf<charT,traits>::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<char_type, traits_type>* 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 <class charT, class traits>
+const size_t basic_netbuf<charT,traits>::def_buf_in_size=(1<<14)-28;
+template <class charT, class traits>
+const size_t basic_netbuf<charT,traits>::def_buf_out_size=(1<<14)-28;
+
+
+template <class charT, class traits=std::char_traits<charT> >
+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<charT, traits>* rdbuf() const { return const_cast<basic_netbuf<charT, traits>*>(&nb); }
+
+protected:
+	~basic_netbuf_interface() {}
+	basic_netbuf<charT, traits> nb;
+};
+
+template <class charT, class traits=std::char_traits<charT> >
+class basic_inetstream : public virtual basic_netbuf_interface<charT,traits>, public std::basic_istream<charT,traits>
+{
+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<charT,traits>(), std::basic_istream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_inetstream(const IPaddr& addr, bool datagram=false) : basic_netbuf_interface<charT,traits>(addr,datagram), std::basic_istream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_inetstream(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false) : basic_netbuf_interface<charT,traits>(host,port,datagram), std::basic_istream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_inetstream(size_t buf_in_size, size_t buf_out_size) : basic_netbuf_interface<charT,traits>(buf_in_size,buf_out_size), std::basic_istream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	using basic_netbuf_interface<charT,traits>::rdbuf;
+};
+
+
+template <class charT, class traits=std::char_traits<charT> >
+class basic_onetstream : public virtual basic_netbuf_interface<charT,traits>, public std::basic_ostream<charT,traits>
+{
+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<charT,traits>(), std::basic_ostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_onetstream(const IPaddr& addr, bool datagram=false) : basic_netbuf_interface<charT,traits>(addr,datagram), std::basic_ostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_onetstream(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false) : basic_netbuf_interface<charT,traits>(host,port,datagram), std::basic_ostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_onetstream(size_t buf_in_size, size_t buf_out_size) : basic_netbuf_interface<charT,traits>(buf_in_size,buf_out_size) , std::basic_ostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()){}
+	using basic_netbuf_interface<charT,traits>::rdbuf;
+};
+
+
+template <class charT, class traits=std::char_traits<charT> >
+class basic_ionetstream : public virtual basic_netbuf_interface<charT,traits>, public std::basic_iostream<charT,traits>
+{
+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<charT,traits>(), std::basic_iostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_ionetstream(const IPaddr& addr, bool datagram=false) : basic_netbuf_interface<charT,traits>(addr,datagram), std::basic_iostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_ionetstream(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram=false) : basic_netbuf_interface<charT,traits>(host,port,datagram), std::basic_iostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()) {}
+	basic_ionetstream(size_t buf_in_size, size_t buf_out_size) : basic_netbuf_interface<charT,traits>(buf_in_size,buf_out_size) , std::basic_iostream<charT,traits>(basic_netbuf_interface<charT,traits>::rdbuf()){}
+	using basic_netbuf_interface<charT,traits>::rdbuf;
+};
+
+/*
+template<class T>
+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<char, std::char_traits<char> > netbuf;
+typedef basic_inetstream<char, std::char_traits<char> > inetstream;
+typedef basic_onetstream<char, std::char_traits<char> > onetstream;
+typedef basic_ionetstream<char, std::char_traits<char> > ionetstream;
+
+
+
+
+template <class charT, class traits>
+basic_netbuf<charT,traits>::basic_netbuf() 
+  : std::basic_streambuf<charT,traits>(), 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 <class charT, class traits>
+basic_netbuf<charT,traits>::basic_netbuf(const IPaddr& addr, bool datagram)
+  : std::basic_streambuf<charT,traits>(), 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 <class charT, class traits>
+basic_netbuf<charT,traits>::basic_netbuf(const IPaddr::ipname_t& host, const IPaddr::ipport_t port, bool datagram)
+  : std::basic_streambuf<charT,traits>(), 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 <class charT, class traits>
+basic_netbuf<charT,traits>::basic_netbuf(size_t buf_in_size, size_t buf_out_size) 
+  : std::basic_streambuf<charT,traits>(), 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 <class charT, class traits>
+basic_netbuf<charT,traits>::~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<class charT, class traits>
+void
+basic_netbuf<charT,traits>::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<class charT, class traits>
+void
+basic_netbuf<charT,traits>::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 <class charT, class traits>
+bool
+basic_netbuf<charT,traits>::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<sockaddr *>(&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<sockaddr *>(&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 <class charT, class traits>
+bool
+basic_netbuf<charT,traits>::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<sockaddr *>(&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<sockaddr *>(&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 <class charT, class traits>
+bool
+basic_netbuf<charT,traits>::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 <class charT, class traits>
+void
+basic_netbuf<charT,traits>::close() {
+	//cout << "close called" << endl;
+	if(!is_open())
+		return;
+	//cout << "closing" << endl;
+	::close(sock);
+	//cout << "closed" << endl;
+	sock = INVALID_SOCKET;
+}
+
+template <class charT, class traits>
+void
+basic_netbuf<charT,traits>::reconnect() {
+	if(sockFromServer) {
+		listen(tgtAddress,isDatagram);
+	} else {
+		open(tgtAddress,isDatagram);
+	}
+}
+
+template <class charT, class traits>
+void
+basic_netbuf<charT,traits>::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 <class charT, class traits>
+void
+basic_netbuf<charT,traits>::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 <class charT, class traits>
+void
+basic_netbuf<charT,traits>::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<n) {
+		int sent = write(sock, pbase()+total, n-total);
+		while(sent < 0) {
+			//cout << "netstream error: send error" << endl;
+			//perror("netstream send");
+			close();
+			if(autoReconnect)
+				reconnect();
+			if(!is_open())
+				return;
+			sent = write(sock, pbase()+total, n-total);
+		}
+		//if(sent==0)
+		//	cout << "got send 0" << endl;
+		if(is_echoing)
+			printBuffer(pbase()+total, sent, "netstream sending: ", "> ");
+		total += sent;
+	}
+	total/=sizeof(charT);
+	n/=sizeof(charT);
+	if(total!=n)
+		traits::move(pbase(),pbase()+total,n-total);
+	pbump( -total );
+}
+
+
+template <class charT, class traits>
+inline std::streamsize
+basic_netbuf<charT, traits>::showmanyc() {
+	update_status();
+	return (is_open() && canRead) ? 1 : 0;
+	//return (gptr()<egptr())?(egptr()-gptr()):0;
+}
+
+template <class charT, class traits>
+inline typename basic_netbuf<charT, traits>::int_type
+basic_netbuf<charT, traits>::underflow() {
+	in_sync();
+	if(gptr()<egptr())
+		return traits::to_int_type(*gptr());
+//	cout << "UNDERFLOW" << endl;
+	return traits::eof();
+}
+
+template <class charT, class traits>
+inline typename basic_netbuf<charT, traits>::int_type
+basic_netbuf<charT, traits>::uflow() {
+	in_sync();
+	if(gptr()<egptr()) {
+		int_type ans = traits::to_int_type(*gptr());
+		gbump(1);
+		return ans;
+	}
+//	cout << "UNDERFLOW" << endl;
+	return traits::eof();
+}
+
+template <class charT, class traits>
+inline typename basic_netbuf<charT, traits>::int_type
+basic_netbuf<charT, traits>::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 <class charT, class traits>
+//inline basic_netbuf<charT, traits>::_Myt //not supported - don't know details of expected implementation
+//basic_netbuf<charT, traits>::setbuf(char_type* /*s*/, streamsize /*n*/) {
+//	return this;
+//}
+
+template <class charT, class traits>
+typename basic_netbuf<charT, traits>::pos_type
+basic_netbuf<charT, traits>::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<eback() || egptr()<newg) || dop && (newp<pbase() || epptr()<newp))
+		return pos_type(off_type(-1));
+	if(dog)
+		gbump(gb);
+	if(dop) {
+		pbump(pb);
+		return pptr()-pbase();
+	} else {
+		return gptr()-eback();
+	}
+}
+
+template <class charT, class traits>
+inline int
+basic_netbuf<charT, traits>::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<NumOutputs; i++) {
 		primIDs[i]=oprimitiveID_UNDEF;
 		open[i]=false;
 	}
-
-	//need to register any events which we might be sending or receiving
-	EventTranslator::registerPrototype<EventBase>();
-	EventTranslator::registerPrototype<LocomotionEvent>();
-	EventTranslator::registerPrototype<TextMsgEvent>();
-	EventTranslator::registerPrototype<VisionObjectEvent>();
 } 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; i<NumOutputs; i++)
@@ -140,14 +151,18 @@
 		
 		//Setup wireless
 		wireless = new Wireless();
-		sout=wireless->socket(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; output<LEDOffset+NumLEDs; output++)
+				state->outputs[output]=motman->getOutputCmd(output).value;
+			for(uint output=BinJointOffset; output<BinJointOffset+NumBinJoints; output++)
+				state->outputs[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<unsigned int>& fakes = RobotInfo::capabilities.getFakeOutputs();
+			for(std::set<unsigned int>::const_iterator it=fakes.begin(); it!=fakes.end(); ++it)
+				state->outputs[*it]=motman->getOutputCmd(*it).value;
+			
 		} else {
 			for(unsigned int f=0; f<NumFrames; f++)
 				for(unsigned int i=0; i<NumOutputs; i++)
@@ -600,10 +624,9 @@
 		unsigned int used=0; //but only copy open joints (so main does ears on 210, motion does everything else)
 		for(unsigned int i=PIDJointOffset; i<PIDJointOffset+NumPIDJoints; i++)
 			if(open[i]) {
-				float cal=config->motion.calibration[i-PIDJointOffset];
 				OJointCommandValue2* jval = reinterpret_cast<OJointCommandValue2*>(cmdVecData->GetData(used)->value);
 				for(unsigned int frame=0; frame<NumFrames; frame++)
-					jval[frame].value = (slongword)(outputs[frame][i]/cal*1.0e6f);
+					jval[frame].value = (slongword)(outputs[frame][i]*1.0e6f);
 				used++;
 			}
 		if(isERS7) {
@@ -715,6 +738,7 @@
 		return;
 	}
 
+#ifndef NO_PROFILING
 	static unsigned int id=-1U;
 	Profiler::Timer timer;
 	if(ProcessID::getID()==ProcessID::MotionProcess) {
@@ -726,7 +750,8 @@
 			id=mainProfiler->getNewID("GotSensorFrame()");
 		timer.setID(id,&mainProfiler->prof);
 	}
-	TimeET t;
+#endif
+	//TimeET t;
 
 	OSensorFrameVectorData* rawsensor = reinterpret_cast<OSensorFrameVectorData*>(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<unsigned int*>(&tv);
-			unsigned int seed=tm[0]+tm[1];
-			for(unsigned int i=0; i<NumPIDJoints; i++) { //joint positions
-				unsigned int * x=reinterpret_cast<unsigned int*>(&state->outputs[i]);
-				seed+=(*x)<<((i%sizeof(unsigned int))*8);
-			}
-			for(unsigned int i=0; i<NumPIDJoints; i++) { //joint forces
-				unsigned int * x=reinterpret_cast<unsigned int*>(&state->pidduties[i]);
-				seed+=(*x)<<((i%sizeof(unsigned int))*8);
-			}
-			for(unsigned int i=0; i<NumSensors; i++) {
-				unsigned int * x=reinterpret_cast<unsigned int*>(&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<NumOutputs; j++)
-				open[j]=to_open[j] && ERS210Info::IsRealERS210[j];
-		} else if(strcmp(robotDesignStr,"ERS-220")==0) {
-			for(unsigned int j=0; j<NumOutputs; j++)
-				open[j]=to_open[j] && ERS220Info::IsRealERS220[j];
-		} else if(strcmp(robotDesignStr,"ERS-7")==0) {
-			for(unsigned int j=0; j<NumOutputs; j++)
-				open[j]=to_open[j] && ERS7Info::IsRealERS7[j];
-		} else {
-			cout << "MMCombo::SetupOutputs - ERROR: Unrecognized model: "<<robotDesignStr<<"\nSorry..."<<endl;
-			return;
-		}
-	}
+	const std::set<unsigned int>& fakes = RobotInfo::capabilities.getFakeOutputs();
+	for(unsigned int j=0; j<NumOutputs; j++)
+		open[j] = to_open[j] && fakes.find(j)==fakes.end();
 	
 	// count how many we're opening
 	for(unsigned int j=0; j<NumOutputs; j++)
@@ -1082,7 +1070,7 @@
 				OCommandInfo* info = cmdVecData->GetInfo(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; j<ERS7Info::FaceLEDPanelOffset; j++)
 				if(open[j]) {
@@ -1145,10 +1133,41 @@
 }
 
 void
+MMCombo::initRNG() {
+	//seed the random number generator with time value and sensor noise
+	if(config->main.seed_rng) {
+		double tv=TimeET().Value(); //current time with nanosecond resolution
+		unsigned int * tm=reinterpret_cast<unsigned int*>(&tv);
+		unsigned int seed=tm[0]+tm[1];
+		for(unsigned int i=0; i<NumPIDJoints; i++) { //joint positions
+			unsigned int * x=reinterpret_cast<unsigned int*>(&state->outputs[i]);
+			seed+=(*x)<<((i%sizeof(unsigned int))*8);
+		}
+		for(unsigned int i=0; i<NumPIDJoints; i++) { //joint forces
+			unsigned int * x=reinterpret_cast<unsigned int*>(&state->pidduties[i]);
+			seed+=(*x)<<((i%sizeof(unsigned int))*8);
+		}
+		for(unsigned int i=0; i<NumSensors; i++) {
+			unsigned int * x=reinterpret_cast<unsigned int*>(&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<Config::vision_config::gain_levels> GainSetting;
+	OPrimitiveID fbkID = 0;
+	if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){
+		std::cout << "Open FbkImageSensor failure." << std::endl;
+	} else if(const GainSetting* v=dynamic_cast<const GainSetting*>(&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<Config::vision_config::shutter_speeds> SpeedSetting;
+	OPrimitiveID fbkID = 0;
+	if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){
+		std::cout << "Open FbkImageSensor failure." << std::endl;
+	} else if(const SpeedSetting* v=dynamic_cast<const SpeedSetting*>(&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<Config::vision_config::white_balance_levels> WBSetting;
+	OPrimitiveID fbkID = 0;
+	if(OPENR::OpenPrimitive(CameraLocator, &fbkID) != oSUCCESS){
+		std::cerr << "Open FbkImageSensor failure." << std::endl;
+	} else if(const WBSetting* v=dynamic_cast<const WBSetting*>(&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<EventBase>(); //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 <sys/types.h>
+
+/* 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 \<digit> matches <digit>.
+   If not set, then \<digit> 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 internal error.  Also return register
+   information in REGS (if REGS and BUFFER->no_sub are nonzero).  */
+extern int re_search (struct re_pattern_buffer *__buffer, const char *__string,
+		      int __length, int __start, int __range,
+		      struct re_registers *__regs);
+
+
+/* Like `re_search', but search in the concatenation of STRING1 and
+   STRING2.  Also, stop searching at index START + STOP.  */
+extern int re_search_2 (struct re_pattern_buffer *__buffer,
+			const char *__string1, int __length1,
+			const char *__string2, int __length2, int __start,
+			int __range, struct re_registers *__regs, int __stop);
+
+
+/* Like `re_search', but return how many characters in STRING the regexp
+   in BUFFER matched, starting at position START.  */
+extern int re_match (struct re_pattern_buffer *__buffer, const char *__string,
+		     int __length, int __start, struct re_registers *__regs);
+
+
+/* Relates to `re_match' as `re_search_2' relates to `re_search'.  */
+extern int re_match_2 (struct re_pattern_buffer *__buffer,
+		       const char *__string1, int __length1,
+		       const char *__string2, int __length2, int __start,
+		       struct re_registers *__regs, int __stop);
+
+
+/* Set REGS to hold NUM_REGS registers, storing them in STARTS and
+   ENDS.  Subsequent matches using BUFFER and REGS will use this memory
+   for recording register information.  STARTS and ENDS must be
+   allocated with malloc, and must each be at least `NUM_REGS * sizeof
+   (regoff_t)' bytes long.
+
+   If NUM_REGS == 0, then subsequent matches should allocate their own
+   register data.
+
+   Unless this function is called, the first search or match using
+   PATTERN_BUFFER will allocate its own register data, without
+   freeing the old data.  */
+extern void re_set_registers (struct re_pattern_buffer *__buffer,
+			      struct re_registers *__regs,
+			      unsigned int __num_regs,
+			      regoff_t *__starts, regoff_t *__ends);
+
+#if defined _REGEX_RE_COMP || defined _LIBC
+# ifndef _CRAY
+/* 4.2 bsd compatibility.  */
+extern char *re_comp (const char *);
+extern int re_exec (const char *);
+# endif
+#endif
+
+/* GCC 2.95 and later have "__restrict"; C99 compilers have
+   "restrict", and "configure" may have defined "restrict".  */
+#ifndef __restrict
+# if ! (2 < __GNUC__ || (2 == __GNUC__ && 95 <= __GNUC_MINOR__))
+#  if defined restrict || 199901L <= __STDC_VERSION__
+#   define __restrict restrict
+#  else
+#   define __restrict
+#  endif
+# endif
+#endif
+/* gcc 3.1 and up support the [restrict] syntax.  */
+#ifndef __restrict_arr
+# if (__GNUC__ > 3 || (__GNUC__ == 3 && __GNUC_MINOR__ >= 1)) \
+     && !defined __GNUG__
+#  define __restrict_arr __restrict
+# else
+#  define __restrict_arr
+# endif
+#endif
+
+/* POSIX compatibility.  */
+extern int regcomp (regex_t *__restrict __preg,
+		    const char *__restrict __pattern,
+		    int __cflags);
+
+extern int regexec (const regex_t *__restrict __preg,
+		    const char *__restrict __string, size_t __nmatch,
+		    regmatch_t __pmatch[__restrict_arr],
+		    int __eflags);
+
+extern size_t regerror (int __errcode, const regex_t *__restrict __preg,
+			char *__restrict __errbuf, size_t __errbuf_size);
+
+extern void regfree (regex_t *__preg);
+
+
+#ifdef __cplusplus
+}
+#endif	/* C++ */
+
+#endif /* regex.h */
Binary files ../Tekkotsu_3.0/aperios/lib/libregex.a and ./aperios/lib/libregex.a differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/benchmarks/profilerun_ERS210A_4.0.txt ./docs/benchmarks/profilerun_ERS210A_4.0.txt
--- ../Tekkotsu_3.0/docs/benchmarks/profilerun_ERS210A_4.0.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/benchmarks/profilerun_ERS210A_4.0.txt	2007-11-21 17:20:20.000000000 -0500
@@ -0,0 +1,134 @@
+Setup:
+  Default build for ERS-2xx (TGT_ERS2xx)
+  Pink ball in view (8.5in from snout)
+  Press power button, start timer
+  Telnet to system console (port 59000)
+  Connect ControllerGUI
+  STARTUP script:
+    Launch StareAtBallBehavior (leave E-Stop ON)
+    Navigate to Status Reports -> Profiler
+  Wait until 5 minutes from initial press of power button.
+  Recorded profiler run shown below
+
+~~~ Main: ~~~
+Profiling information since: 19.905465 to 298.074142
+PowerEvent():
+        52 calls
+        0.447615 ms avg
+        0.277876 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        5190.932231 ms avg inter (0.192644 fps)
+        4572.906738 ms exp.avg (0.218679 fps)
+        Exec: 0 0 49 2 0 1 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 
+        Inter: 0 0 0 0 0 0 0 0 0 0 0 1 0 8 0 0 0 0 0 0 5 13 0 0 1 4 0 5 0 3 0 11 
+ReadySendJoints():
+        2160 calls
+        1.049186 ms avg
+        0.944754 ms exp.avg
+        0.001409 ms avg child time (0.100000%)
+        128.276519 ms avg inter (7.795659 fps)
+        127.686737 ms exp.avg (7.831667 fps)
+        Exec: 0 0 649 1496 14 1 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 
+        Inter: 0 0 0 1 1 0 0 1 0 0 1745 409 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotAudio():
+        8625 calls
+        0.347871 ms avg
+        0.338311 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.108230 ms avg inter (31.144663 fps)
+        31.832664 ms exp.avg (31.414272 fps)
+        Exec: 0 0 7877 746 2 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 
+        Inter: 0 0 0 0 0 0 5 8611 6 0 0 0 0 0 0 0 2 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotImage():
+        6881 calls
+        14.496140 ms avg
+        15.426720 ms exp.avg
+        11.493344 ms avg child time (79.200000%)
+        40.161593 ms avg inter (24.899411 fps)
+        39.932194 ms exp.avg (25.042450 fps)
+        Exec: 0 0 1 17 3 2001 4858 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+        Inter: 0 0 0 0 0 0 3 12 6864 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+BallDetection::processEvent():
+        6865 calls
+        11.520323 ms avg
+        12.491241 ms exp.avg
+        9.596301 ms avg child time (83.200000%)
+        40.066053 ms avg inter (24.958785 fps)
+        39.959042 ms exp.avg (25.025623 fps)
+        Exec: 3 1 0 1 0 5000 1860 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 
+        Inter: 0 3 1 0 0 0 1 11 6848 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+RegionGenerator::calcImage(...):
+        6860 calls
+        9.603292 ms avg
+        10.349340 ms exp.avg
+        6.004879 ms avg child time (62.500000%)
+        40.096281 ms avg inter (24.939969 fps)
+        39.964394 ms exp.avg (25.022274 fps)
+        Exec: 0 0 0 0 0 5149 1711 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 
+        Inter: 0 0 0 0 0 0 1 10 6848 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+RLEGenerator::calcImage(...):
+        6860 calls
+        6.004879 ms avg
+        6.287493 ms exp.avg
+        4.074106 ms avg child time (67.800000%)
+        40.096223 ms avg inter (24.940005 fps)
+        39.964558 ms exp.avg (25.022171 fps)
+        Exec: 0 0 0 0 3481 3362 17 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 
+        Inter: 0 0 0 0 0 0 1 10 6848 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+SegmentedColorGenerator::calcImage(...):
+        6860 calls
+        4.074106 ms avg
+        3.919755 ms exp.avg
+        0.024344 ms avg child time (0.500000%)
+        40.096427 ms avg inter (24.939878 fps)
+        39.964676 ms exp.avg (25.022097 fps)
+        Exec: 0 0 0 0 5175 1685 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 
+        Inter: 0 0 0 0 0 0 1 10 6848 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+RawCameraGenerator::calcImage(...):
+        20580 calls
+        0.008115 ms avg
+        0.006116 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        13.362241 ms avg inter (74.837747 fps)
+        11.208715 ms exp.avg (89.216286 fps)
+        Exec: 13644 6906 11 19 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 
+        Inter: 6640 7041 16 23 0 0 2 9 6848 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+Bucket distribution (in ms):
+        0<0.00802, <0.133, <0.686, <2.2, <5.43, <11.4, <21.2, <36.4, <58.7, <90, <132, <188, <260, <352, <465, <604, <772, <973, <1.21e+03, <1.49e+03, <1.82e+03, <2.19e+03, <2.63e+03, <3.12e+03, <3.68e+03, <4.31e+03, <5.03e+03, <5.82e+03, <6.71e+03, <7.7e+03, <8.79e+03, <1e+04, 
+
+~~~ Motion: ~~~
+Profiling information since: 20.268370 to 298.097919
+ReadySendJoints():
+        8641 calls
+        6.176780 ms avg
+        7.893387 ms exp.avg
+        0.000415 ms avg child time (0.000000%)
+        32.061502 ms avg inter (31.190054 fps)
+        32.132229 ms exp.avg (31.121399 fps)
+        Exec: 0 0 0 9 5081 3509 28 1 0 11 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+        Inter: 0 1 0 0 0 0 6 8615 4 9 4 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotSensorFrame():
+        8651 calls
+        2.435364 ms avg
+        2.399463 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.024923 ms avg inter (31.225680 fps)
+        33.179947 ms exp.avg (30.138687 fps)
+        Exec: 0 0 1 4752 3778 117 2 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 
+        Inter: 0 0 0 1 5 11 9 8596 15 4 8 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+Bucket distribution (in ms):
+        0<0.00802, <0.133, <0.686, <2.2, <5.43, <11.4, <21.2, <36.4, <58.7, <90, <132, <188, <260, <352, <465, <604, <772, <973, <1.21e+03, <1.49e+03, <1.82e+03, <2.19e+03, <2.63e+03, <3.12e+03, <3.68e+03, <4.31e+03, <5.03e+03, <5.82e+03, <6.71e+03, <7.7e+03, <8.79e+03, <1e+04, 
+
+~~~ Sound: ~~~
+Profiling information since: 19.842183 to 298.103381
+doSendSound():
+        56 calls
+        1.806000 ms avg
+        2.533968 ms exp.avg
+        0.063429 ms avg child time (3.500000%)
+        4949.283143 ms avg inter (0.202049 fps)
+        35061.843750 ms exp.avg (0.028521 fps)
+        Exec: 2 1 11 33 6 2 1 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 
+        Inter: 0 1 0 0 1 0 0 49 2 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 1 
+Bucket distribution (in ms):
+        0<0.00802, <0.133, <0.686, <2.2, <5.43, <11.4, <21.2, <36.4, <58.7, <90, <132, <188, <260, <352, <465, <604, <772, <973, <1.21e+03, <1.49e+03, <1.82e+03, <2.19e+03, <2.63e+03, <3.12e+03, <3.68e+03, <4.31e+03, <5.03e+03, <5.82e+03, <6.71e+03, <7.7e+03, <8.79e+03, <1e+04, 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/benchmarks/profilerun_ERS7_4.0.txt ./docs/benchmarks/profilerun_ERS7_4.0.txt
--- ../Tekkotsu_3.0/docs/benchmarks/profilerun_ERS7_4.0.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/benchmarks/profilerun_ERS7_4.0.txt	2007-11-21 17:20:20.000000000 -0500
@@ -0,0 +1,134 @@
+Setup:
+  Default build for ERS-7 (TGT_ERS7)
+  Pink ball in view (8.5in from snout)
+  Press power button, start timer
+  Telnet to system console (port 59000)
+  Connect ControllerGUI
+  STARTUP script:
+    Launch StareAtBallBehavior (leave E-Stop ON)
+    Navigate to Status Reports -> Profiler
+  Wait until 5 minutes from initial press of power button.
+  Recorded profiler run shown below
+
+~~~ Main: ~~~
+Profiling information since: 18.204827 to 297.970325
+ReadySendJoints():
+        1 calls
+        0.005000 ms avg
+        0.005000 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        0.000000 ms avg inter (Inf fps)
+        0.000000 ms exp.avg (Inf fps)
+        Exec: 1 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 0 0 
+        Inter: 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 0 0 0 
+GotAudio():
+        8712 calls
+        0.128476 ms avg
+        0.122860 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.018388 ms avg inter (31.232053 fps)
+        31.956676 ms exp.avg (31.292366 fps)
+        Exec: 0 6734 1967 11 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 
+        Inter: 0 0 0 1 0 1 1 8705 1 0 0 1 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotImage():
+        8354 calls
+        6.426067 ms avg
+        5.666499 ms exp.avg
+        4.872636 ms avg child time (75.800000%)
+        33.364011 ms avg inter (29.972415 fps)
+        33.722668 ms exp.avg (29.653643 fps)
+        Exec: 0 6 22 4 3571 4751 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 
+        Inter: 0 0 0 1 0 2 0 6921 1427 0 0 1 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+PowerEvent():
+        8 calls
+        31.721500 ms avg
+        80.835716 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        31368.884500 ms avg inter (0.031879 fps)
+        36474.906250 ms exp.avg (0.027416 fps)
+        Exec: 0 3 3 1 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+        Inter: 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 0 0 7 
+BallDetection::processEvent():
+        8327 calls
+        4.888475 ms avg
+        4.407200 ms exp.avg
+        4.023273 ms avg child time (82.300000%)
+        33.336470 ms avg inter (29.997177 fps)
+        33.687176 ms exp.avg (29.684889 fps)
+        Exec: 4 0 1 0 5958 2364 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 
+        Inter: 2 2 0 0 0 1 1 6899 1421 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+RegionGenerator::calcImage(...):
+        8322 calls
+        4.025688 ms avg
+        3.653399 ms exp.avg
+        2.717215 ms avg child time (67.400000%)
+        33.356094 ms avg inter (29.979529 fps)
+        33.687759 ms exp.avg (29.684372 fps)
+        Exec: 0 0 0 0 6397 1925 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 
+        Inter: 0 0 0 0 0 1 0 6899 1421 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+RLEGenerator::calcImage(...):
+        8322 calls
+        2.717215 ms avg
+        2.497596 ms exp.avg
+        1.997289 ms avg child time (73.500000%)
+        33.356119 ms avg inter (29.979507 fps)
+        33.687740 ms exp.avg (29.684389 fps)
+        Exec: 0 0 0 0 8316 6 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 
+        Inter: 0 0 0 0 0 1 0 6899 1421 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+SegmentedColorGenerator::calcImage(...):
+        8322 calls
+        1.997289 ms avg
+        1.834098 ms exp.avg
+        0.013444 ms avg child time (0.600000%)
+        33.356100 ms avg inter (29.979524 fps)
+        33.687885 ms exp.avg (29.684261 fps)
+        Exec: 0 0 0 6233 2089 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 
+        Inter: 0 0 0 0 0 1 0 6899 1421 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+RawCameraGenerator::calcImage(...):
+        24966 calls
+        0.004481 ms avg
+        0.003650 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        11.117756 ms avg inter (89.946206 fps)
+        9.556930 ms exp.avg (104.636116 fps)
+        Exec: 19109 5854 3 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 
+        Inter: 8321 8320 3 0 0 1 0 6899 1421 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+Bucket distribution (in ms):
+        0<0.00802, <0.133, <0.686, <2.2, <5.43, <11.4, <21.2, <36.4, <58.7, <90, <132, <188, <260, <352, <465, <604, <772, <973, <1.21e+03, <1.49e+03, <1.82e+03, <2.19e+03, <2.63e+03, <3.12e+03, <3.68e+03, <4.31e+03, <5.03e+03, <5.82e+03, <6.71e+03, <7.7e+03, <8.79e+03, <1e+04, 
+
+~~~ Motion: ~~~
+Profiling information since: 18.682721 to 297.973808
+ReadySendJoints():
+        8694 calls
+        1.909765 ms avg
+        1.547360 ms exp.avg
+        0.000244 ms avg child time (0.000000%)
+        32.090481 ms avg inter (31.161889 fps)
+        32.025234 ms exp.avg (31.225378 fps)
+        Exec: 0 0 15 6592 2068 2 0 0 0 14 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+        Inter: 0 1 0 0 0 0 1 8673 1 14 2 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+GotSensorFrame():
+        8707 calls
+        0.876861 ms avg
+        0.858722 ms exp.avg
+        0.000000 ms avg child time (0.000000%)
+        32.043887 ms avg inter (31.207200 fps)
+        31.944118 ms exp.avg (31.304667 fps)
+        Exec: 0 0 168 8370 168 0 1 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 
+        Inter: 0 0 2 2 12 6 7 8659 1 5 11 1 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 0 
+Bucket distribution (in ms):
+        0<0.00802, <0.133, <0.686, <2.2, <5.43, <11.4, <21.2, <36.4, <58.7, <90, <132, <188, <260, <352, <465, <604, <772, <973, <1.21e+03, <1.49e+03, <1.82e+03, <2.19e+03, <2.63e+03, <3.12e+03, <3.68e+03, <4.31e+03, <5.03e+03, <5.82e+03, <6.71e+03, <7.7e+03, <8.79e+03, <1e+04, 
+
+~~~ Sound: ~~~
+Profiling information since: 18.131377 to 297.974561
+doSendSound():
+        50 calls
+        0.585760 ms avg
+        0.687861 ms exp.avg
+        0.031900 ms avg child time (5.400000%)
+        5582.170860 ms avg inter (0.179142 fps)
+        35323.535156 ms exp.avg (0.028310 fps)
+        Exec: 3 0 27 20 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 
+        Inter: 0 1 1 0 0 0 0 43 2 0 0 0 0 0 0 0 0 1 0 0 0 0 0 0 0 0 0 0 0 0 0 1 
+Bucket distribution (in ms):
+        0<0.00802, <0.133, <0.686, <2.2, <5.43, <11.4, <21.2, <36.4, <58.7, <90, <132, <188, <260, <352, <465, <604, <772, <973, <1.21e+03, <1.49e+03, <1.82e+03, <2.19e+03, <2.63e+03, <3.12e+03, <3.68e+03, <4.31e+03, <5.03e+03, <5.82e+03, <6.71e+03, <7.7e+03, <8.79e+03, <1e+04, 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/builddocs ./docs/builddocs
--- ../Tekkotsu_3.0/docs/builddocs	2006-02-01 16:08:58.000000000 -0500
+++ ./docs/builddocs	2007-11-09 15:36:36.000000000 -0500
@@ -13,9 +13,9 @@
 always_detailed_sec="ALWAYS_DETAILED_SEC = NO";
 generate_treeview="GENERATE_TREEVIEW = NO";
 searchengine="SEARCHENGINE = NO";
-enabled_sections="ENABLED_SECTIONS += INTERNAL";
+#enabled_sections="ENABLED_SECTIONS += INTERNAL";
 input="$src";
-exclude="$input/docs $input/build $input/TinyFTPD $input/ms $input/tools $input/contrib $input/deprecated $input/Shared/jpeg-6b $input/Motion/Spline.h $input/Motion/gvector.h $input/Motion/Path.h $input/SoundPlay/WAV.h $input/SoundPlay/WAV.cc $input/Wireless/ionetstream.h $input/Motion/OldKinematics.h $input/Motion/OldKinematics.cc $input/Motion/Geometry.h $input/Shared/Util.h $input/project/templates $input/DualCoding";
+exclude="$input/docs $input/build $input/TinyFTPD $input/ms $input/tools $input/contrib $input/deprecated $input/Shared/jpeg-6b $input/Motion/Spline.h $input/Motion/gvector.h $input/Motion/Path.h $input/SoundPlay/WAV.h $input/SoundPlay/WAV.cc $input/Wireless/ionetstream.h $input/Motion/OldKinematics.h $input/Motion/OldKinematics.cc $input/Motion/Geometry.h $input/Shared/Util.h $input/DualCoding $input/local";
 
 while [ $# -gt 0 ] ; do
 	case $1 in
@@ -73,16 +73,30 @@
 touch doxygenbuildcfg;
 if [ -f "generated/tekkotsu.tag" ] ; then
 echo "TAGFILES += generated/tekkotsu.tag=.." >> doxygenbuildcfg
+echo "INCLUDE_PATH += $src" >> doxygenbuildcfg
 fi;
 mkdir -p generated/html;
+
 doxygen newmat.doxycfg;
 cp ${target}/newmat/annotated.html ${target}/newmat/main.html
 doxygen roboop.doxycfg;
 cp ${target}/roboop/annotated.html ${target}/roboop/main.html
 doxygen dualcoding.doxycfg;
-cp ${target}/dualcoding/annotated.html ${target}/dualcoding/main.html
+cp ${target}/dualcoding/namespaceDualCoding.html ${target}/dualcoding/main.html
+
 mv doxygenbuildcfg.tmp doxygenbuildcfg
 doxygen doxygencfg ;
+
+mv doxygenbuildcfg doxygenbuildcfg.tmp;
+touch doxygenbuildcfg;
+if [ -f "generated/tekkotsu.tag" ] ; then
+echo "TAGFILES += generated/tekkotsu.tag=.." >> doxygenbuildcfg
+echo "INCLUDE_PATH += $src" >> doxygenbuildcfg
+fi;
+doxygen hal.doxycfg;
+cp ${target}/hal/annotated.html ${target}/hal/main.html
+mv doxygenbuildcfg.tmp doxygenbuildcfg
+
 printf "done\n";
 
 if [ $search -ne 0 ] ; then
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/doxygencfg ./docs/doxygencfg
--- ../Tekkotsu_3.0/docs/doxygencfg	2006-10-03 23:16:57.000000000 -0400
+++ ./docs/doxygencfg	2007-11-21 02:03:36.000000000 -0500
@@ -1,4 +1,4 @@
-# Doxyfile 1.4.7
+# Doxyfile 1.5.4
 
 # This file describes the settings to be used by the documentation system
 # doxygen (www.doxygen.org) for a project
@@ -14,6 +14,14 @@
 # Project related configuration options
 #---------------------------------------------------------------------------
 
+# This tag specifies the encoding used for all characters in the config file that 
+# follow. The default is UTF-8 which is also the encoding used for all text before 
+# the first occurrence of this tag. Doxygen uses libiconv (or the iconv built into 
+# libc) for the transcoding. See http://www.gnu.org/software/libiconv for the list of 
+# possible encodings.
+
+DOXYFILE_ENCODING      = UTF-8
+
 # The PROJECT_NAME tag is a single word (or a sequence of words surrounded 
 # by quotes) that should identify the project.
 
@@ -23,7 +31,7 @@
 # This could be handy for archiving the generated documentation or 
 # if some version control system is used.
 
-PROJECT_NUMBER         = 3.0
+PROJECT_NUMBER         = 4.0
 
 # The OUTPUT_DIRECTORY tag is used to specify the (relative or absolute) 
 # base path where the generated documentation will be put. 
@@ -46,24 +54,14 @@
 # documentation generated by doxygen is written. Doxygen will use this 
 # information to generate all constant output in the proper language. 
 # The default language is English, other supported languages are: 
-# Brazilian, Catalan, Chinese, Chinese-Traditional, Croatian, Czech, Danish, 
-# Dutch, Finnish, French, German, Greek, Hungarian, Italian, Japanese, 
-# Japanese-en (Japanese with English messages), Korean, Korean-en, Norwegian, 
-# Polish, Portuguese, Romanian, Russian, Serbian, Slovak, Slovene, Spanish, 
-# Swedish, and Ukrainian.
+# Afrikaans, Arabic, Brazilian, Catalan, Chinese, Chinese-Traditional, 
+# Croatian, Czech, Danish, Dutch, Finnish, French, German, Greek, Hungarian, 
+# Italian, Japanese, Japanese-en (Japanese with English messages), Korean, 
+# Korean-en, Lithuanian, Norwegian, Polish, Portuguese, Romanian, Russian, 
+# Serbian, Slovak, Slovene, Spanish, Swedish, and Ukrainian.
 
 OUTPUT_LANGUAGE        = English
 
-# This tag can be used to specify the encoding used in the generated output. 
-# The encoding is not always determined by the language that is chosen, 
-# but also whether or not the output is meant for Windows or non-Windows users. 
-# In case there is a difference, setting the USE_WINDOWS_ENCODING tag to YES 
-# forces the Windows encoding (this is the default for the Windows binary), 
-# whereas setting the tag to NO uses a Unix-style encoding (the default for 
-# all platforms other than Windows).
-
-USE_WINDOWS_ENCODING   = NO
-
 # If the BRIEF_MEMBER_DESC tag is set to YES (the default) Doxygen will 
 # include brief member descriptions after the members that are listed in 
 # the file and class documentation (similar to JavaDoc). 
@@ -137,11 +135,19 @@
 # If the JAVADOC_AUTOBRIEF tag is set to YES then Doxygen 
 # will interpret the first line (until the first dot) of a JavaDoc-style 
 # comment as the brief description. If set to NO, the JavaDoc 
-# comments will behave just like the Qt-style comments (thus requiring an 
-# explicit @brief command for a brief description.
+# comments will behave just like regular Qt-style comments 
+# (thus requiring an explicit @brief command for a brief description.)
 
 JAVADOC_AUTOBRIEF      = NO
 
+# If the QT_AUTOBRIEF tag is set to YES then Doxygen will 
+# interpret the first line (until the first dot) of a Qt-style 
+# comment as the brief description. If set to NO, the comments 
+# will behave just like regular Qt-style comments (thus requiring 
+# an explicit \brief command for a brief description.)
+
+QT_AUTOBRIEF           = NO
+
 # The MULTILINE_CPP_IS_BRIEF tag can be set to YES to make Doxygen 
 # treat a multi-line C++ special comment block (i.e. a block of //! or /// 
 # comments) as a brief description. This used to be the default behaviour. 
@@ -206,6 +212,17 @@
 
 BUILTIN_STL_SUPPORT    = YES
 
+# If you use Microsoft's C++/CLI language, you should set this option to YES to
+# enable parsing support.
+
+CPP_CLI_SUPPORT        = NO
+
+# Set the SIP_SUPPORT tag to YES if your project consists of sip sources only. 
+# Doxygen will parse them like normal C++ but will assume all classes use public 
+# instead of private inheritance when no explicit protection keyword is present.
+
+SIP_SUPPORT            = NO
+
 # If member grouping is used in the documentation and the DISTRIBUTE_GROUP_DOC 
 # tag is set to YES, then doxygen will reuse the documentation of the first 
 # member in the group (if any) for the other members of the group. By default 
@@ -221,6 +238,16 @@
 
 SUBGROUPING            = YES
 
+# When TYPEDEF_HIDES_STRUCT is enabled, a typedef of a struct (or union) is 
+# documented as struct with the name of the typedef. So 
+# typedef struct TypeS {} TypeT, will appear in the documentation as a struct 
+# with name TypeT. When disabled the typedef will appear as a member of a file, 
+# namespace, or class. And the struct will be named TypeS. This can typically 
+# be useful for C code where the coding convention is that all structs are 
+# typedef'ed and only the typedef is referenced never the struct's name.
+
+TYPEDEF_HIDES_STRUCT   = NO
+
 #---------------------------------------------------------------------------
 # Build related configuration options
 #---------------------------------------------------------------------------
@@ -256,6 +283,13 @@
 
 EXTRACT_LOCAL_METHODS  = NO
 
+# If this flag is set to YES, the members of anonymous namespaces will be extracted 
+# and appear in the documentation as a namespace called 'anonymous_namespace{file}', 
+# where file will be replaced with the base name of the file that contains the anonymous 
+# namespace. By default anonymous namespace are hidden.
+
+EXTRACT_ANON_NSPACES   = NO
+
 # If the HIDE_UNDOC_MEMBERS tag is set to YES, Doxygen will hide all 
 # undocumented members of documented classes, files or namespaces. 
 # If set to NO (the default) these members will be included in the 
@@ -401,7 +435,7 @@
 # provided by doxygen. Whatever the program writes to standard output 
 # is used as the file version. See the manual for examples.
 
-FILE_VERSION_FILTER    = "/bin/sh ../tools/versionFilter"
+FILE_VERSION_FILTER    = "/bin/sh ../tools/versionFilter "
 
 #---------------------------------------------------------------------------
 # configuration options related to warning and progress messages
@@ -466,12 +500,19 @@
 #builddocs will set this in doxygenbuildcfg
 #INPUT                  = 
 
+# This tag can be used to specify the character encoding of the source files that 
+# doxygen parses. Internally doxygen uses the UTF-8 encoding, which is also the default 
+# input encoding. Doxygen uses libiconv (or the iconv built into libc) for the transcoding. 
+# See http://www.gnu.org/software/libiconv for the list of possible encodings.
+
+INPUT_ENCODING         = UTF-8
+
 # If the value of the INPUT tag contains directories, you can use the 
 # FILE_PATTERNS tag to specify one or more wildcard pattern (like *.cpp 
 # and *.h) to filter out the source-files in the directories. If left 
 # blank the following patterns are tested: 
 # *.c *.cc *.cxx *.cpp *.c++ *.java *.ii *.ixx *.ipp *.i++ *.inl *.h *.hh *.hxx 
-# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py
+# *.hpp *.h++ *.idl *.odl *.cs *.php *.php3 *.inc *.m *.mm *.py *.f90
 
 FILE_PATTERNS          = 
 
@@ -505,10 +546,16 @@
                          */Shared/newmat/* \
                          */Motion/roboop/* \
                          */project/* \
-                         */local/* \
                          */aperios/* \
                          */Behaviors/Demos/*
 
+# The EXCLUDE_SYMBOLS tag can be used to specify one or more symbol names 
+# (namespaces, classes, functions, etc.) that should be excluded from the output. 
+# The symbol name can be a fully qualified name, a word, or if the wildcard * is used, 
+# a substring. Examples: ANamespace, AClass, AClass::ANamespace, ANamespace::*Test
+
+EXCLUDE_SYMBOLS        = 
+
 # The EXAMPLE_PATH tag can be used to specify one or more files or 
 # directories that contain example code fragments that are included (see 
 # the \include command).
@@ -567,7 +614,9 @@
 # If the SOURCE_BROWSER tag is set to YES then a list of source files will 
 # be generated. Documented entities will be cross-referenced with these sources. 
 # Note: To get rid of all source code in the generated output, make sure also 
-# VERBATIM_HEADERS is set to NO.
+# VERBATIM_HEADERS is set to NO. If you have enabled CALL_GRAPH or CALLER_GRAPH 
+# then you must also enable this option. If you don't then doxygen will produce 
+# a warning and turn it on anyway
 
 SOURCE_BROWSER         = YES
 
@@ -694,6 +743,14 @@
 
 GENERATE_HTMLHELP      = NO
 
+# If the HTML_DYNAMIC_SECTIONS tag is set to YES then the generated HTML 
+# documentation will contain sections that can be hidden and shown after the 
+# page has loaded. For this to work a browser that supports 
+# JavaScript and DHTML is required (for instance Mozilla 1.0+, Firefox 
+# Netscape 6.0+, Internet explorer 5.0+, Konqueror, or Safari).
+
+HTML_DYNAMIC_SECTIONS  = NO
+
 # If the GENERATE_HTMLHELP tag is set to YES, the CHM_FILE tag can 
 # be used to specify the file name of the resulting .chm file. You 
 # can add a path in front of the file if the result should not be 
@@ -1010,6 +1067,7 @@
 # contain include files that are not input files but should be processed by 
 # the preprocessor.
 
+# This is set in builddocs for the sub-packages like DualCoding
 INCLUDE_PATH           = 
 
 # You can use the INCLUDE_FILE_PATTERNS tag to specify one or more wildcard 
@@ -1029,8 +1087,9 @@
 
 PREDEFINED             = __cplusplus \
                          DEBUG \
-                         PLATFORM_APERIOS \
                          TGT_ERS7 \
+                         PLATFORM_LOCAL \
+                         HAVE_ICE \
                          __DOXYGEN__
 
 # If the MACRO_EXPANSION and EXPAND_ONLY_PREDEF tags are set to YES then 
@@ -1042,7 +1101,9 @@
                          PLIST_CLONE_DEF \
                          PLIST_CLONE_IMP \
                          PLIST_CLONE_IMPT \
-                         PLIST_OBJECT_SPECIALIZATION
+                         PLIST_CLONE_IMPT2 \
+                         PLIST_OBJECT_SPECIALIZATION \
+                         DIRECTION_PAIR
 
 # If the SKIP_FUNCTION_MACROS tag is set to YES (the default) then 
 # doxygen's preprocessor will remove all function-like macros that are alone 
@@ -1110,6 +1171,14 @@
 
 CLASS_DIAGRAMS         = YES
 
+# You can define message sequence charts within doxygen comments using the \msc 
+# command. Doxygen will then run the mscgen tool (see http://www.mcternan.me.uk/mscgen/) to 
+# produce the chart and insert it in the documentation. The MSCGEN_PATH tag allows you to 
+# specify the directory where the mscgen tool resides. If left empty the tool is assumed to 
+# be found in the default search path.
+
+MSCGEN_PATH            = 
+
 # If set to YES, the inheritance and collaboration graphs will hide 
 # inheritance and usage relations if the target is undocumented 
 # or is not a class.
@@ -1167,7 +1236,7 @@
 
 INCLUDED_BY_GRAPH      = YES
 
-# If the CALL_GRAPH and HAVE_DOT tags are set to YES then doxygen will 
+# If the CALL_GRAPH, SOURCE_BROWSER and HAVE_DOT tags are set to YES then doxygen will 
 # generate a call dependency graph for every global function or class method. 
 # Note that enabling this option will significantly increase the time of a run. 
 # So in most cases it will be better to enable call graphs for selected 
@@ -1175,7 +1244,7 @@
 
 CALL_GRAPH             = NO
 
-# If the CALLER_GRAPH and HAVE_DOT tags are set to YES then doxygen will 
+# If the CALLER_GRAPH, SOURCE_BROWSER and HAVE_DOT tags are set to YES then doxygen will 
 # generate a caller dependency graph for every global function or class method. 
 # Note that enabling this option will significantly increase the time of a run. 
 # So in most cases it will be better to enable caller graphs for selected 
@@ -1212,33 +1281,25 @@
 
 DOTFILE_DIRS           = 
 
-# The MAX_DOT_GRAPH_WIDTH tag can be used to set the maximum allowed width 
-# (in pixels) of the graphs generated by dot. If a graph becomes larger than 
-# this value, doxygen will try to truncate the graph, so that it fits within 
-# the specified constraint. Beware that most browsers cannot cope with very 
-# large images.
-
-MAX_DOT_GRAPH_WIDTH    = 800
-
-# The MAX_DOT_GRAPH_HEIGHT tag can be used to set the maximum allows height 
-# (in pixels) of the graphs generated by dot. If a graph becomes larger than 
-# this value, doxygen will try to truncate the graph, so that it fits within 
-# the specified constraint. Beware that most browsers cannot cope with very 
-# large images.
+# The MAX_DOT_GRAPH_MAX_NODES tag can be used to set the maximum number of 
+# nodes that will be shown in the graph. If the number of nodes in a graph 
+# becomes larger than this value, doxygen will truncate the graph, which is 
+# visualized by representing a node as a red box. Note that doxygen if the number 
+# of direct children of the root node in a graph is already larger than 
+# MAX_DOT_GRAPH_NOTES then the graph will not be shown at all. Also note 
+# that the size of a graph can be further restricted by MAX_DOT_GRAPH_DEPTH.
 
-MAX_DOT_GRAPH_HEIGHT   = 768
+DOT_GRAPH_MAX_NODES    = 50
 
 # The MAX_DOT_GRAPH_DEPTH tag can be used to set the maximum depth of the 
 # graphs generated by dot. A depth value of 3 means that only nodes reachable 
 # from the root by following a path via at most 3 edges will be shown. Nodes 
 # that lay further from the root node will be omitted. Note that setting this 
 # option to 1 or 2 may greatly reduce the computation time needed for large 
-# code bases. Also note that a graph may be further truncated if the graph's 
-# image dimensions are not sufficient to fit the graph (see MAX_DOT_GRAPH_WIDTH 
-# and MAX_DOT_GRAPH_HEIGHT). If 0 is used for the depth value (the default), 
-# the graph is not depth-constrained.
+# code bases. Also note that the size of a graph can be further restricted by 
+# DOT_GRAPH_MAX_NODES. Using a depth of 0 means no depth restriction.
 
-MAX_DOT_GRAPH_DEPTH    = 0
+MAX_DOT_GRAPH_DEPTH    = 3
 
 # Set the DOT_TRANSPARENT tag to YES to generate images with a transparent 
 # background. This is disabled by default, which results in a white background. 
@@ -1246,7 +1307,7 @@
 # badly anti-aliased labels on the edges of a graph (i.e. they become hard to 
 # read).
 
-DOT_TRANSPARENT        = NO
+DOT_TRANSPARENT        = YES
 
 # Set the DOT_MULTI_TARGETS tag to YES allow dot to generate multiple output 
 # files in one run (i.e. multiple -o and -T options on the command line). This 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/doxygenfoot.html ./docs/doxygenfoot.html
--- ../Tekkotsu_3.0/docs/doxygenfoot.html	2006-02-01 16:08:59.000000000 -0500
+++ ./docs/doxygenfoot.html	2007-11-21 02:31:09.000000000 -0500
@@ -38,7 +38,7 @@
 					</script> 
 					
 					<noscript>
-						<img src="http://aibo4.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
+						<img src="http://aibo2.boltz.cs.cmu.edu/head.gif" border="0" width=16 height=16 align="middle">
 					</noscript>
 				</td>
 			</tr>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/doxygenhead.html ./docs/doxygenhead.html
--- ../Tekkotsu_3.0/docs/doxygenhead.html	2006-09-16 12:09:27.000000000 -0400
+++ ./docs/doxygenhead.html	2007-11-21 02:31:09.000000000 -0500
@@ -11,8 +11,77 @@
 		<link rel="home" href="../index.html">
 		<link rel="up" href="../index.html">
 		<link rel="SHORTCUT ICON" href="favicon.ico">
-	</head>
-	<body>
+		<script language="JavaScript">
+		<!--
+		// name - name of the desired cookie
+		// * return string containing value of specified cookie or null if cookie does not exist
+		function getCookie(name) {
+		  var dc = document.cookie;
+		  var prefix = name + "=";
+		  var begin = dc.indexOf("; " + prefix);
+		  if (begin == -1) {
+		    begin = dc.indexOf(prefix);
+		    if (begin != 0) return null;
+		  } else
+		    begin += 2;
+		  var end = document.cookie.indexOf(";", begin);
+		  if (end == -1)
+		    end = dc.length;
+		  return unescape(dc.substring(begin + prefix.length, end));
+		}
+		
+		// name - name of the cookie
+		// [path] - path of the cookie (must be same as path used to create cookie)
+		// [domain] - domain of the cookie (must be same as domain used to create cookie)
+		// * path and domain default if assigned null or omitted if no explicit argument proceeds
+		function deleteCookie(name, path, domain) {
+		  if (getCookie(name)) {
+		    document.cookie = name + "=" + 
+		    ((path) ? "; path=" + path : "") +
+		    ((domain) ? "; domain=" + domain : "") +
+		    "; expires=Thu, 01-Jan-70 00:00:01 GMT";
+		  }
+		}
+		var newURL = getCookie('newURL');
+		if (newURL != null) {
+			deleteCookie('newURL', '/', null);
+			document.location=newURL;
+		}
+		
+		function addFrames() {
+			document.cookie = "newURL=" + escape(document.URL) + "; path=/;";
+			location="index.html";
+		}
+		
+		window.onload=function() {
+			toggle=document.getElementById('toggleframes');
+			if(!toggle) {
+				alert("no toggle found!");
+				return;
+			}
+			toggle.style.display="block";
+			toggle.href=document.location;
+		  if (top.frames.length == 0) {
+				toggle.onclick=function() { addFrames(); return false; };
+				toggle.innerHTML="show<br>frames";
+		  } else {
+				toggle.target="_top";
+				toggle.innerHTML="hide<br>frames";
+		  }
+		}
+		//-->
+		</script>
+		<style type="text/css">
+			#toggleframes { display:none; background-color:#EEE; border:1px solid #888; padding:.25em; opacity:.5; filter:alpha(opacity=50); font-size:85%;}
+			#toggleframes:hover { background-color:#E4E4F8; opacity:1; filter:alpha(opacity=100); }
+		</style>
+		</head>
+		<body>
+		<table style="position:absolute; top:.25em; left:.25em;" cellpadding="0" cellspacing="0" id="toggleframesbox">
+			<tr><td align="center">
+			<a id="toggleframes"></a>
+			</td></tr>
+		</table>
 		<!-- <img src="aibosmall.jpg" width=92 height=75 align=right> -->
 		<table cellpadding="1" cellspacing="6" border="0"
 					 style="text-align: left; margin-left: auto; margin-right: auto;">
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/dualcoding.doxycfg ./docs/dualcoding.doxycfg
--- ../Tekkotsu_3.0/docs/dualcoding.doxycfg	2006-02-21 12:58:41.000000000 -0500
+++ ./docs/dualcoding.doxycfg	2007-06-14 11:37:39.000000000 -0400
@@ -1,7 +1,6 @@
 @INCLUDE = doxygencfg
 
 PROJECT_NAME = DualCoding
-PROJECT_NUMBER = 3.0 beta
 INPUT = ../DualCoding
 EXCLUDE =
 EXCLUDE_PATTERNS =
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/exthead.html ./docs/exthead.html
--- ../Tekkotsu_3.0/docs/exthead.html	2006-03-03 10:33:05.000000000 -0500
+++ ./docs/exthead.html	2007-02-13 00:35:27.000000000 -0500
@@ -18,19 +18,19 @@
 					 style="text-align: left; margin-left: auto; margin-right: auto;">
 			<tbody>
 				<tr>
-					<!-- #Homepage# --> <td style="vertical-align: top;"><a target="_top" href="../../index.html">Homepage</a></td>
-					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"></td>
+					<!-- #Homepage# --> <td style="vertical-align: top;"><a target="_top" href="../../index.html">Tekkotsu Homepage</a></td>
+					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"><br></td>
 					<!-- #Demos# --> <td style="vertical-align: top;"><a target="_top" href="../../Samples.html">Demos</a></td>
-					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"></td>
-					<!-- #Overview# --> <td style="vertical-align: top;"><a target="_top" href="../../Overview.html">Overview</a></td>
-					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"></td>
-					<!-- #Downloads# --> <td style="vertical-align: top;"><a target="_top" href="../../VersionHistory.html">Downloads</a></td>
-					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"></td>
-					<!-- #Tutorials# --> <td style="vertical-align: top;"><a target="_top" href="../../Tutorials.html">Tutorials</a></td>
-					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"></td>
-					<!-- #Reference# --> <td style="vertical-align: top;"><a target="_top" href="../index.html">Reference</a></td>
 					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"><br></td>
-					<!-- #Credits# --> <td style="vertical-align: top;"><a target="_top" href="../../Credits.html">Credits</a> </td>
+					<!-- #Overview# --> <td style="vertical-align: top;"><a target="_top" href="../../ArchitecturalOverview.html">Overview</a></td>
+					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"><br></td>
+					<!-- #Downloads# --> <td style="vertical-align: top;"><a target="_top" href="../../downloads.html">Downloads</a></td>
+					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"><br></td>
+					<!-- #Tutorials# --> <td style="vertical-align: top;"><a target="_top" href="../../development.html">Dev. Resources</a></td>
+					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"><br></td>
+					<!-- #Current# --><!-- #Reference# --> <td style="vertical-align: top;"><a target="_top" href="../index.html"><i>Reference</i></a></td>
+					<!-- #Bar# --> <td style="vertical-align: top; background-color: rgb(0, 0, 0);"><br></td>
+					<!-- #Credits# --> <td style="vertical-align: top;"><a target="_top" href="../../acknowledgments.html">Credits</a> </td>
 				</tr>
 			</tbody>
 		</table>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/hal.doxycfg ./docs/hal.doxycfg
--- ../Tekkotsu_3.0/docs/hal.doxycfg	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/hal.doxycfg	2007-06-21 15:35:39.000000000 -0400
@@ -0,0 +1,17 @@
+@INCLUDE = doxygencfg
+
+PROJECT_NAME = "Tekkotsu Hardware Abstraction Layer"
+INPUT = ../local
+EXCLUDE = ../local/terk
+EXCLUDE_PATTERNS =
+OUTPUT_DIRECTORY = generated/html
+EXTRACT_ALL = YES
+ALWAYS_DETAILED_SEC = NO
+GENERATE_TREEVIEW = YES
+HTML_OUTPUT = hal
+HIDE_SCOPE_NAMES = YES
+SEARCHENGINE = YES
+GENERATE_TAGFILE = generated/hal.tag
+HTML_HEADER = exthead.html
+HTML_FOOTER = dualcodingfoot.html
+PREDEFINED += use_namespace
Binary files ../Tekkotsu_3.0/docs/html/MotionModel.png and ./docs/html/MotionModel.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/html/doxygen-override.css ./docs/html/doxygen-override.css
--- ../Tekkotsu_3.0/docs/html/doxygen-override.css	2005-07-19 20:00:17.000000000 -0400
+++ ./docs/html/doxygen-override.css	2007-08-14 14:24:56.000000000 -0400
@@ -1,5 +1,4 @@
-H1 { letter-spacing: 0; margin-top: 1em; }
-H2 { letter-spacing: .1em; border: none; text-align:left; margin-bottom: 0px; }
-PRE.fragment { border:none; background-color:none; margin:0; padding:10px 0; }
-P {
-}
+H1 { letter-spacing: 0; padding-top:1.5em; text-align: center; margin-top:1em; }
+H2 { letter-spacing: 2px; border: none; text-align:left; margin-bottom: 0px; font-size:125%;}
+
+PRE.fragment { border:none; background-color:transparent; margin:0; padding:10px 0; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/html/doxygen.css ./docs/html/doxygen.css
--- ../Tekkotsu_3.0/docs/html/doxygen.css	2006-03-28 19:37:17.000000000 -0500
+++ ./docs/html/doxygen.css	2007-11-21 02:03:37.000000000 -0500
@@ -7,11 +7,15 @@
 	padding: 2px;
 	line-height: 140%;
     width: 640px;
-    align: center;
     margin-left: auto;
     margin-right: auto; 
 	font-size: smaller;
 }
+DIV.dynsection {
+	width:725px;
+	max-height:450px;
+	overflow:auto;
+}
 DIV.nav {
 	width: 100%;
 	background-color: #eeeeff;
@@ -136,7 +140,7 @@
 SPAN.charliteral   { color: #008080 }
 .mdescLeft {
        padding: 0px 8px 4px 8px;
-	font-size: 80%;
+	font-size: 95%;
 	font-style: italic;
 	background-color: #F4F4F4;
 	border-top: 1px none #E0E0E0;
@@ -147,7 +151,7 @@
 }
 .mdescRight {
        padding: 0px 8px 4px 8px;
-	font-size: 80%;
+	font-size: 95%;
 	font-style: italic;
 	background-color: #F4F4F4;
 	border-top: 1px none #E0E0E0;
@@ -172,7 +176,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 80%;
+	font-size: 95%;
 }
 .memItemRight {
 	padding: 1px 8px 0px 8px;
@@ -190,7 +194,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 80%;
+	font-size: 95%;
 }
 .memTemplItemLeft {
 	padding: 1px 0px 0px 8px;
@@ -208,7 +212,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 80%;
+	font-size: 95%;
 }
 .memTemplItemRight {
 	padding: 1px 8px 0px 8px;
@@ -226,7 +230,7 @@
 	border-bottom-style: none;
 	border-left-style: none;
 	background-color: #F4F4F4;
-	font-size: 80%;
+	font-size: 95%;
 }
 .memTemplParams {
 	padding: 1px 0px 0px 8px;
@@ -245,7 +249,7 @@
 	border-left-style: none;
 	background-color: #F4F4F4;
        color: #606060;
-	font-size: 80%;
+	font-size: 95%;
 }
 .search     { color: #003399;
               font-weight: bold;
@@ -281,7 +285,7 @@
 
 /* Style for detailed member documentation */
 .memtemplate {
-  font-size: 80%;
+  font-size: 95%;
   color: #606060;
   font-weight: normal;
 } 
@@ -300,6 +304,7 @@
   border-style: solid;
   border-color: #dedeee;
   -moz-border-radius: 8px 8px 8px 8px;
+  border-radius: 8px 8px 8px 8px;
 }
 .memname {
   white-space: nowrap;
@@ -316,6 +321,7 @@
   border-color: #84b0c7;
   font-weight: bold;
   -moz-border-radius: 8px 8px 8px 8px;
+  border-radius: 8px 8px 8px 8px;
 }
 .paramkey {
   text-align: right;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/html/index.html ./docs/html/index.html
--- ../Tekkotsu_3.0/docs/html/index.html	2006-10-03 23:01:52.000000000 -0400
+++ ./docs/html/index.html	2007-08-14 14:24:56.000000000 -0400
@@ -1,10 +1,48 @@
 <!DOCTYPE HTML PUBLIC "-//W3C//DTD HTML 4.0 Transitional//EN">
 <html>
 <head>
-<!--#include virtual="../setup.shtml" -->
-  <meta content="text/html;charset=iso-8859-1" http-equiv="Content-Type">
-  <title>Tekkotsu: Reference Documenation</title>
-  <link type="text/css" rel="stylesheet" href="doxygen.css">
+	<!--#include virtual="../setup.shtml" -->
+	<script language="JavaScript">
+	<!--
+		// name - name of the desired cookie
+		// * return string containing value of specified cookie or null if cookie does not exist
+		function getCookie(name) {
+		  var dc = document.cookie;
+		  var prefix = name + "=";
+		  var begin = dc.indexOf("; " + prefix);
+		  if (begin == -1) {
+		    begin = dc.indexOf(prefix);
+		    if (begin != 0) return null;
+		  } else
+		    begin += 2;
+		  var end = document.cookie.indexOf(";", begin);
+		  if (end == -1)
+		    end = dc.length;
+		  return unescape(dc.substring(begin + prefix.length, end));
+		}
+		
+		// name - name of the cookie
+		// [path] - path of the cookie (must be same as path used to create cookie)
+		// [domain] - domain of the cookie (must be same as domain used to create cookie)
+		// * path and domain default if assigned null or omitted if no explicit argument proceeds
+		function deleteCookie(name, path, domain) {
+		  if (getCookie(name)) {
+		    document.cookie = name + "=" + 
+		    ((path) ? "; path=" + path : "") +
+		    ((domain) ? "; domain=" + domain : "") +
+		    "; expires=Thu, 01-Jan-70 00:00:01 GMT";
+		  }
+		}
+		var newURL = getCookie('newURL');
+		if (newURL != null) {
+			deleteCookie('newURL', '/', null);
+			document.location=newURL;
+		}
+	//-->
+	</script>
+	<meta content="text/html;charset=iso-8859-1" http-equiv="Content-Type">
+	<title>Tekkotsu: Reference Documenation</title>
+	<link type="text/css" rel="stylesheet" href="doxygen.css">
 	<link type="text/css" rel="stylesheet" href="tabs.css" >
 	<link type="text/css" rel="stylesheet" href="../tutorialcode.css">
 	<link type="text/css" rel="stylesheet" href="../tekkotsu.css">
@@ -99,6 +137,7 @@
 <div style="margin-left:20px;"><b>Library Sub-Documentation:</b></div>
       <ul>
         <li><a href="dualcoding/index.html" target="_top">DualCoding</a></li>
+        <li><a href="hal/index.html" target="_top">Hardware Abstraction Layer</a></li>
         <li><a href="newmat/index.html" target="_top">newmat</a></li>
         <li><a href="roboop/index.html" target="_top">ROBOOP</a></li>
       </ul>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/docs/plist-example.cc ./docs/plist-example.cc
--- ../Tekkotsu_3.0/docs/plist-example.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./docs/plist-example.cc	2007-11-08 23:58:08.000000000 -0500
@@ -0,0 +1,124 @@
+#include "Shared/plist.h"
+
+using namespace std;
+// you might want to 'using namespace plist'...
+// we'll be using plist:: scoping everywhere below just for clarity
+
+/* Generic base class for "shapes"... we specify a generic Collection,
+ * as its base, allows either Dictionary or Array-based! */
+class Shape : virtual public plist::Collection {};
+
+
+/* We will use a float for coordinates, wrapped by a plist::Primitive<>
+ * The Primitive class provides transparent conversions and operations,
+ * so we can usually pretend this is just a regular float! */
+typedef plist::Primitive<float> coord_t;
+
+
+/* A point is defined as an array of coordinates, one for each dimension.
+ * We'll assume 2D points unless otherwise directed.
+ * An alternative definition could use explicit 'x' and 'y' members, and/or
+ * use a Dictionary with labels instead of an Array with subscripts... */
+class Point : public Shape, virtual public plist::ArrayOf<coord_t> {
+public:
+	explicit Point(size_t n=2) : plist::ArrayOf<coord_t>(n,0), Shape() { }
+	Point(float xVal, float yVal) : plist::ArrayOf<coord_t>(2,0), Shape() {
+		getEntry(0)=xVal;
+		getEntry(1)=yVal;
+	}
+};
+
+
+/* We'll define a rectangle by the lower-left point and the upper-right point.
+ * Further, we'll set up an accessor to maintain this invariant. */
+class Rectangle : public Shape, public virtual plist::DictionaryOf<Point> {
+public:
+	Rectangle()
+		: plist::DictionaryOf<Point>(), Shape(), lower(), upper(),
+		xm(lower[0],upper[0]), ym(lower[1],upper[1])
+	{
+		/* The next line 'fixes' the entries during load, save, or assignment.
+		 * The default is to allow dynamic resizing, so you should call this when
+		 * you expect the entry structure to be immutable. (e.g. if you are using
+		 * members as collection entries.) */
+		setLoadSavePolicy(FIXED,SYNC);
+		addEntry("lower",lower); // still can always 'explicitly' add or remove entries
+		addEntry("upper",upper); // ... the LoadSavePolicy only restricts 'implicit' changes
+	}
+	
+	/* Can provide public access to members, the Monitor will provide
+	 * the flexibility usually provided by get/set accessor functions. */
+	Point lower, upper;
+	
+	/* Note automatic conversion to value type, will never be negative due to our Monitor */
+	float getWidth() const { return upper[0] - lower[0]; }
+	float getHeight() const { return upper[1] - lower[1]; }
+	
+protected:
+	/* Implements plist::PrimitiveListener to receive notification when
+	 * a member's value is changed.  We could also do this by having
+	 * rectangle itself be the listener instead of an inner class. */
+	class Monitor : public plist::PrimitiveListener {
+	public:
+		Monitor(coord_t& low, coord_t& high) : _low(low), _high(high) {
+			_low.addPrimitiveListener(this);
+			_high.addPrimitiveListener(this);
+		}
+		virtual void plistValueChanged(const plist::PrimitiveBase&) {
+			if(_low>_high) std::swap(_low,_high);
+		}
+	protected:
+		coord_t &_low, &_high;
+	} xm, ym;
+};
+
+
+/* Here's an example of a purely dynamic class... just a resizeable list
+ * of points!  For a "real" implementation, you'd probably want to use
+ * a dictionary, add a few more properties (e.g. 'isClosed'), and have
+ * the point list as a member variable... */
+class Polygon : public Shape, public virtual plist::ArrayOf<Point> {};
+
+
+// Here's some sample usage...
+int main(int argc, const char** argv) {
+	Point p;
+	p[0] = 1; // transparent conversion from value type to plist::Primitive
+	p[1] = 2.5;
+	p.saveFile("point.plist");
+	
+	Rectangle r;
+	r.upper = Point(4,5); // we can assign to directly to member...
+	r["lower"] = p; // ... or dynamically via operator[] lookup
+	r.saveFile("rectangle.plist");
+	
+	// test the low/high invariant
+	cout << "Original r, width: " << r.getWidth() << '\n' << r;
+	/* Original r, width: 3
+	 * lower.0 = 1
+	 * lower.1 = 2.5
+	 * upper.0 = 4
+	 * upper.1 = 5 */
+	
+	r.upper[0] = -4; // note we assign to upper.x, but it's lower.x that will be -4
+	// (because of the PrimitiveListener added by Rectangle's constructor)
+	cout << "Negated r, width: " << r.getWidth() << '\n' << r;
+	/* Negated r, width: 5
+	 * lower.0 = -4
+	 * lower.1 = 2.5
+	 * upper.0 = 1
+	 * upper.1 = 5 */
+	
+	// dynamic resizing:
+	Polygon poly;
+	/* Notice we are adding pointers here, vs. references in Rectangle,
+	 * vs. float values in Point.  (De)allocation from pointers or converted 
+	 * values is handled by the collection, whereas entries added from
+	 * references are *not* deallocated. */
+	poly.addEntry(new Point(1,2));
+	poly.addEntry(new Point(3,4));
+	poly.addEntry(new Point(5,0));
+	poly.saveFile("poly.plist");
+	
+	return 0;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/license.txt ./license.txt
--- ../Tekkotsu_3.0/license.txt	2004-03-31 19:16:51.000000000 -0500
+++ ./license.txt	1969-12-31 19:00:00.000000000 -0500
@@ -1,504 +0,0 @@
-		  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.
-
-    <one line to give the library's name and a brief idea of what it does.>
-    Copyright (C) <year>  <name of author>
-
-    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.
-
-  <signature of Ty Coon>, 1 April 1990
-  Ty Coon, President of Vice
-
-That's all there is to it!
-
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPort.h ./local/CommPort.h
--- ../Tekkotsu_3.0/local/CommPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPort.h	2007-11-18 01:47:06.000000000 -0500
@@ -0,0 +1,202 @@
+//-*-c++-*-
+#ifndef INCLUDED_CommPort_h_
+#define INCLUDED_CommPort_h_
+
+#include "Shared/plistCollections.h"
+#include "Shared/InstanceTracker.h"
+#include "Shared/Resource.h"
+#include "IPC/Thread.h"
+#include <string>
+#include <streambuf>
+#include <ios>
+
+//! A CommPort provides an abstract interface to a communication resource, based on wrapping a standard library stream buffer
+/*! Key extensions provided beyond the std::basic_streambuf are a mutual exclusion lock,
+ *  explicitly separate read/write buffers (which, depending on implementation, could refer
+ *  to the same stream), recursive open/close, plist-based configuration parameters, and
+ *  integration with an InstanceTracker registry and factory for dynamic reconfigurability.
+ *
+ *  Usually you can get by using one of the standard stream buffers (streambuf, filebuf, stringbuf)
+ *  but if you need to implement a custom stream, these links may help
+ *  get you started:
+ *  - An article by Paul Grenyer stepping through the process:
+ *    http://accu.org/index.php/journals/264
+ *  - Sample code from Chris Frey for a network class:
+ *    http://www.netdirect.ca/~cdfrey/software/sockstream.cc.txt
+ * 
+ *  See also our own network stream class, ionetstream (Wireless/netstream.h/.cc).
+ *  Although intended for networking, you can pass it any file descriptor, which makes
+ *  it handy for pipes as well.
+ *
+ *  Clients should be careful to use the locking mechanism if there is a possibility of
+ *  confusing query-responses or competing command/query-polls!
+ *
+ * Example usage: look up an instance named "Foo", and send it a query.
+ * @code
+ * CommPort* comm = CommPort::getRegistry().getInstance("Foo");
+ * std::ostream is(&comm->getReadStreambuf());
+ * std::ostream os(&comm->getWriteStreambuf());
+ * is.tie(&os); // fancy failsafe -- make sure 'os' is flushed anytime we read from 'is'
+ *
+ * // Locking a CommPort across query-response pairs:
+ * int value;
+ * {
+ *     MarkScope autolock(*comm); // marks the comm port as "in use" until the end of its scope
+ *     os << "query-value-command" << endl;
+ *     is >> value;
+ *     // because we have the lock, we know 'value' is in response
+ *     // to the 'query-value-command', and not a response to any other thread
+ * }
+ * @endcode
+ *
+ * Advanced locking: try to get a lock, then transfer it to a MarkScope to
+ * ensure exception-safety.
+ * @code
+ * ThreadNS::Lock& l = comm->getLock();
+ * if(l.trylock()) {
+ *     MarkScope autolock(l); l.unlock(); // transfer lock to MarkScope
+ *     // use comm ...
+ * }
+ * @endcode
+ */
+class CommPort : public virtual plist::Dictionary, public Resource {
+public:
+	//! destructor, removes from registry in case we're deleting it from some other source than registry's own destroy()
+	virtual ~CommPort() { getRegistry().destroy(instanceName); }
+	
+	//! the streambuf which does the actual work should inherit from basic_streambuf, using the system's default character type
+	typedef std::basic_streambuf<std::ios::char_type> streambuf;
+	
+	//! Returns the name of the class (aka its type)
+	/*! Suggested implementation is to declare a static string member, set it to the result of
+	 *  calling the registry's registerType, and then return that member here */
+	virtual std::string getClassName() const=0;
+	
+	//! Provides serialized access to the comm port
+	/*! Multiple drivers might be using the same comm port, callers should get the
+	 *  lock when doing operations on the comm port, particularly across sending
+	 *  a command and waiting for the reply.  See MarkScope for usage. */
+	virtual ThreadNS::Lock& getLock() { return lock; }
+	
+	//! Called when communication is about to begin, should handle recursive open/close calls
+	/*! The subclass is expected to have its own configuration settings
+	 *  which define the parameters of what is to be "opened".
+	 *  Hence, no arguments are passed.
+	 *
+	 *  You should be able to handle recursive levels of open/close in case multiple
+	 *  drivers are using the same CommPort.
+	 *
+	 *  @return true if successful (or already open) */
+	virtual bool open()=0;
+	
+	//! Called when communication is complete, should handle recursive open/close calls
+	/*! @return true if successful, false if still open (in use elsewhere) */
+	virtual bool close()=0;
+	
+	//! Allows you to check whether the reference from getReadStreambuf() is currently functional (if checking is supported!)
+	/*! For streambufs which don't have a way to check this, always returns true. */
+	virtual bool isReadable() { return true; }
+	
+	//! Allows you to check whether the reference from getWriteStreambuf() is currently functional (if checking is supported!)
+	/*! For streambufs which don't have a way to check this, always returns true. */
+	virtual bool isWriteable() { return true; }
+	
+	//! Returns a std::basic_streambuf, which is expected to implement the actual work
+	/*! You can pass this to an istream to use the nice C++ style input and output,
+	 *  or you can call the streambuf functions directly.  However, if you're going
+	 *  the latter route, probably easier to just call CommPort's own read() and write().
+	 *
+	 *  Depending on implementation, the streambuf this returns might be a
+	 *  different instance than getWriteStreambuf.  If they are the same instance,
+	 *  then you could use an iostream instead of separate istream and ostream.*/
+	virtual streambuf& getReadStreambuf()=0;
+	
+	//! Returns a std::basic_streambuf, which is expected to implement the actual work
+	/*! You can pass this to an ostream to use the nice C++ style input and output,
+	 *  or you can call the streambuf functions directly.  However, if you're going
+	 *  the latter route, probably easier to just call CommPort's own read() and write().
+	 *
+	 *  Depending on implementation, the streambuf this returns might be a
+	 *  different instance than getReadStreambuf.  If they are the same instance,
+	 *  then you could use an iostream instead of separate istream and ostream.*/
+	virtual streambuf& getWriteStreambuf()=0;
+	
+	//! returns up to @a n bytes from the streambuf, returns the number read
+	virtual size_t read(char* buf, size_t n) { return getReadStreambuf().sgetn(buf,n); }
+	//! writes up to @a n bytes from the streambuf, returns the number written
+	virtual size_t write(const char* buf, size_t n) { return getWriteStreambuf().sputn(buf,n); }
+	
+	//! reads all available data from getReadStreambuf()
+	virtual void read(std::string& s) {
+		s.clear();
+		const size_t BUFSIZE=256;
+		char buf[BUFSIZE];
+		size_t nread=read(buf,BUFSIZE);
+		while(nread!=0) {
+			s.append(buf,nread);
+			if(nread!=BUFSIZE || getReadStreambuf().in_avail()<=0)
+				break;
+			nread=read(buf,BUFSIZE);
+		}
+	}
+	//! writes the string into getWriteStreambuf()
+	virtual size_t write(const std::string& s) { return write(s.c_str(),s.size()); }
+	
+	//! short hand for the instance tracker, which allows dynamic reconfiguration of CommPort instances
+	typedef InstanceTracker<CommPort,std::string,Factory1Arg<CommPort,std::string> > registry_t;
+	//! registry from which current instances can be discovered and new instances allocated based on their class names
+	static registry_t& getRegistry() { static registry_t registry; return registry; }
+	
+protected:
+	//! constructor, pass the name of the class's type so we can use it in error messages, and a name for the instance so we can register it for MotionHook's to lookup
+	CommPort(const std::string& /*classname*/, const std::string& instancename)
+	: plist::Dictionary(), Resource(), instanceName(instancename), lock()
+	{
+		setLoadSavePolicy(FIXED,SYNC);
+	}
+	
+	//! To be called be "deepest" subclass constructor at the end of construction
+	/*! Don't want to register until completed construction!  plist::Collection listeners would be
+	 *  triggered and might start performing operations on instance while partially constructed */
+	virtual void registerInstance() {
+		if(CommPort * inst=getRegistry().getInstance(instanceName)) {
+			std::cerr << "Warning: registration of CommPort " << getClassName() << " named " << instanceName << " @ " << this
+			<< " blocked by previous " << inst->getClassName() << " instance of same name @ " << inst << std::endl;
+		}
+		if(!getRegistry().registerInstance(getClassName(),instanceName,this))
+			std::cerr << "Error: failed to register " << getClassName() << " named " << instanceName << " @ " << this;
+		//addEntry(".type",new plist::Primitive<std::string>(className),"Stores the typename of the comm port so it can be re-instantiated on load.\n** Do not edit ** ");
+	}
+		
+	//! Provides a Resource interface, allowing you to use MarkScope directly on the CommPort instead of calling through getLock().
+	/*! Users don't need to call this directly... either pass the CommPort to a MarkScope, or call getLock(). */
+	virtual void useResource(Data&) { lock.lock(); }
+	//! provides a Resource interface, allowing you to use MarkScope directly on the CommPort instead of calling through getLock().
+	/*! Users don't need to call this directly... either pass the CommPort to a MarkScope, or call getLock(). */
+	virtual void releaseResource(Data&) { lock.unlock(); }
+	
+	const std::string instanceName; //!< holds the name of this instance of CommPort (mainly for error message reporting by the class itself)
+	
+	//!< ensures that serialized access is maintained (assuming clients use the lock...)
+	/*! Often devices have either half-duplex communication, or may give responses to
+	 *  command strings.  It is important to get a lock across a query-response pair so that
+	 *  there is no risk of a second thread attempting a competing command or query. */
+	ThreadNS::Lock lock;
+	
+private:
+	CommPort(const CommPort&); // no copy, don't call
+	CommPort& operator=(const CommPort&); // no copy, don't call
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.12 $
+ * $State: Exp $
+ * $Date: 2007/11/18 06:47:06 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/ExecutableCommPort.cc ./local/CommPorts/ExecutableCommPort.cc
--- ../Tekkotsu_3.0/local/CommPorts/ExecutableCommPort.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/ExecutableCommPort.cc	2007-06-03 13:03:36.000000000 -0400
@@ -0,0 +1,161 @@
+#include "ExecutableCommPort.h"
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <sys/wait.h>
+#include <unistd.h>
+
+using namespace std; 
+
+const std::string ExecutableCommPort::autoRegisterExecutableCommPort = CommPort::getRegistry().registerType<ExecutableCommPort>("ExecutableCommPort");
+
+ExecutableCommPort::~ExecutableCommPort() {
+	if(opened>0) {
+		cerr << "Connection still open in ExecutableCommPort destructor" << endl;
+		command.removePrimitiveListener(this);
+		shell.removePrimitiveListener(this);
+	}
+	if(!isChildRunning())
+		return;
+	cerr << "ExecutableCommPort destructing, but child is still running... waiting 3 seconds" << endl;
+	if(waitChild(3000,500))
+		return;
+	cerr << "ExecutableCommPort child is STILL running... sending interrupt signal" << endl;
+	if(kill(child,SIGINT)==-1) {
+		perror("ExecutableCommPort unable to kill child");
+		return;
+	}
+	if(waitChild(2000,500))
+		return;
+	cerr << "ExecutableCommPort child is STILL running... sending kill signal and moving on..." << endl;
+	if(kill(child,SIGKILL)==-1) {
+		perror("ExecutableCommPort unable to kill child");
+		return;
+	}
+}
+
+bool ExecutableCommPort::open() {
+	if(opened++>0)
+		return true;
+	command.addPrimitiveListener(this);
+	shell.addPrimitiveListener(this);
+	
+	int s2c[2];
+	int c2s[2];
+	if(pipe(s2c)==-1) {
+		perror("ERROR: ExecutableCommPort could not open simulator to child pipe");
+		return false;
+	}
+	if(pipe(c2s)==-1) {
+		perror("ERROR: ExecutableCommPort could not open child to simulator pipe");
+		::close(s2c[0]);
+		::close(s2c[1]);
+		return false;
+	}
+	
+	child = fork();
+	if(child==-1) {
+		perror("ERROR: ExecutableCommPort could not fork to launch executable");
+		::close(s2c[0]);
+		::close(s2c[1]);
+		::close(c2s[0]);
+		::close(c2s[1]);
+		return false;
+	}
+	
+	if(child==0) {
+		// child process
+		::close(s2c[WRITEPIPE]); // close write of sim to child (not used on our end!)
+		::close(c2s[READPIPE]); // close read of child to sim (not used on our end!)
+		
+		::close(STDIN_FILENO); // theoretically not necessary (dup2 will close it), but we'll be paranoid
+		if(::dup2(s2c[READPIPE],STDIN_FILENO)==-1)
+			perror("ERROR: ExecutableCommPort could not dup2 the child's input to stdin");
+		::close(s2c[READPIPE]); // now duplicated, close this reference
+		
+		::close(STDOUT_FILENO); // theoretically not necessary (dup2 will close it), but we'll be paranoid
+		if(::dup2(c2s[WRITEPIPE],STDOUT_FILENO)==-1)
+			perror("ERROR: ExecutableCommPort could not dup2 the child's output to stdout");
+		::close(c2s[WRITEPIPE]); // now duplicated, close this reference
+		
+		// Launch executable!
+		execlp(shell.c_str(), shell.c_str(), "-c", command.c_str(), NULL);
+		
+		// any return from here means error occurred!
+		perror("ERROR: ExecutableCommPort could not launch the executable!");
+		::close(STDIN_FILENO);
+		::close(STDOUT_FILENO);
+		_exit(EXIT_FAILURE); // note _exit() instead of exit(), avoids double-flushing buffers...
+		
+	} else {
+		// parent process
+		::close(s2c[READPIPE]); // close read of sim to child (not used on our end!)
+		::close(c2s[WRITEPIPE]); // close write of child to sim (not used on our end!)
+		rbuf.adoptFD(c2s[READPIPE]);
+		wbuf.adoptFD(s2c[WRITEPIPE]);
+	}
+	return true;
+}
+
+bool ExecutableCommPort::close() {
+	if(opened==0)
+		std::cerr << "Warning: ExecutableCommPort close() without open()" << std::endl;
+	if(--opened>0)
+		return false;
+	command.removePrimitiveListener(this);
+	shell.removePrimitiveListener(this);
+	rbuf.close();
+	wbuf.close();
+	return true;
+}
+
+void ExecutableCommPort::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&command || &pl==&shell) {
+		if(opened>0) {
+			unsigned int tmp=opened;
+			opened=1; // fake out close() and open() to make sure they trigger the action
+			close();
+			open();
+			opened=tmp; // reset original reference count
+		}
+	} else {
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+bool ExecutableCommPort::waitChild(unsigned int t, unsigned int p) {
+	if(!isChildRunning())
+		return true;
+	for(unsigned int x=0; x<t; x+=p) {
+		usleep(p*1000);
+		if(!isChildRunning())
+			return true;
+	}
+	return false;
+}
+
+bool ExecutableCommPort::isChildRunning() const {
+	if(child==0)
+		return false;
+	int status=0;
+	int ret=waitpid(child,&status,WNOHANG);
+	if(ret==-1) {
+		perror("ExecutableCommPort unable to check child status, waitpid");
+		return false;
+	}
+	if(ret==0)
+		return false;
+	if(WIFEXITED(status) || WIFSIGNALED(status))
+		return false;
+	return true;
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:36 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/ExecutableCommPort.h ./local/CommPorts/ExecutableCommPort.h
--- ../Tekkotsu_3.0/local/CommPorts/ExecutableCommPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/ExecutableCommPort.h	2007-06-03 13:03:36.000000000 -0400
@@ -0,0 +1,85 @@
+//-*-c++-*-
+#ifndef INCLUDED_ExecutableCommPort_h_
+#define INCLUDED_ExecutableCommPort_h_
+
+#include "local/CommPort.h"
+#include "Wireless/netstream.h"
+
+//! Run a specified executable, with the comm port connected to its stdin and stdout
+/*! This can be handy for testing with a device simulator, or if you want to
+ *  interface with a device as an external process.  It's more efficient to run your
+ *  driver as an DeviceDriver subclass than to spawn an external process however.
+ *
+ *  If you need to keep your external program running across instances of the
+ *  simulator (or just want to launch it externally), you'll need to use file system
+ *  fifos (see mkfifo command), probably separate ones for reading and writing
+ *  with a RedirectionCommPort to combine them (unless your platform supports
+ *  bidirectional pipes... most don't) */
+class ExecutableCommPort : public CommPort, public virtual plist::PrimitiveListener {
+public:
+	explicit ExecutableCommPort(const std::string& name)
+		: CommPort(autoRegisterExecutableCommPort,name),
+		command(), shell("sh"), child(0), rbuf(), wbuf(), opened(0)
+	{
+		addEntry("Command",command,"Specifies the shell command to run, stdio from this process will be piped through the comm port");
+		addEntry("Shell",shell,"The shell executable to use for executing the command, can be found via PATH, or explicit path\n"
+						 "The shell will be passed '-c' and then your command");
+	}
+	
+	//! destructor, checks that child process is no longer running, kills it if it is (after some delay)
+	virtual ~ExecutableCommPort();
+	
+	virtual std::string getClassName() const { return autoRegisterExecutableCommPort; }
+	
+	virtual streambuf& getReadStreambuf() { return rbuf; }
+	virtual streambuf& getWriteStreambuf() { return wbuf; }
+	virtual bool isWriteable() { wbuf.update_status(); return wbuf.is_open(); }
+	virtual bool isReadable() { rbuf.update_status(); return rbuf.is_open(); }
+	
+	//! launches the executable, connecting its stdin and stdout to this comm port
+	virtual bool open();
+	
+	//! sends kill signal to the child process
+	virtual bool close();
+	
+	//! if #command is modified, close current connection (if running) and launch new one
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	plist::Primitive<std::string> command; //!< shell command
+	plist::Primitive<std::string> shell; //!< shell name
+	
+protected:
+	pid_t child; //!< process ID of the child (0 if not launched, -1 if error)
+	
+	basic_netbuf<std::ios::char_type> rbuf; //!< reads from child process
+	basic_netbuf<std::ios::char_type> wbuf; //!< writes to child process
+	
+	unsigned int opened; //!< reference count of the number of times we've been opened (i.e. pending close()s)
+	
+	enum {
+		READPIPE=0, //!< pipe() system call returns read end on the first entry, lets make it symbolic so it's more clear
+		WRITEPIPE=1 //!< pipe() system call returns write end on the second entry, lets make it symbolic so it's more clear
+	};
+	
+	//! waits for child process to exit for t milliseconds, polling status every p millseconds, returns true if no longer running
+	bool waitChild(unsigned int t, unsigned int p);
+	
+	//! returns true if child is still running
+	bool isChildRunning() const;
+
+	//! holds the class name, set via registration with the CommPort registry
+	static const std::string autoRegisterExecutableCommPort;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:36 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/FileSystemCommPort.cc ./local/CommPorts/FileSystemCommPort.cc
--- ../Tekkotsu_3.0/local/CommPorts/FileSystemCommPort.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/FileSystemCommPort.cc	2007-06-18 17:47:20.000000000 -0400
@@ -0,0 +1,67 @@
+#include "FileSystemCommPort.h"
+
+const std::string FileSystemCommPort::autoRegisterFileSystemCommPort = CommPort::getRegistry().registerType<FileSystemCommPort>("FileSystemCommPort");
+
+bool FileSystemCommPort::open() {
+	if(opened++>0)
+		return true;
+	path.addPrimitiveListener(this);
+	mode.addPrimitiveListener(this);
+	curloc=path;
+	curmode=static_cast<std::ios_base::openmode>((int)mode);
+	bool ans=true;
+	if(mode & std::ios_base::in) {
+		if(rbuf.open(path.c_str(),curmode & ~(std::ios_base::out | std::ios_base::trunc))==NULL) {
+			connectionError("Could not open file system path for reading "+path,true);
+			ans=false;
+		}
+	}
+	if(mode & std::ios_base::out) {
+		if(wbuf.open(path.c_str(),curmode & ~std::ios_base::in)==NULL) {
+			connectionError("Could not open file system path for writing "+path,true);
+			ans=false;
+		}
+	}
+	return ans;
+}
+
+bool FileSystemCommPort::close() {
+	if(opened==0)
+		std::cerr << "Warning: FileSystemCommPort close() without open()" << std::endl;
+	if(--opened>0)
+		return false;
+	path.removePrimitiveListener(this);
+	mode.removePrimitiveListener(this);
+	bool rc = (rbuf.close()!=NULL);
+	bool wc = (wbuf.close()!=NULL);
+	return rc && wc;
+}
+
+void FileSystemCommPort::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&path) {
+		if(path!=curloc) {
+			unsigned int ref=opened;
+			while(opened)
+				close();
+			while(opened<ref)
+				open();
+		}
+	} else if(&pl==&mode) {
+		if(mode!=curmode) {
+			std::cerr << "Cannot change access mode while file is open" << std::endl;
+		}
+	} else {
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/06/18 21:47:20 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/FileSystemCommPort.h ./local/CommPorts/FileSystemCommPort.h
--- ../Tekkotsu_3.0/local/CommPorts/FileSystemCommPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/FileSystemCommPort.h	2007-11-09 14:01:17.000000000 -0500
@@ -0,0 +1,89 @@
+//-*-c++-*-
+#ifndef INCLUDED_FileSystemCommPort_h_
+#define INCLUDED_FileSystemCommPort_h_
+
+#include "local/CommPort.h"
+#include "Shared/plist.h"
+#include <fstream>
+#include <ios>
+
+//! Provides CommPort interface to file system devices, such as serial ports
+/*! Pass a path to use a file system device, or see NetworkCommPort for a network interface */
+class FileSystemCommPort : public CommPort, public virtual plist::PrimitiveListener {
+public:
+	//! constructor (see also sub-class constructor in protected section)
+	explicit FileSystemCommPort(const std::string& name)
+		: CommPort(autoRegisterFileSystemCommPort,name),
+		path(), mode(std::ios_base::in | std::ios_base::out | std::ios_base::trunc | std::ios_base::binary),
+		rbuf(), wbuf(), curloc(), curmode(), opened(0)
+	{
+		addEntry("Path",path,"Path of file system object being accessed");
+		addEntry("Mode",mode,"Mode bitmask to pass to the open() call, defaults to 'w+b': in|out|trunc|binary (see std::ios_base::openmode)");
+	}
+	
+	//! destructor, checks that the file descriptor has already been closed
+	virtual ~FileSystemCommPort() {
+		if(opened>0)
+			connectionError("File descriptor still open in FileSystemCommPort destructor",true);
+	}
+	
+	virtual std::string getClassName() const { return autoRegisterFileSystemCommPort; }
+	
+	virtual std::basic_filebuf<std::ios::char_type>& getReadStreambuf() { return rbuf; }
+	virtual std::basic_filebuf<std::ios::char_type>& getWriteStreambuf() { return wbuf; }
+	virtual bool isReadable() { return rbuf.is_open(); }
+	virtual bool isWriteable() { return wbuf.is_open(); }
+	
+	//! tries to have #rbuf and/or #wbuf open #path, subject to #mode 
+	virtual bool open();
+	
+	//! closes #rbuf and #wbuf
+	virtual bool close();
+	
+	//! watches #path, triggers a close() and re-open() if it changes
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	plist::Primitive<std::string> path; //!< path of file system object being accessed
+	plist::Primitive<int> mode; //!< mode bitmask to pass to the open() call (see std::ios_base::openmode)
+	
+protected:
+	explicit FileSystemCommPort(const std::string& classname, const std::string& instancename)
+		: CommPort(classname,instancename), 
+		path(), mode(std::ios_base::in | std::ios_base::out | std::ios_base::trunc | std::ios_base::binary),
+		rbuf(), wbuf(), curloc(), curmode(), opened(0)
+	{
+		addEntry("Path",path,"Path of file system object being accessed");
+		addEntry("Mode",mode,"Mode bitmask to pass to the open() call, defaults to 'w+b': in|out|trunc|binary (see std::ios_base::openmode)");
+	}
+	
+	//! Displays message on stderr and if @a fatal is set, calls closeFD()
+	virtual void connectionError(const std::string& msg, bool fatal) {
+		std::cerr << msg << std::endl;
+		if(fatal && (rbuf.is_open() || wbuf.is_open())) {
+			opened=1;
+			close();
+		}
+	}
+	
+	std::basic_filebuf<std::ios::char_type> rbuf;
+	std::basic_filebuf<std::ios::char_type> wbuf;
+	std::string curloc;
+	std::ios_base::openmode curmode;
+	unsigned int opened;
+	
+	//! holds the class name, set via registration with the CommPort registry
+	static const std::string autoRegisterFileSystemCommPort;
+};
+
+/*! @file
+ * @brief Describes FileDescriptorMotionHook, which provides a file descriptor interface for hardware "drivers"
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/11/09 19:01:17 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/NetworkCommPort.cc ./local/CommPorts/NetworkCommPort.cc
--- ../Tekkotsu_3.0/local/CommPorts/NetworkCommPort.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/NetworkCommPort.cc	2007-11-11 18:57:29.000000000 -0500
@@ -0,0 +1,98 @@
+#include "NetworkCommPort.h"
+#include "Shared/MarkScope.h"
+
+using namespace std;
+
+const std::string NetworkCommPort::autoRegisterNetworkCommPort = CommPort::getRegistry().registerType<NetworkCommPort>("NetworkCommPort");
+
+bool NetworkCommPort::open() {
+	if(opened++>0)
+		return true;
+	sbuf.setReconnect(block);
+	block.addPrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	host.addPrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	port.addPrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	transport.addPrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	server.addPrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	curaddr.set_name(host);
+	curaddr.set_port(port);
+	return doOpen(true);
+}
+
+bool NetworkCommPort::doOpen(bool dispError) {
+	if(lastAttempt.Age()<.75)
+		return false;
+	lastAttempt.Set();
+	if(server) {
+		if(block)
+			cout << "Waiting for '" << instanceName << "' connection on port " << port << "... " << flush;
+		if(!sbuf.listen(curaddr,transport==Config::UDP)) {
+			if(dispError) {
+				stringstream ss;
+				ss << "Could not listen on port " << port;
+				connectionError(ss.str(),true);
+			}
+			return false;
+		}
+	} else {
+		if(block)
+			cout << "Waiting for '" << instanceName << "' connection to " << host << ':' << port << "... " << flush;
+		if(!sbuf.open(curaddr,transport==Config::UDP)) {
+			if(dispError) {
+				stringstream ss;
+				ss << "Could not open connection to " << host << ":" << port;
+				connectionError(ss.str(),true);
+			}
+			return false;
+		}
+	}
+	if(block)
+		cout << instanceName <<  " connected." << endl;
+	return true;
+}
+
+bool NetworkCommPort::close() {
+	MarkScope l(getLock());
+	if(opened==0)
+		std::cerr << "Warning: NetworkCommPort close() without open()" << std::endl;
+	if(--opened>0)
+		return false;
+	sbuf.setReconnect(false);
+	sbuf.close();
+	host.removePrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	port.removePrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	transport.removePrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	server.removePrimitiveListener(dynamic_cast<plist::PrimitiveListener*>(this));
+	return true;
+}
+
+void NetworkCommPort::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&host || &pl==&port || &pl==&transport) {
+		MarkScope l(getLock());
+		if(host!=curaddr.get_name() || port!=curaddr.get_port() || curtrans!=transport) {
+			close();
+			open();
+		}
+	} else if(&pl==&server) {
+		MarkScope l(getLock());
+		close();
+		open();
+	} else if(&pl==&verbose) {
+		sbuf.setEcho(verbose);
+	} else if(&pl==&block) {
+		sbuf.setReconnect(block);
+	} else {
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.5 $
+ * $State: Exp $
+ * $Date: 2007/11/11 23:57:29 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/NetworkCommPort.h ./local/CommPorts/NetworkCommPort.h
--- ../Tekkotsu_3.0/local/CommPorts/NetworkCommPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/NetworkCommPort.h	2007-10-12 12:44:48.000000000 -0400
@@ -0,0 +1,90 @@
+//-*-c++-*-
+#ifndef INCLUDED_NetworkCommPort_h_
+#define INCLUDED_NetworkCommPort_h_
+
+#include "local/CommPort.h"
+#include "Wireless/netstream.h"
+#include "Shared/Config.h"
+#include "Shared/TimeET.h"
+
+//! description of NetworkCommPort
+/*! You probably want to use UDP if you're sending high-frequency, full-state updates, and
+*  use TCP if you're sending low-frequency or partial-state updates. */
+class NetworkCommPort : public CommPort, public virtual plist::PrimitiveListener {
+public:
+	explicit NetworkCommPort(const std::string& name)
+		: CommPort(autoRegisterNetworkCommPort,name),
+		host(), port(), transport(Config::TCP,Config::transport_names), server(false), verbose(false), block(false),
+		sbuf(), curaddr(), curtrans(Config::TCP), opened(0), lastAttempt(0L)
+	{
+		sbuf.setEcho(verbose);
+		addEntry("Host",host,"Hostname to connect to, or interface to listen on (blank for INADDR_ANY)");
+		addEntry("Port",port,"Port number to connect to or listen on");
+		addEntry("Transport",transport,"Transport protocol to use");
+		addEntry("Server",server,"If true, should listen for incoming connections instead of making an outgoing one.");
+		addEntry("Verbose",verbose,"If true, all traffic will be echoed to the terminal (handy for debugging plain-text protocols)");
+		addEntry("Block",block,"If true, will block until connection is (re)established on initial open or after losing the connection.");
+		verbose.addPrimitiveListener(this);
+	}
+	
+	//! destructor, checks that #sbuf has already been closed
+	virtual ~NetworkCommPort() {
+		if(opened>0)
+			connectionError("Connection still open in NetworkCommPort destructor",true);
+	}
+	
+	virtual std::string getClassName() const { return autoRegisterNetworkCommPort; }
+	
+	virtual streambuf& getReadStreambuf() { return sbuf; }
+	virtual streambuf& getWriteStreambuf() { return sbuf; }
+	virtual bool isWriteable() { sbuf.update_status(); if(!sbuf.is_open() && opened>0) doOpen(false); return sbuf.is_open(); }
+	virtual bool isReadable() { sbuf.update_status(); if(!sbuf.is_open() && opened>0) doOpen(false); return sbuf.is_open(); }
+	
+	//! activates the #sbuf based on the current configuration settings
+	virtual bool open();
+	
+	//! closes #sbuf
+	virtual bool close();
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	plist::Primitive<std::string> host;
+	plist::Primitive<unsigned short> port;
+	plist::NamedEnumeration<Config::transports> transport;
+	plist::Primitive<bool> server;
+	plist::Primitive<bool> verbose;
+	plist::Primitive<bool> block;
+	
+protected:
+	//! Displays message on stderr and if @a fatal is set, calls closeFD()
+	virtual void connectionError(const std::string& msg, bool fatal) {
+		std::cerr << msg << std::endl;
+		if(fatal && sbuf.is_open())
+			close();
+	}
+	
+	//! attempts to make a connection, checking that the previous attempt wasn't too recent
+	virtual bool doOpen(bool dispError);
+	
+	basic_netbuf<std::ios::char_type> sbuf;
+	IPaddr curaddr;
+	Config::transports curtrans;
+	unsigned int opened;
+	TimeET lastAttempt;
+	
+	//! holds the class name, set via registration with the CommPort registry
+	static const std::string autoRegisterNetworkCommPort;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.4 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:44:48 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/RedirectionCommPort.cc ./local/CommPorts/RedirectionCommPort.cc
--- ../Tekkotsu_3.0/local/CommPorts/RedirectionCommPort.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/RedirectionCommPort.cc	2007-06-03 13:03:36.000000000 -0400
@@ -0,0 +1,66 @@
+#include "RedirectionCommPort.h"
+
+using namespace std; 
+
+RedirectionCommPort::invalid_streambuf RedirectionCommPort::invalid;
+const std::string RedirectionCommPort::autoRegisterRedirectionCommPort = CommPort::getRegistry().registerType<RedirectionCommPort>("RedirectionCommPort");
+
+bool RedirectionCommPort::open() {
+	if(opened++>0)
+		return true;
+	input.addPrimitiveListener(this);
+	output.addPrimitiveListener(this);
+	curin=input;
+	curout=output;
+	bool ans=true;
+	if(CommPort * cur=getInputCP())
+		ans&=cur->open();
+	if(CommPort * cur=getOutputCP())
+		ans&=cur->open();
+	return ans;
+}
+
+bool RedirectionCommPort::close() {
+	if(opened==0)
+		std::cerr << "Warning: RedirectionCommPort close() without open()" << std::endl;
+	if(--opened>0)
+		return false;
+	input.removePrimitiveListener(this);
+	output.removePrimitiveListener(this);
+	bool ans=true;
+	if(CommPort * cur=getInputCP())
+		ans&=cur->close();
+	if(CommPort * cur=getOutputCP())
+		ans&=cur->close();
+	return ans;
+}
+
+void RedirectionCommPort::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&input) {
+		if(CommPort * prev=getInputCP())
+			prev->close();
+		curin=input;
+		if(CommPort * cur=getInputCP())
+			cur->open();
+	} else if(&pl==&output) {
+		if(CommPort * prev=getOutputCP())
+			prev->close();
+		curout=output;
+		if(CommPort * cur=getOutputCP())
+			cur->open();
+	} else {
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:36 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/RedirectionCommPort.h ./local/CommPorts/RedirectionCommPort.h
--- ../Tekkotsu_3.0/local/CommPorts/RedirectionCommPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/RedirectionCommPort.h	2007-06-03 13:03:36.000000000 -0400
@@ -0,0 +1,73 @@
+//-*-c++-*-
+#ifndef INCLUDED_RedirectionCommPort_h_
+#define INCLUDED_RedirectionCommPort_h_
+
+#include "local/CommPort.h"
+
+//! Allows you to recombine the input/output of other CommPorts in various ways
+/*! This will take input from one CommPort, and can send output to a different CommPort.
+ *  It's not a 'pipe' from the input to the output, it just changes where the inputs and outputs
+ *  are coming from. */
+class RedirectionCommPort : public CommPort, public virtual plist::PrimitiveListener {
+public:
+	//! constructor
+	explicit RedirectionCommPort(const std::string& name)
+	: CommPort(autoRegisterRedirectionCommPort,name), input(), output(), curin(), curout(), opened(0)
+	{
+		addEntry("Input",input,"Name of comm port from which to get input");
+		addEntry("Output",output,"Name of comm port into which to send output");
+	}
+
+	//! destructor, checks that the file descriptor has already been closed
+	virtual ~RedirectionCommPort() {
+		if(opened>0)
+			std::cerr << "Still open in RedirectionCommPort destructor" << std::endl;
+	}
+
+	virtual std::string getClassName() const { return autoRegisterRedirectionCommPort; }
+
+	virtual streambuf& getReadStreambuf() { CommPort * cp=getInputCP(); return (cp!=NULL) ? cp->getReadStreambuf() : invalid; }
+	virtual streambuf& getWriteStreambuf() { CommPort * cp=getOutputCP(); return (cp!=NULL) ? cp->getWriteStreambuf() : invalid; }
+	virtual bool isReadable() { CommPort * cp=getInputCP(); return (cp!=NULL) ? cp->isReadable() : false; }
+	virtual bool isWriteable() { CommPort * cp=getOutputCP(); return (cp!=NULL) ? cp->isWriteable() : false; }
+
+	virtual bool open();
+	virtual bool close();
+
+	//! watches #input and #output, triggers a close() and re-open() as needed
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+
+	plist::Primitive<std::string> input; //!< Name of comm port from which to get input
+	plist::Primitive<std::string> output; //!< Name of comm port into which to send output
+
+protected:
+	//! convenience function to lookup the current input comm port instance
+	CommPort * getInputCP() { return (curin.size()==0) ? NULL : CommPort::getRegistry().getInstance(curin); }
+	//! convenience function to lookup the current output comm port instance
+	CommPort * getOutputCP() { return (curout.size()==0) ? NULL : CommPort::getRegistry().getInstance(curout); }
+	
+	std::string curin; //!< name of the current input comm port (stored separately from #input so if that changes, we can close the old one)
+	std::string curout; //!< name of the current output comm port (stored separately from #output so if that changes, we can close the old one)
+	unsigned int opened; //!< open() call depth, tracks multiple usage
+	
+	//! std::streambuf uses a protected constructor, so we have to inherit to make an empty streambuf for #invalid
+	class invalid_streambuf : public std::streambuf {};
+	//! needed so we have something to return when the RedirectionCommPort doesn't have a valid external comm port to take a streambuf from
+	static invalid_streambuf invalid;
+	
+	//! holds the class name, set via registration with the CommPort registry
+	static const std::string autoRegisterRedirectionCommPort;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:36 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/SerialCommPort.cc ./local/CommPorts/SerialCommPort.cc
--- ../Tekkotsu_3.0/local/CommPorts/SerialCommPort.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/SerialCommPort.cc	2007-11-08 11:30:46.000000000 -0500
@@ -0,0 +1,140 @@
+#include "SerialCommPort.h"
+#include <termios.h>
+#include <sys/ioctl.h>
+#include <errno.h>
+#ifdef __APPLE__
+#  include <IOKit/serial/ioss.h>
+#endif
+
+#ifdef __CYGWIN__
+// Cygwin doesn't provide cfmakeraw...
+// this definition found in port of unix 'script' utility
+// by Alan Evans (Alan_Evans AT iwv com), 2002-09-27
+// http://marc.info/?l=cygwin&m=103314951904556&w=2
+void cfmakeraw(struct termios *termios_p) {
+  termios_p->c_iflag &= ~(IGNBRK|BRKINT|PARMRK|ISTRIP
+			  |INLCR|IGNCR|ICRNL|IXON);
+  termios_p->c_oflag &= ~OPOST;
+  termios_p->c_lflag &= ~(ECHO|ECHONL|ICANON|ISIG|IEXTEN);
+  termios_p->c_cflag &= ~(CSIZE|PARENB);
+  termios_p->c_cflag |= CS8;
+}
+#endif
+
+using namespace std;
+
+const char * const SerialCommPort::parityNames[] = { "EVEN", "ODD", "NONE", "" };
+INSTANTIATE_NAMEDENUMERATION_STATICS(SerialCommPort::parity_t);
+
+const std::string SerialCommPort::autoRegisterSerialCommPort = CommPort::getRegistry().registerType<SerialCommPort>("SerialCommPort");
+
+void SerialCommPort::setupSerial() {
+	if(fd<0)
+		return;
+	
+	// ** first do a basic setup to initialize our access to the serial port **
+	
+	// get current termios structure (sys/termios.h)
+	struct termios	theTermios;
+	int ret = tcgetattr(fd, &theTermios);
+	cfmakeraw(&theTermios);
+	
+#ifndef __APPLE__
+	// linux can handle non-standard baud rates directly
+	// we'll handle Darwin below, uses an ioctl call instead
+	cfsetispeed(&theTermios, baudRate);
+	cfsetospeed(&theTermios, baudRate);
+#endif
+	
+	// turn on READ and ignore modem control lines
+	theTermios.c_cflag |= CREAD | CLOCAL;
+	//theTermios.c_cflag = CIGNORE;
+	
+	switch (dataBits) {
+		case 5:		theTermios.c_cflag |= CS5;		break;
+		case 6:		theTermios.c_cflag |= CS6;		break;
+		case 7:		theTermios.c_cflag |= CS7;		break;
+		case 8:		theTermios.c_cflag |= CS8;		break;
+		default: std::cerr << "SerialCommPort: bad DataBits value " << dataBits << std::endl; 
+	}
+	
+	// stop bit(s)?
+	if(stopBits==1)
+		theTermios.c_cflag &= ~CSTOPB;
+	else if(stopBits==2)
+		theTermios.c_cflag |= CSTOPB;
+	else
+		std::cerr << "SerialCommPort: bad StopBits value " << stopBits << std::endl; 
+	
+	// parity?
+	switch(parity) {
+		case EVEN:
+			theTermios.c_cflag |= PARENB; theTermios.c_cflag &= ~PARODD; break;
+		case ODD:
+			theTermios.c_cflag |= PARENB; theTermios.c_cflag |= PARODD; break;
+		case NONE:
+			theTermios.c_cflag &= ~PARENB; break;
+	}
+	// default no flow control:
+	theTermios.c_iflag &= ~(IXON | IXOFF);
+	theTermios.c_cflag &= ~CRTSCTS;
+	
+	// apply our settings
+	ret = tcsetattr(fd, TCSAFLUSH, &theTermios);
+	//ret = ioctl(fd, TIOCSETA, &theTermios); // alternative ?
+	if (ret)
+		dispError("tcsetattr(TCSAFLUSH)",ret,errno);
+	
+#ifdef __APPLE__
+	// this allows higher (non-standard) baud rates, apparently not supported (on darwin) via termios
+	const int TGTBAUD = baudRate;
+	ret = ioctl(fd, IOSSIOSPEED, &TGTBAUD); // as opposed to setting it in theTermios ?
+	if (ret)
+		dispError("ioctl(IOSSIOSPEED)",ret,errno);
+#endif
+	
+	// this part doesn't seem to be necessary, but better safe than sorry...
+	int modem;
+	ret = ioctl(fd, TIOCMGET, &modem);
+	if (ret)
+		dispError("ioctl(TIOCMGET)",ret,errno);
+	modem |= TIOCM_DTR;
+	ret = ioctl(fd, TIOCMSET, &modem);
+	if (ret)
+		dispError("ioctl(TIOCMSET)",ret,errno);
+	
+	if(sttyConfig.size()>0) {
+		// ** do additional setup by calling out to stty **
+	#ifdef __linux__
+		std::string cmd="stty -F "+path+" "+sttyConfig;
+	#else /* assume BSD style... use a -f instead of -F (...sigh...) */
+		std::string cmd="stty -f "+path+" "+sttyConfig;
+	#endif
+		switch(::system(cmd.c_str())) {
+			case 0:
+				break; // good!
+			case -1:
+				perror("Warning: SerialCommPort could not make system call to stty"); break;
+			case 127:
+				std::cerr << "Warning: SerialCommPort could not make system call to stty: no shell found" << std::endl; break;
+			default:
+				std::cerr << "Warning: SerialCommPort stty reported error on configuration string: " << sttyConfig << std::endl; break;
+		}
+	}
+}
+
+void SerialCommPort::dispError(const char* where, int ret, int err) {
+	std::cerr << where << " returned " << ret << " (errno " << err << ": " << strerror(err) << ")" << std::endl;
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.9 $
+ * $State: Exp $
+ * $Date: 2007/11/08 16:30:46 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/CommPorts/SerialCommPort.h ./local/CommPorts/SerialCommPort.h
--- ../Tekkotsu_3.0/local/CommPorts/SerialCommPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/CommPorts/SerialCommPort.h	2007-11-08 11:30:46.000000000 -0500
@@ -0,0 +1,122 @@
+//-*-c++-*-
+#ifndef INCLUDED_SerialCommPort_h_
+#define INCLUDED_SerialCommPort_h_
+
+#include "FileSystemCommPort.h"
+#include <fcntl.h>
+
+//! Provides CommPort interface to serial port devices -- essentially just a FileSystemCommPort, but can apply terminal IO settings
+/*! You could use FileSystemCommPort instead of this class, and thus
+ *  rely on a prior manual call to stty.  However, other programs (or rebooting)
+ *  will reset those parameters, so it's nice to use this class to ensure the
+ *  desired settings are reapplied each time the device is opened. */
+class SerialCommPort : public FileSystemCommPort {
+public:
+	//! constructor
+	explicit SerialCommPort(const std::string& name)
+	: FileSystemCommPort(autoRegisterSerialCommPort,name),
+	baudRate(57600), dataBits(8), stopBits(1), parity(NONE,parityNames), sttyConfig(),
+	fd(-1)
+	{
+		addEntry("Baud",baudRate,"Communication frequency (bits per second)");
+		addEntry("DataBits",dataBits,"Number of data bits to send at a time (5-8)");
+		addEntry("StopBits",stopBits,"Number of stop bits to send between data bits (1-2)");
+		addEntry("Parity",parity,"Parity bit can be sent for error checking\n"+parity.getDescription());
+		addEntry("TTYFlags",sttyConfig,"Additional configuration string to pass to stty\n(may be unavailble when using non-standard baud rates on OS X)");
+		baudRate.addPrimitiveListener(this);
+		dataBits.addPrimitiveListener(this);
+		stopBits.addPrimitiveListener(this);
+		parity.addPrimitiveListener(this);
+		sttyConfig.addPrimitiveListener(this);
+	}
+	
+	//! destructor
+	~SerialCommPort() {
+		baudRate.removePrimitiveListener(this);
+		dataBits.removePrimitiveListener(this);
+		stopBits.removePrimitiveListener(this);
+		parity.removePrimitiveListener(this);
+		sttyConfig.removePrimitiveListener(this);
+	}
+
+	virtual std::string getClassName() const { return autoRegisterSerialCommPort; }
+	
+	virtual bool open() {
+		if(opened==0) { // just do it on initial call
+			// open serial port, need to keep it open through the FileSystemCommPort opening
+			fd = ::open(path.c_str(), O_RDWR | O_NONBLOCK);
+			setupSerial();
+		}
+		return FileSystemCommPort::open();
+	}
+	
+	virtual bool close() {
+		bool ans = FileSystemCommPort::close();
+		if(opened==0) {
+			::close(fd);
+			fd=-1;
+		}
+		return ans;
+	}
+	
+	//! watches #sttyConfig, reapplies the settings if changed
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl) {
+		if(&pl==&sttyConfig) {
+			setupSerial();
+		} else if(&pl==&baudRate) {
+			setupSerial();
+		} else if(&pl==&dataBits) {
+			if(dataBits<5 || dataBits>8) {
+				std::cerr << "Cannot set DataBits to " << dataBits << ", reset to " << dataBits.getPreviousValue() << std::endl;
+				dataBits=dataBits.getPreviousValue();
+				return;
+			}
+			setupSerial();
+		} else if(&pl==&stopBits) {
+			if(stopBits<1 || stopBits>2) {
+				std::cerr << "Cannot set StopBits to " << stopBits << ", reset to " << stopBits.getPreviousValue() << std::endl;
+				stopBits=stopBits.getPreviousValue();
+				return;
+			}
+			setupSerial();
+		} else if(&pl==&parity) {
+			setupSerial();
+		} else {
+			// path or mode changed... if opened, will be called if changing path...
+			FileSystemCommPort::plistValueChanged(pl);
+		}
+	}
+	
+	plist::Primitive<unsigned int> baudRate;
+	plist::Primitive<unsigned int> dataBits;
+	plist::Primitive<unsigned int> stopBits;
+	enum parity_t { EVEN, ODD, NONE };
+	static const char * const parityNames[];
+	plist::NamedEnumeration<parity_t> parity;
+	plist::Primitive<std::string> sttyConfig; //!< Configuration string to pass to stty
+	
+protected:
+	//! file descriptor for serial port -- needed for tcsetattr and ioctl interfaces
+	int fd;
+	
+	//! performs serial port initialization (if fd is non-negative)
+	virtual void setupSerial();
+	
+	void dispError(const char* where, int ret, int err);
+		
+	//! holds the class name, set via registration with the CommPort registry
+	static const std::string autoRegisterSerialCommPort;
+};
+
+/*! @file
+* @brief Describes SerialCommPort, which provides CommPort interface to serial port devices -- essentially just a FileSystemCommPort, but can apply terminal IO settings
+* @author Ethan Tira-Thompson (ejt) (Creator)
+*
+* $Author: ejt $
+* $Name: tekkotsu-4_0 $
+* $Revision: 1.4 $
+* $State: Exp $
+* $Date: 2007/11/08 16:30:46 $
+*/
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSource.h ./local/DataSource.h
--- ../Tekkotsu_3.0/local/DataSource.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSource.h	2007-07-23 23:46:35.000000000 -0400
@@ -0,0 +1,163 @@
+//-*-c++-*-
+#ifndef INCLUDED_DataSource_h_
+#define INCLUDED_DataSource_h_
+
+#include <string>
+#include <iostream>
+
+/* Usage cases:
+
+Pulled (on demand):
+	block with timeout: save bandwidth, accept latency -- load only after last was read and framerate delay
+	sleep: minimize latency, waste bandwidth -- send requests at framerate
+Pushed (sent by source):
+	block (no timeout): when new data arrives, insert into queue (might overwrite last queue slot)
+	sleep: can't block, have to poll at framerate
+*/
+
+class LoadDataThread;
+
+//! abstract base class for simulator data sources
+/*! Each subclass will implement loading data from some piece of hardware or network protocol.  This class
+ *  is expected to be tied to a LoadDataThread (or subclass) which holds configuration settings which might
+ *  be shared by multiple data sources, in particular LoadDataThread::src.
+ *
+ *  Ideally, getData() should return the most recent unprocessed data -- meaning that if you are pulling
+ *  from a realtime source like a network stream, if multiple frames have arrived since the last call to
+ *  getData(), you should return the most recent frame of the bunch.
+ *
+ *  If your data source provides sensor data including current output values, you should call
+ *  providingOutput() for those outputs when you start being used by a LoadDataThread
+ *  (e.g. setDataSourceThread() is called), and ignoringOutput() when you are no longer active
+ *  (e.g. setDataSourceThread() is called with NULL).  This prevents the Motion process from
+ *  clobbering your readings with its own feedback.
+ */
+class DataSource {
+public:
+	DataSource() : frozen(true), framerate(-1), verbose(0), thread(NULL) {} //!< constructor
+	DataSource(const DataSource& ds) : frozen(ds.frozen), framerate(ds.framerate), verbose(ds.verbose), thread(NULL) {} //!< copy constructor, just in case your subclass wants it
+	DataSource& operator=(const DataSource&) { return *this; } //!< assignment operator, just in case your subclass wants it
+	virtual ~DataSource() {} //!< destructor
+
+	//! returns the simulator time of the next data segment
+	/*! should be in the future if nothing new since last data segment, otherwise should be the 
+	 *  timestamp of the most recent data segment (older segments are skipped), return -1U if there is no more data
+	 *  @see timestamp argument of getData() */
+	virtual unsigned int nextTimestamp()=0;
+	
+	//! returns a descriptive name of the next data segment for user feedback
+	/*! @see name argument of getData() */
+	virtual const std::string& nextName()=0;
+	
+	//! called to retrieve the most recent data segment, or blocking until new data is available
+	/*! @param[out] payload on return, should point to beginning of data segment, or NULL if none available
+	 *  @param[out] payloadSize on return, should indicate size in bytes of data segment as @a payload
+	 *  @param[in] timestamp the suggested return time; if multiple samples may be taken in the interval, they should be skipped until this time
+	 *  @param[out] timestamp on return, should contain the time at which the data arrived (real time stream) or was scheduled to be sent (log on disk)
+	 *  @param[out] name on return, a human-readable name for the frame -- e.g. filename for a data file loaded from disk
+	 *  @return frame serial number, used to tell when frames from the data source have been dropped (indicated by the return value incrementing by more than one)
+	 *
+	 *  If no more data is available, set payload to NULL, and return the current frame (i.e. don't increment serial number).
+	 *
+	 * This call <b>should block</b> until data is available.  Other functions may be called
+	 * asynchronously from other threads while in this function, see ThreadNS::Lock to implement
+	 * mutual exclusion locks if needed.
+	 *
+	 * The input value of @a timestamp is a suggestion from the user's requested framerate -- try
+	 * to return the frame closest to it.  If it is already past (e.g. 0 on 'advance'), return the current data!
+	 * If you return a timestamp in the future, the LoadDataThread will sleep until the appropriate time.
+	 * 
+	 * Note that this can be called when the source is frozen, which means you should unfreeze,
+	 * get the current (unread) data or block until the next data, freeze again, and return the data.  */
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name)=0;
+	
+	//! called by simulator when the data source's activity changes; calls doFreeze() or doUnfreeze() as appropriate
+	/*! You probably don't want to override this function -- that's what doFreeze() doUnfreeze are for! */
+	virtual void setFrozen(bool fr) { if(fr==frozen) return; if((frozen=fr)) doFreeze(); else doUnfreeze(); }
+	virtual bool getFrozen() const { return frozen; } //!< returns #frozen status
+	
+	//! if called, indicates a request to restart/reinitialize the data source
+	/*! For example, a FileSystemDataSource would go back to the beginning of its list,
+	 *  and a network-based source would close and reopen the connection */
+	virtual void reset() {}
+	
+	//! called by the LoadDataThread subclass, allows you to register for properties which your subclass may care about
+	/*! a pointer to the LoadDataThread is passed when this is becoming the current data source;
+	 *  NULL will be passed when the data source is no longer being used */
+	virtual void setDataSourceThread(LoadDataThread* th) { thread=th; }
+	//! returns the LoadDataThread using this data source
+	virtual LoadDataThread* getDataSourceThread() const { return thread; }
+	
+	virtual void setDataSourceFramerate(float fr) { framerate=fr; } //!< called by LoadDataThread whenever the expected framerate changes (LoadDataThread::framerate)
+	virtual void setDataSourceVerbose(int v) { verbose=v; } //!< called by LoadDataThread whenever the requested verbosity level changes (LoadDataThread::verbosity)
+	
+	//! Called by simulator during initialization to tell DataSources where the array of output reference counts are stored (see #providedOutputs)
+	/*! This would need to point into a shared memory region if using multi-process model, hence we can't just
+	 *  use process-local static allocation. */
+	static void setOutputTracker(unsigned int outputs[]) { providedOutputs=outputs; }
+	
+	//! will be called by initialization code prior to first getData() if client code is going to block on getting the first sensor reading
+	static void setNeedsSensor(bool waiting) { requiresFirstSensor=waiting; }
+	
+protected:
+	//! subclasses should call this if they provide sensor updates which will contain a measurement of the current position of output @a i.
+	/* A DataSource should consider itself providing an output if it will be sending some kind of measurement of
+	 *  the current value of an output, and has been assigned to a LoadDataThread
+	 *  (i.e. setDataSourceThread() has been called and #thread is non-NULL).\n
+	 *  This prevents the motion process from clobbering your readings with its own feedback.  */
+	static void providingOutput(unsigned int i) {
+		if(providedOutputs==NULL) {
+			std::cerr << "Warning: unable to access DataSource::providedOutputs (NULL) +" << i << std::endl;
+			return;
+		}
+		providedOutputs[i]++;
+	}
+	//! subclasses should call this if they used to, but will no longer, provide sensor updates containing the current position of output @a i.
+	/*! You don't need to call this if you didn't previously call providingOutput(). */
+	static void ignoringOutput(unsigned int i) {
+		if(providedOutputs==NULL) {
+			std::cerr << "Warning: unable to access DataSource::providedOutputs (NULL) -" << i << std::endl;
+			return;
+		}
+		if(providedOutputs[i]==0) {
+			std::cerr << "ERROR: DataSource output tracking underflow (" << __FILE__ << ":" << __LINE__ << ")" << std::endl;
+			return;
+		}
+		providedOutputs[i]--;
+	}
+
+	virtual void doFreeze() {} //!< user hook for when #frozen is set to true
+	virtual void doUnfreeze() {} //!< user hook for when #frozen is set to false
+	
+	bool frozen;	//!< indicates that data is going to be requested "sparsely"; logged data sources should not increment with time
+	float framerate;
+	int verbose;
+	LoadDataThread* thread; //!< stores last call to setParent()
+
+	//! if true, indicates that client code is going to wait for sensor readings returned by getData before executing
+	/*! Allocation defined in LoadDataThread.cc */
+	static bool requiresFirstSensor;
+
+private:
+	//! The counts of which outputs are being provided are used so the motion process can tell if it needs to provide feedback.
+	/*! Subclasses should call providingOutput() and ignoringOutput() when they start and stop providing an output.
+	 *  A DataSource should consider itself providing an output if it will be sending some kind of measurement of
+	 *  the current value of an output, and has been assigned to a LoadDataThread
+	 *  (i.e. setDataSourceThread() has been called and #thread is non-NULL).
+	 *
+	 *  Allocation is found in LoadDataThread.cc to avoid file clutter (no other need for a DataSource.cc) */
+	static unsigned int * providedOutputs;
+};
+
+/*! @file
+ * @brief Defines DataSource, an abstract base class for simulator data sources
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.8 $
+ * $State: Exp $
+ * $Date: 2007/07/24 03:46:35 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSources/CameraSourceOSX.cc ./local/DataSources/CameraSourceOSX.cc
--- ../Tekkotsu_3.0/local/DataSources/CameraSourceOSX.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSources/CameraSourceOSX.cc	2007-11-12 23:16:05.000000000 -0500
@@ -0,0 +1,669 @@
+#if defined(__APPLE__) && !defined(__x86_64__)
+
+#include "CameraSourceOSX.h"
+#include "Shared/LoadSave.h"
+#include "Shared/get_time.h"
+#include "Shared/RobotInfo.h"
+#include <pthread.h>
+#include <set>
+#include <sstream>
+#include <iostream>
+
+using namespace std;
+
+static pthread_key_t qtInit;
+struct QTThreadInfo {};
+
+static bool doGlobalQTInit();
+static bool autoRegisterQTInit = doGlobalQTInit();
+
+bool checkQTThreadInit() {
+	if(!autoRegisterQTInit)
+		return false;
+	if(pthread_getspecific(qtInit)!=NULL)
+		return true;
+	OSErr err = EnterMoviesOnThread(kQTEnterMoviesFlagDontSetComponentsThreadMode);
+	if(err!=noErr) {
+		cerr << "CameraSource: EnterMoviesOnThread returned error " << err << endl;
+		return false;
+	}
+	pthread_setspecific(qtInit,new QTThreadInfo);
+	return true;
+}
+static void qtThreadDestructor(void* threadInfo) {
+	ExitMoviesOnThread();
+	delete static_cast<QTThreadInfo*>(threadInfo);
+}
+static bool doGlobalQTInit() {
+	int err = pthread_key_create(&qtInit,qtThreadDestructor);
+	if(err!=0)
+		cerr << "CameraSource: error during doGlobalQTInit, pthread_key_create:" << strerror(err) << endl;
+	return (err==0);
+}
+
+CameraSource::~CameraSource() {
+	if(thread!=NULL)
+		setDataSourceThread(NULL);
+	if(sgChan!=NULL)
+		SGDisposeChannel(sg,sgChan);
+	sgChan=NULL;
+	if(gworld!=NULL)
+		DisposeGWorld(gworld);
+	gworld=NULL;
+	// docs say that QTNewGWorldFromPtr is supposed to mark the underlying buffer
+	// so that DisposeGWorld doesn't release it, but that doesn't seem to be the case...
+	// If we delete here, we get double-free warnings.
+	/*if(gworldBuf!=NULL)
+		free(gworldBuf);*/
+	gworldBuf=NULL;
+	if(sg!=NULL)
+		CloseComponent(sg);
+	sg=NULL;
+	
+	delete [] imgbuf;
+	imgbuf=NULL;
+}
+
+void CameraSource::initCamera() {
+	OSErr err;
+	
+	// open the sequence grabber, assuming there's only ever one component of this type listed
+	sg = OpenDefaultComponent(SeqGrabComponentType, 0);
+	if(sg==NULL) throw std::make_pair(NULL,"OpenDefaultComponent(SeqGrabComponentType,0)");
+	
+	// initialize the default sequence grabber component
+	err = SGInitialize(sg);
+	if(err!=noErr) throw std::make_pair(err,"SGInitialize");
+	
+	err = SGSetDataRef(sg, 0, 0, seqGrabToMemory | seqGrabDontMakeMovie | seqGrabDataProcIsInterruptSafe);
+	if(err!=noErr) throw "SGSetDataRef";
+		
+	// this section would get the "default" capture device
+	/*
+	ComponentDescription searchCompDesc;
+	memset(&searchCompDesc,0,sizeof(searchCompDesc));
+	searchCompDesc.componentType=SeqGrabChannelType;
+	searchCompDesc.componentSubType=VideoMediaType;
+	Component chanComponent = FindNextComponent(chanComponent,&searchCompDesc);
+	if(chanComponent==0) throw std::make_pair(err,"FindNextComponent");
+		
+	SGNewChannelFromComponent(sg,&sgChan,chanComponent);
+	if(err!=noErr) throw std::make_pair(err,"SGNewChannelFromComponent");
+	 */
+
+	// instead, open the *specified* capture device
+	// thanks Harald ( hxr AT users sourceforge net ) for 'wacaw' source to demonstrate this
+	err = SGNewChannel(sg, VideoMediaType, &sgChan);
+	if(err!=noErr) throw std::make_pair(err,"SGNewChannel");
+	
+	unsigned char pstr[256]; // sigh, convert devName to pascal-style string
+	pstr[0]=deviceName.size();
+	memcpy(pstr+1,deviceName.c_str(),pstr[0]);
+	err = SGSetChannelDevice(sgChan, pstr);
+	if(err!=noErr) throw std::make_pair(err,"SGSetChannelDevice");
+	err = SGSetChannelDeviceInput(sgChan,devInputIdx);
+	if(err!=noErr) throw std::make_pair(err,"SGSetChannelDeviceInput");
+	
+	// does this need to be done? not found in any sample code...
+	// doesn't seem to work here in any case... 
+	// (error -9400: noDeviceForChannel; tried before or after the SGSetChannelDevice()...)
+	/*err = SGInitChannel(sgChan,sg);
+	if(err!=noErr) throw std::make_pair(err,"SGInitChannel");*/
+			
+	// get the active rectangle 
+	Rect  srcBounds;
+	err = SGGetSrcVideoBounds(sgChan, &srcBounds);
+	if(err!=noErr)
+		std::cerr << "Warning: CameraSource SGGetSrcVideoBounds returned error " << err << std::endl;
+	else {
+		srcBounds.right -= srcBounds.left;
+		srcBounds.bottom -= srcBounds.top;
+		srcBounds.left = srcBounds.top = 0;
+		//cout << "original bounds " << srcBounds.right << "x" << srcBounds.bottom << endl;
+		if((unsigned int)srcBounds.right>CameraResolutionX*2 || (unsigned int)srcBounds.bottom>CameraResolutionY*2) {
+			srcBounds.right=CameraResolutionX*2;
+			srcBounds.bottom=CameraResolutionY*2;
+			//cout << "restricting to " << srcBounds.right << "x" << srcBounds.bottom << endl;
+		}
+		err = SGSetChannelBounds(sgChan, &srcBounds);
+		if(err!=noErr) std::cerr << "Warning: SGSetChannelBounds returned error " << err << std::endl;
+	}
+	
+	// set options for our expected usage
+	err = SGSetChannelUsage(sgChan, seqGrabRecord | seqGrabLowLatencyCapture /* | seqGrabPreview | seqGrabAlwaysUseTimeBase */);
+	if(err!=noErr) throw std::make_pair(err,"SGSetChannelUsage");
+	
+	// don't need a gworld (yet) -- we want to grab the raw YUV bytes from the camera
+	/*unsigned int width = srcBounds.right-srcBounds.left;
+	unsigned int height = srcBounds.bottom-srcBounds.top;
+	gworldBuf = new char[width*height*4];
+	err = QTNewGWorldFromPtr(&gworld, k32ARGBPixelFormat, &srcBounds, NULL, NULL, 0, gworldBuf, width*4);
+	if(err!=noErr) throw std::make_pair(err,"QTNewGWorldFromPtr"); */
+	
+	// still have to call SGSetGWorld() though or else SGPrepare() will complain later
+	err = SGSetGWorld(sg, NULL, NULL);
+	if(err!=noErr) throw std::make_pair(err,"SGSetGWorld");
+	
+	//SGSettingsDialog(sg, sgChan, 0, nil, 0, nil, 0);
+	
+	// set up the video bottlenecks so we can get our queued frame count
+	VideoBottles vb;
+	memset(&vb,0,sizeof(VideoBottles));
+	err = SGGetVideoBottlenecks(sgChan, &vb);
+	if(err!=noErr) throw std::make_pair(err,"SGGetVideoBottlenecks");
+	
+	vb.procCount = 9; // there are 9 bottleneck procs; this must be filled in
+	vb.grabCompressCompleteProc = NewSGGrabCompressCompleteBottleUPP(compressCompleteBottleProc);
+	
+	err = SGSetVideoBottlenecks(sgChan, &vb);
+	if(err!=noErr) throw std::make_pair(err,"SGSetVideoBottlenecks");
+	
+	// specify a sequence grabber data function
+	err = SGSetDataProc(sg, NewSGDataUPP(grabDataProc), (long)this);
+	if(err!=noErr) throw std::make_pair(err,"SGSetDataProc");
+	err = SGSetChannelRefCon(sgChan, (long)this); // callback reference context
+	if(err!=noErr) throw std::make_pair(err,"SGSetChannelRefCon");
+
+	// try to switch to YUV mode
+	// kComponentVideoCodecType doesn't seem to do what I expect, and k422YpCbCr8CodecType doesn't seem supported...
+	err = SGSetVideoCompressorType(sgChan,k422YpCbCr8CodecType); // produces 2vuy images
+	if(err!=noErr) {
+		if(err!=noCodecErr) std::cerr << "    Could not switch to yuv codec (k422YpCbCr8CodecType), err " << err << std::endl;
+		
+		// try component video...
+		// Actually, this is a little slower than converting each frame individually, so we'll do that instead.
+		// See color space specification in NewGWorld call below...
+		/*err = SGSetVideoCompressorType(sgChan,kComponentVideoCodecType); // produces yuv2/yuvu images
+		if(err==noCodecErr) std::cerr << "    Could not switch to yuv codec (k422YpCbCr8CodecType or kComponentVideoCodecType), not supported by camera (?)" << std::endl;
+		else if(err!=noErr) std::cerr << "    Could not switch to yuv codec (kComponentVideoCodecType), err " << err << std::endl;*/
+	}
+	
+	// just for debugging...
+	/*OSType ct;
+	err = SGGetVideoCompressorType(sgChan,&ct);
+	if(err!=noErr) std::cerr << "    Could not get current codec" << std::endl;
+	else { std::cout << "    Current codec type is "; dumpLiteral(ct); std::cout << std::endl; }*/
+}
+
+void CameraSource::setDataSourceThread(LoadDataThread* ldt) {
+	DataSource::setDataSourceThread(ldt);
+	if(!checkQTThreadInit())
+		return;
+	if(thread!=NULL && !grabbing) { // we're about to be used!
+		// lights...camera...
+		OSErr err = SGPrepare(sg, false, true);
+		if(err!=noErr) {
+			cerr << "CameraSource: SGPrepare returned error " << err << endl;
+			return;
+		}
+		
+		/*
+		// make sure the timebase used by the video channel is being driven by
+		// the sound clock if there is a sound channel, this has to be done
+		// after calling SGPrepare - see Q&A 1314
+		if (NULL != sgchanSound) {
+			TimeBase soundTimeBase = NULL, sgTimeBase = NULL;
+			err = SGGetTimeBase(this->seqGrab, &sgTimeBase);
+			if(noErr == err)
+				err = SGGetChannelTimeBase(sgchanSound, &soundTimeBase);
+			if (noErr == err && NULL != soundTimeBase)
+				SetTimeBaseMasterClock(sgTimeBase, (Component)GetTimeBaseMasterClock(soundTimeBase), NULL);
+		}
+		 */
+		
+		// ...action
+		err = SGStartRecord(sg);
+		if(err!=noErr) {
+			cerr << "CameraSource: SGStartRecord returned error " << err << endl;
+			err = SGRelease(sg); // undo SGPrepare()
+			if(err!=noErr)
+				cerr << "CameraSource: SGRelease returned error during recovery " << err << endl;
+			return;
+		}
+		
+		grabbing=true;
+		
+	} else if(thread==NULL || grabbing) {
+		OSErr err = SGStop(sg); // undo SGStartPreview or SGStartRecord
+		if(err!=noErr)
+			cerr << "CameraSource: SGStop returned error " << err << endl;
+		err = SGRelease(sg); // undo SGPrepare()
+		if(err!=noErr)
+			cerr << "CameraSource: SGRelease returned error " << err << endl;
+		grabbing=false;
+	}
+}
+
+void CameraSource::setDataSourceFramerate(float fps) {
+	DataSource::setDataSourceFramerate(fps);
+	float s = std::max(getTimeScale(),.1f);
+	ComponentResult err = SGSetFrameRate(sgChan, FloatToFixed(framerate*s));
+	if(err!=noErr)
+		std::cerr << "CameraSource::setDataSourceFramerate("<<fps<<") had error calling SGSetFrameRate " << err << endl;
+}
+
+
+unsigned int CameraSource::getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& dataname) {
+	payload=NULL;
+	payloadSize=0;
+	if(!checkQTThreadInit() || !grabbing)
+		return frame;
+	
+	//cout << "getData at " << get_time() << " request " << timestamp << endl;
+	setDataSourceFramerate(framerate);
+	
+	unsigned int t=get_time();
+	if(timestamp>t)
+		usleep(static_cast<unsigned int>((timestamp-t)*1000/(getTimeScale()>0?getTimeScale():1.f)));
+	if(!grabbing) // in case we shutdown while asleep!
+		return frame;
+	
+	unsigned int prev=frame;
+	
+	OSErr err = SGIdle(sg);
+	if (err!=noErr && err!=callbackerr) {
+		// some error specific to SGIdle occurred - any errors returned from the
+		// data proc will also show up here and we don't want to write over them
+		
+		// in QT 4 you would always encounter a cDepthErr error after a user drags
+		// the window, this failure condition has been greatly relaxed in QT 5
+		// it may still occur but should only apply to vDigs that really control
+		// the screen
+		
+		// you don't always know where these errors originate from, some may come
+		// from the VDig...
+		
+		//DisplayError(pMungData->pWindow, "SGIdle", err);
+		cerr << "CameraSource: SGIdle error " << err << " occurred, resetting camera!" << endl;
+		
+		// ...to fix this we simply call SGStop and SGStartRecord again
+		// calling stop allows the SG to release and re-prepare for grabbing
+		// hopefully fixing any problems, this is obviously a very relaxed
+		// approach
+		err = SGStop(sg); // undo SGStartPreview or SGStartRecord
+		if(err!=noErr)
+			cerr << "CameraSource: SGStop returned error during recovery " << err << endl;
+		err = SGStartRecord(sg);
+		if(err!=noErr) {
+			cerr << "CameraSource: SGStartRecord returned error during recovery " << err << endl;
+			grabbing=false;
+			err = SGRelease(sg); // undo SGPrepare()
+			if(err!=noErr)
+				cerr << "CameraSource: SGRelease returned error during recovery " << err << endl;
+		}
+		return frame;
+	}
+	
+	if(prev!=frame && imgbufUsed!=0) {
+		//cout << "new frame! ";
+		payload=imgbuf; // has been filled in during callback of SGIdle
+		payloadSize=imgbufUsed;
+		timestamp=get_time();
+		dataname=nextName();
+	}
+	
+	return frame;
+}
+	
+void CameraSource::dumpLiteral(OSType t) {
+	union {
+		OSType v;
+		char s[4];
+	} x;
+	x.v=t;
+	cout << x.s[3] << x.s[2] << x.s[1] << x.s[0];
+}
+
+
+/* 
+* Purpose:   used to allow us to figure out how many frames are queued by the vDig
+*
+* Notes:     the UInt8 *queuedFrameCount replaces Boolean *done.  0 (==false) still means no frames, and 1 (==true) one,
+*            but if more than one are available, the number should be returned here - The value 2 previously meant more than
+*            one frame, so some VDIGs may return 2 even if more than 2 are available, and some will still return 1 as they are
+*            using the original definition.
+*/
+pascal ComponentResult CameraSource::compressCompleteBottleProc(SGChannel c, UInt8 *queuedFrameCount, SGCompressInfo *ci, TimeRecord *t, long refCon)
+{
+	OSErr err;
+	CameraSource* cam = (CameraSource*)refCon;
+	if (NULL == cam) return -1;
+	
+	// call the original proc; you must do this
+	err = SGGrabCompressComplete(c, queuedFrameCount, ci, t);
+	
+	// save the queued frame count so we have it
+	cam->queuedFrames = *queuedFrameCount;
+	/*if(cam->queuedFrames>0)
+		cout << "compressCompleteBottleProc " << cam->queuedFrames << endl;*/
+	
+	return err;
+}
+
+
+/*****************************************************
+* Purpose:   sequence grabber data procedure - this is where the work is done
+*
+* Notes:
+
+the sequence grabber calls the data function whenever
+any of the grabber's channels write digitized data to the destination movie file.
+
+NOTE: We really mean any, if you have an audio and video channel then the DataProc will
+be called for either channel whenever data has been captured. Be sure to check which
+channel is being passed in. In this example we never create an audio channel so we know
+we're always dealing with video.
+
+This data function does two things, it first decompresses captured video
+data into an offscreen GWorld, draws some status information onto the frame then
+transfers the frame to an onscreen window.
+
+For more information refer to Inside Macintosh: QuickTime Components, page 5-120
+c - the channel component that is writing the digitized data.
+p - a pointer to the digitized data.
+len - the number of bytes of digitized data.
+offset - a pointer to a field that may specify where you are to write the digitized data,
+and that is to receive a value indicating where you wrote the data.
+chRefCon - per channel reference constant specified using SGSetChannelRefCon.
+time	- the starting time of the data, in the channel's time scale.
+writeType - the type of write operation being performed.
+seqGrabWriteAppend - Append new data.
+seqGrabWriteReserve - Do not write data. Instead, reserve space for the amount of data
+specified in the len parameter.
+seqGrabWriteFill - Write data into the location specified by offset. Used to fill the space
+previously reserved with seqGrabWriteReserve. The Sequence Grabber may
+call the DataProc several times to fill a single reserved location.
+refCon - the reference constant you specified when you assigned your data function to the sequence grabber.
+*/
+pascal OSErr CameraSource::grabDataProc(SGChannel c, Ptr p, long len, long *offset, long chRefCon, TimeValue time, short writeType, long refCon)
+{
+#pragma unused(offset,chRefCon,writeType)
+	//cout << "MungGrabDataProc" << endl;
+	
+	CameraSource* cam = (CameraSource*)refCon; // might want to use chRefCon instead?
+	if (NULL == cam) {
+		cerr << "CameraSource::grabDataProc called without a context" << endl;
+		return -1;
+	}
+	
+	// we only care about the video	
+	if (c != cam->sgChan) {
+		cerr << "CameraSource::grabDataProc called for something other than our channel" << endl;
+		return noErr; //not an error as far as OS is concerned...
+	}
+		
+	++cam->skipped; // unless we make it through all the way, in which case we'll subtract this off and add to frame instead
+	
+	ComponentResult err=noErr;
+	TimeValue frameTimeDelta=0;
+	ImageDescriptionHandle imageDesc = NULL;
+	try {
+		// apparently can't do this before we get a frame (I tried, get seqGrabInfoNotAvailable (-9407) on SGGetChannelTimeScale
+		if(cam->chanTimeScale==0) {
+			Fixed framesPerSecond;
+			long  milliSecPerFrameIgnore, bytesPerSecondIgnore;
+			
+			// first time here so get the time scale & timebase
+			err = SGGetChannelTimeScale(cam->sgChan, &cam->chanTimeScale);
+			if(err!=noErr) throw make_pair(err,"SGGetChannelTimeScale");
+			
+			err = SGGetTimeBase(cam->sg, &cam->chanTimeBase);
+			if(err!=noErr) throw make_pair(err,"SGGetTimeBase");
+			
+			err = VDGetDataRate(SGGetVideoDigitizerComponent(cam->sgChan), &milliSecPerFrameIgnore, &framesPerSecond, &bytesPerSecondIgnore);
+			if(err!=noErr) throw make_pair(err,"VDGetDataRate");
+			
+			cam->duration = cam->chanTimeScale / (framesPerSecond >> 16);
+		}
+		
+		// retrieve a channel's current sample description, the channel returns a
+		// sample description that is appropriate to the type of data being captured
+		imageDesc = (ImageDescriptionHandle)NewHandle(0);
+		err = SGGetChannelSampleDescription(c, (Handle)imageDesc);
+		if(err!=noErr) throw "SGGetChannelSampleDescription";
+		string formatName = p2c((**imageDesc).name);
+		//cout << formatName << " TYPE IS "; dumpLiteral((**imageDesc).cType); cout << " " << (**imageDesc).width << "x" << (**imageDesc).height << " => " << (**imageDesc).dataSize << " @ " << (**imageDesc).depth << endl;
+		
+		if((**imageDesc).cType==k422YpCbCr8CodecType) { // aka 2vuy
+		
+			cam->imgFrom2vuy((unsigned char*)p, (**imageDesc).width, (**imageDesc).height, (**imageDesc).depth, (**imageDesc).dataSize);
+			
+		} else if((**imageDesc).cType==kComponentVideoCodecType) { // aka yuv2 aka yuvu
+			
+			cam->imgFromyuv2((unsigned char*)p, (**imageDesc).width, (**imageDesc).height, (**imageDesc).depth, (**imageDesc).dataSize);
+			
+		} else {
+			// use a OS provided decompression sequence to put it in the gworld
+			if (cam->drawSeq == 0) {
+				
+				// set up decompression sequence	
+				Rect				   sourceRect = { 0, 0, 0, 0 };
+				MatrixRecord		   scaleMatrix;	
+				CodecFlags			   cFlags = codecNormalQuality;
+				
+				if(cam->gworld==NULL) {
+					Rect  srcBounds;
+					err = SGGetChannelBounds(cam->sgChan, &srcBounds);
+					if(err!=noErr) throw "SGGetSrcVideoBounds";
+					unsigned int width = srcBounds.right-srcBounds.left;
+					unsigned int height = srcBounds.bottom-srcBounds.top;
+					cam->gworldBuf = (char*)malloc(width*height*2); // NewPtr(width*height*4);
+					// once upon a time I could've sworn I had to use k32ARGBPixelFormat and do
+					// the color space conversion manually, but apparently this is working... (yay! very fast...)
+					err = QTNewGWorldFromPtr(&cam->gworld, k2vuyPixelFormat, &srcBounds, NULL, NULL, 0, cam->gworldBuf, width*2);
+					if(err!=noErr) throw "QTNewGWorldFromPtr";
+				}
+					
+				// make a scaling matrix for the sequence
+				sourceRect.right = (**imageDesc).width;
+				sourceRect.bottom = (**imageDesc).height;
+				RectMatrix(&scaleMatrix, &sourceRect, &(*GetPortPixMap(cam->gworld))->bounds);
+				
+				// begin the process of decompressing a sequence of frames
+				// this is a set-up call and is only called once for the sequence - the ICM will interrogate different codecs
+				// and construct a suitable decompression chain, as this is a time consuming process we don't want to do this
+				// once per frame (eg. by using DecompressImage)
+				// for more information see Ice Floe #8 http://developer.apple.com/quicktime/icefloe/dispatch008.html
+				// the destination is specified as the GWorld
+				err = DecompressSequenceBeginS(&cam->drawSeq,					// pointer to field to receive unique ID for sequence
+					imageDesc,							// handle to image description structure
+					p,									// points to the compressed image data
+					len,                             		// size of the data buffer
+					cam->gworld,	// port for the DESTINATION image
+					NULL,									// graphics device handle, if port is set, set to NULL
+					NULL,									// decompress the entire source image - no source extraction
+					&scaleMatrix,							// transformation matrix
+					srcCopy,								// transfer mode specifier
+					(RgnHandle)NULL,						// clipping region in dest. coordinate system to use as a mask
+					0,									// flags
+					cFlags, 								// accuracy in decompression
+					bestSpeedCodec);						// compressor identifier or special identifiers ie. bestSpeedCodec
+				
+				if(err!=noErr) throw "DecompressSequenceBeginS";
+			}
+			
+			// get the TimeBase time and figure out the delta between that time and this frame time
+			TimeValue timeBaseTime, timeBaseDelta;
+			timeBaseTime = GetTimeBaseTime(cam->chanTimeBase, cam->chanTimeScale, NULL);
+			timeBaseDelta = timeBaseTime - time;
+			frameTimeDelta = time - cam->lastTime;
+			
+			if (timeBaseDelta < 0) return err; // probably don't need this
+			
+			// if we have more than one queued frame and our capture rate drops below 10 frames, skip the frame to try and catch up
+			if ((cam->queuedFrames > 1) &&  ((cam->chanTimeScale / frameTimeDelta) < 10) && (cam->skipped < 15)) {
+				// do nothing, skipping frame
+			} else {
+				CodecFlags ignore;
+				
+				// decompress a frame into the window - can queue a frame for async decompression when passed in a completion proc
+				err = DecompressSequenceFrameS(cam->drawSeq,	// sequence ID returned by DecompressSequenceBegin
+					 p,					// pointer to compressed image data
+					 len,					// size of the buffer
+					 0,					// in flags
+					 &ignore,				// out flags
+					 NULL);				// async completion proc
+				
+				if(err!=noErr) throw "DecompressSequenceFrameS";
+				
+				cam->skipped = 0;
+				cam->lastTime = time;
+				
+				{
+					PixMapPtr pm=*GetPortPixMap(cam->gworld);
+					unsigned int width = pm->bounds.right - pm->bounds.left;
+					unsigned int height = pm->bounds.bottom - pm->bounds.top;
+					unsigned char * s = (unsigned char *)GetPixBaseAddr(&pm);
+					cam->imgFrom2vuy(s,width,height,16,width*height*2);
+				}
+			} 
+		}
+	} catch(const char* call) {
+		cerr << "CameraSource: " << call << " returned error " << err << endl;
+		if(imageDesc!=NULL)
+			DisposeHandle((Handle)imageDesc);
+		return cam->callbackerr=err;
+	}
+	if(imageDesc!=NULL)
+		DisposeHandle((Handle)imageDesc);
+		
+	/*
+	// status information
+	float	fps, averagefps;
+	UInt8   minutes, seconds, frames;
+	
+	fps = (float)cam->chanTimeScale / (float)frameTimeDelta;
+	averagefps = ((float)cam->frame * (float)cam->chanTimeScale) / (float)time;
+	minutes = (time / cam->chanTimeScale) / 60;
+	seconds = (time / cam->chanTimeScale) % 60;
+	frames = (time % cam->chanTimeScale) / frameTimeDelta; //cam->duration;
+	printf("t: %ld, %02d:%02d.%02d, fps:%5.1f av:%5.1f\n", time, minutes, seconds, frames, fps, averagefps);
+	*/
+	
+	// made it!  increment frame and decrement our pessimistic skip
+	++cam->frame;
+	--cam->skipped;
+	
+	return err;
+}
+
+
+/*! 2vuy is an interleaved format, where the u and v channels are downsampled by half.
+*  The first column of pixels has u values, the second column is v's.
+*  For example, the first 6 pixels of a row are stored as: uy, vy, uy, vy, uy, vy, ...  */
+void CameraSource::imgFrom2vuy(const unsigned char * s, short srcWidth, short srcHeight, short depth, long dataSize) {
+#pragma unused(depth,dataSize)
+	unsigned int width=srcWidth/2;
+	unsigned int height=srcHeight/2;
+	size_t reqSize = width * height * 3 + sizeof(unsigned int)*4;
+	if(imgbuf==NULL || imgbufSize<reqSize) {
+		delete [] imgbuf;
+		imgbuf=new char[imgbufSize=reqSize];
+	}
+	
+	unsigned int components=3;
+	char * buf=imgbuf;
+	unsigned int remain=imgbufSize;
+	if(!LoadSave::encodeInc(*layer,buf,remain)) return;
+	if(!LoadSave::encodeInc(width,buf,remain)) return;
+	if(!LoadSave::encodeInc(height,buf,remain)) return;
+	if(!LoadSave::encodeInc(components,buf,remain)) return;
+	
+	const unsigned int srcStride=srcWidth*2;
+	unsigned char * dst=(unsigned char*)buf;
+	unsigned char * const dstEnd=dst+width*height*components;
+	while(dst!=dstEnd) {
+		unsigned char * const rowEnd=dst+width*components;
+		while(dst!=rowEnd) {
+			unsigned int y,u,v;
+			u=*s;
+			u+=*(s+srcStride);
+			++s;
+			
+			y=*s;
+			y+=*(s+srcStride);
+			++s;
+			
+			v=*s;
+			v+=*(s+srcStride);
+			++s;
+			
+			y+=*s;
+			y+=*(s+srcStride);
+			++s;
+			
+			*dst++ = y/4;
+			*dst++ = u/2;
+			*dst++ = v/2;
+		}
+		s+=srcStride;
+	}
+	imgbufUsed=dst-(unsigned char*)imgbuf;
+	if(imgbufUsed!=reqSize) {
+		cerr << "bad payload! " << reqSize << " vs " << imgbufUsed << endl;
+		imgbufUsed=0;
+	}
+}
+
+/*! Similar to 2vuy, except:
+ *  - byte swapped (yu, yv instead of uy, vy)
+ *  - u and v channels are signed instead of unsigned
+ *  - channels use the full byte range, whereas apparently 2vuy only uses 16-235 for the y and 16-240 for the u and v
+ *    (aka 601/YCbCr standard)
+ */
+void CameraSource::imgFromyuv2(const unsigned char * s, short srcWidth, short srcHeight, short depth, long dataSize) {
+#pragma unused(depth,dataSize)
+	unsigned int width=srcWidth/2;
+	unsigned int height=srcHeight/2;
+	size_t reqSize = width * height * 3 + sizeof(unsigned int)*4;
+	if(imgbuf==NULL || imgbufSize<reqSize) {
+		delete [] imgbuf;
+		imgbuf=new char[imgbufSize=reqSize];
+	}
+	
+	unsigned int components=3;
+	char * buf=imgbuf;
+	unsigned int remain=imgbufSize;
+	if(!LoadSave::encodeInc(*layer,buf,remain)) return;
+	if(!LoadSave::encodeInc(width,buf,remain)) return;
+	if(!LoadSave::encodeInc(height,buf,remain)) return;
+	if(!LoadSave::encodeInc(components,buf,remain)) return;
+	
+	const unsigned int srcStride=srcWidth*2;
+	unsigned char * dst=(unsigned char*)buf;
+	unsigned char * const dstEnd=dst+width*height*components;
+	while(dst!=dstEnd) {
+		unsigned char * const rowEnd=dst+width*components;
+		while(dst!=rowEnd) {
+			unsigned int y;
+			int u,v;
+			y=*s;
+			y+=*(s+srcStride);
+			++s;
+			
+			u=(char)*s;
+			u+=(char)*(s+srcStride);
+			++s;
+			
+			y+=*s;
+			y+=*(s+srcStride);
+			++s;
+			
+			v=(char)*s;
+			v+=(char)*(s+srcStride);
+			++s;
+						
+			*dst++ = (y*219/255)/4 + 16;
+			*dst++ = (u*224/255)/2 + 128;
+			*dst++ = (v*224/255)/2 + 128;
+		}
+		s+=srcStride;
+	}
+	imgbufUsed=dst-(unsigned char*)imgbuf;
+	if(imgbufUsed!=reqSize) {
+		cerr << "bad payload! " << reqSize << " vs " << imgbufUsed << endl;
+		imgbufUsed=0;
+	}
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSources/CameraSourceOSX.h ./local/DataSources/CameraSourceOSX.h
--- ../Tekkotsu_3.0/local/DataSources/CameraSourceOSX.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSources/CameraSourceOSX.h	2007-11-09 14:01:13.000000000 -0500
@@ -0,0 +1,106 @@
+//-*-c++-*-
+#ifndef INCLUDED_CameraSource_h_
+#define INCLUDED_CameraSource_h_
+
+#include "local/DataSource.h"
+#include "Shared/plistCollections.h"
+#include <iostream>
+#include <stdexcept>
+#include <map>
+#include <cmath>
+
+#define TARGET_API_MAC_CARBON 1
+#include <Carbon/Carbon.h>
+#include <QuickTime/QuickTime.h>
+
+extern bool checkQTThreadInit();
+
+class CameraSource : public DataSource, public virtual plist::Dictionary {
+public:
+	//! constructor, pass the short name, device name and input index
+	CameraSource(SeqGrabComponent grabber, const std::string& srcName, const std::string& devName, const std::string& inputName, int inputIdx)
+		throw(std::pair<OSErr,const char*>)
+		: DataSource(), layer(0), sg(grabber), sgChan(NULL), gworld(NULL), name(srcName), deviceName(devName), devInputName(inputName), devInputIdx(inputIdx),
+		frame(0), skipped(0), queuedFrames(0), grabbing(false),
+		lastTime(0), duration(0), chanTimeScale(), chanTimeBase(), drawSeq(NULL), callbackerr(noErr),
+		gworldBuf(NULL), imgbuf(NULL), imgbufSize(0), imgbufUsed(0)
+	{
+		initCamera();
+			
+		// plist dictionary stuff
+		setLoadSavePolicy(FIXED,SYNC);
+		addEntry("Layer",layer,"Controls the resolution layer at which the image should be processed.\n"
+		    "0 indicates \"automatic\" mode (picks layer closest to image's resolution), positive numbers indicate the resolution layer directly.\n"
+		    "Negative values are relative to the number of layers marked available by the vision setup, so that typically -1 would correspond to the \"double\" layer, and -2 would correspond to the \"full\" layer.");
+	}
+	
+	//! destructor, free system resources
+	~CameraSource();
+	
+	//! accessor for the instance name
+	virtual const std::string& getName() const { return name; }
+	//! accessor for the device name
+	virtual const std::string& getDeviceName() const { return deviceName; }
+	//! accessor for the name of the input from the device
+	virtual const std::string& getInputName() const { return devInputName; }
+	
+	virtual unsigned int nextTimestamp() { return static_cast<unsigned int>(std::ceil(lastTime+duration)); }
+	virtual const std::string& nextName() { return name; } //!< this is supposed to be the name for the next camera frame, we just reuse our static instance name
+	
+	virtual void setDataSourceThread(LoadDataThread* ldt);
+	virtual void setDataSourceFramerate(float fps);
+	
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	
+	plist::Primitive<int> layer; //!< Controls the resolution layer at which the image should be processed.\n 0 indicates "automatic" mode (picks layer closest to image's resolution), positive numbers indicate the resolution layer directly.\n Negative values are relative to the number of layers marked available by the vision setup, so that typically -1 would correspond to the "double" layer, and -2 would correspond to the "full" layer.
+	
+protected:
+	void initCamera();
+	
+	//! converts from pascal-format string to c-format string
+	static std::string p2c(unsigned char pascalStr[]) {
+		unsigned char len = *pascalStr++;
+		return std::string(reinterpret_cast<char*>(pascalStr),len);
+	}
+
+	static void dumpLiteral(OSType t);
+	static ComponentResult setVideoChannelBounds(SGChannel videoChannel, const Rect *scaledVideoBounds);
+	static pascal ComponentResult compressCompleteBottleProc(SGChannel c, UInt8 *queuedFrameCount, SGCompressInfo *ci, TimeRecord *t, long refCon);
+	static pascal OSErr grabDataProc(SGChannel c, Ptr p, long len, long *offset, long chRefCon, TimeValue time, short writeType, long refCon);
+	
+	//! Resamples a YUV 4:2:2 (aka '2vuy') image to a YUV 4:4:4 form which is expected in getData()'s payload
+	void imgFrom2vuy(const unsigned char * s, short srcWidth, short srcHeight, short depth, long dataSize);
+	//! Resamples a YUV 4:2:2 (aka 'yuv2' or 'yuvu') image to YUV 4:4:4 form which is expected in getData()'s payload
+	void imgFromyuv2(const unsigned char * s, short srcWidth, short srcHeight, short depth, long dataSize);
+	
+	SeqGrabComponent 	sg;	//!< sequence grabber, might need one of these globally instead of one per CameraSource
+	SGChannel			sgChan; //!< channel within the sequence grabber, I think there will be one channel per camera
+	GWorldPtr 		gworld; //!< graphics buffer to store the decompressed image (RGB, will have to be converted back to YUV)
+	std::string name; //!< name to use for image frames
+	const std::string deviceName; //!< name of hardware device the source is connected
+	const std::string devInputName; //!< name of the input on the device (in case a single device has multiple inputs)
+	int devInputIdx; //!< index number of the input
+		
+	unsigned int frame; //!< current frame number
+	unsigned int skipped; //!< number of frames skipped since last successful frame
+	unsigned int queuedFrames; //!< number of frames the system indicates are waiting to be processed
+	bool grabbing; //!< set to true when setDataSourceThread is called with a non-NULL value, but can be set back to false if an error occurs
+	TimeValue 		 	lastTime;
+	UInt32				duration;
+	TimeScale 		 	chanTimeScale;
+	TimeBase			chanTimeBase;
+	ImageSequence 	 	drawSeq;	// unique identifier for our draw sequence
+	OSErr callbackerr; //!< error value from call back, so we can tell if an error came from SGIdle itself or the callback functions it may trigger
+	
+	char * gworldBuf; //!< buffer used for #gworld
+	
+	char * imgbuf;  //!< buffer where YUV image will be stored and returned back to getData caller via payload parameter
+	size_t imgbufSize; //!< size of #imgbuf allocation
+	size_t imgbufUsed; //!< amount of #imgbuf's allocation which is actually in use with data 
+	
+private:
+	CameraSource(const CameraSource&); //!< don't call (copy constructor)
+	CameraSource& operator=(const CameraSource&); //!< don't call (assignment operator)
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSources/FileSystemDataSource.cc ./local/DataSources/FileSystemDataSource.cc
--- ../Tekkotsu_3.0/local/DataSources/FileSystemDataSource.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSources/FileSystemDataSource.cc	2007-11-12 23:16:05.000000000 -0500
@@ -0,0 +1,474 @@
+#include "FileSystemDataSource.h"
+#include "local/DeviceDrivers/LoggedDataDriver.h"
+#include "Shared/get_time.h"
+#include "Shared/RobotInfo.h"
+#include "Shared/string_util.h"
+#include <set>
+#include <fstream>
+#include <sys/types.h>
+#include <sys/mman.h>
+#include <sys/stat.h>
+#include <regex.h>
+#include <dirent.h>
+#include <fcntl.h>
+#include <sys/resource.h>
+#include <cmath>
+#include <errno.h>
+
+using namespace std; 
+
+FileSystemDataSource::~FileSystemDataSource() {
+	clearFiles();
+}
+
+unsigned int FileSystemDataSource::nextTimestamp() {
+	return (curfile!=files.end()) ? static_cast<unsigned int>(nextTime) : -1U;
+}
+
+const std::string& FileSystemDataSource::nextName() {
+	if(curfile!=files.end())
+		return (*curfile)->filename;
+	else {
+		static const std::string noneStr="(none)";
+		return noneStr;
+	}
+}
+
+unsigned int FileSystemDataSource::getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name) {
+	if(curfile==files.end()) {
+		payload=NULL; payloadSize=0;
+		return sn;
+	}
+	if(nextTime<timestamp && std::abs(static_cast<int>(timestamp-nextTime))>std::abs(timestamp-(nextTime+(*curfile)->lifetime))) {
+		float looptime=getLoopTime(true);
+		if(looptime>0) {
+			while(nextTime+looptime<timestamp)
+				nextTime+=looptime;
+		}
+		while(nextTime<timestamp && std::abs(static_cast<int>(timestamp-nextTime))>std::abs(timestamp-(nextTime+(*curfile)->lifetime))) {
+			nextFrame(0); // too late, drop frames
+			sn++;
+		}
+	}
+	if(!(*curfile)->prepared)
+		(*curfile)->prepare();
+	payload=(*curfile)->data;
+	payloadSize=(*curfile)->size;
+	unsigned int reqTime=timestamp;
+	float origNext=nextTime;
+	timestamp=static_cast<unsigned int>(nextTime);
+	name=(*curfile)->filename;
+	nextFrame();
+	if(reqTime==0 && timestamp!=0 && (frozen || getTimeScale()>=0))
+		nextTime=origNext; // the requested time is 0, this is an advance frame, hold nextTime unless not frozen and full speed mode
+	return sn++;
+}
+
+void FileSystemDataSource::setDataSourceThread(LoadDataThread* th) {
+	bool toggle=(th!=NULL && thread==NULL || th==NULL && thread!=NULL);
+	DataSource::setDataSourceThread(th);
+	nextTime=get_time();
+	if(toggle)
+		updateProvidingOutputs();
+}
+
+void FileSystemDataSource::setDataSourceFramerate(float fr) {
+	DataSource::setDataSourceFramerate(fr);
+	if(!usingIndexFile()) {
+		const float dt=1000.f/framerate;
+		bool first = (curfile==files.begin());
+		if(!first)
+			nextTime-=(*--curfile)->lifetime;
+		for(files_t::const_iterator it=files.begin(); it!=files.end(); ++it)
+			(*it)->lifetime=dt;
+		if(!first)
+			nextTime+=(*curfile++)->lifetime;
+		parent.plistValueChanged(path); // to reset the loop time if sharing a source
+	}
+}
+
+const std::string& FileSystemDataSource::getUsedPath() const { return (path.size()==0) ? parent.path : path; }
+
+void FileSystemDataSource::loadFileList(bool clearCurrent/*=true*/, bool reportMissing/*=true*/) {
+	nextTime=freezeTime=get_time();
+	struct stat sb;
+	if(clearCurrent)
+		clearFiles();
+	else if(files.size()==0)
+		clearCurrent=true; // was empty, pretend we just cleared it, have to do the same re-initialization
+	if(getUsedPath().size()==0)
+		return; //empty path means disabled
+	if(stat(getUsedPath().c_str(),&sb)) {
+		if(reportMissing)
+			std::cerr << "FileSystemDataSource could not access path '" << getUsedPath() << "'" << std::endl;
+		return;
+	}
+	if(sb.st_mode&S_IFDIR) {
+		loadFileListFromDirectory();
+	} else {
+		//Test to see if the file matches the filter
+		try {
+			if(string_util::reMatch(getUsedPath(),filenameFilter))
+				loadSingleFile(getUsedPath().c_str());
+			else { //if it doesn't match the image RE, assume it's an index file
+				if(!loadFileListFromIndex())
+					std::cerr << "Source '" << getUsedPath() << "' does not match the filename filter '" << filenameFilter << "' and is not an index list." << std::endl;
+			}
+		} catch(const std::string& err) {
+			std::cerr << err << std::endl;
+		}
+	}
+	if(clearCurrent) {
+		curfile=files.begin();
+		files_t::iterator it=curfile;
+		for(unsigned int numPreload=2; numPreload>0 && it!=files.end(); numPreload--) {
+			(*it)->prepare();
+			if(++it==files.end() && loop)
+				it=files.begin();
+		}
+	}
+	actualLoopTime=naturalLoopTime=calcLoopTime();
+}
+
+void FileSystemDataSource::setFrame(unsigned int f, unsigned int numPreload/*=2*/) {
+	for(;curfile!=files.end() && (*curfile)->prepared; ++curfile) {
+		if(files.size()>MAX_LOAD)
+			(*curfile)->release();
+		else
+			(*curfile)->done();
+	}
+	nextTime=freezeTime=get_time();
+	curfile=files.begin();
+	advance(curfile,f);
+	files_t::iterator it=curfile;
+	for(; numPreload>0 && it!=files.end(); numPreload--) {
+		(*it)->prepare();
+		if(++it==files.end() && loop)
+			it=files.begin();
+	}
+}
+
+void FileSystemDataSource::nextFrame(unsigned int numPreload/*=2*/) {
+	if(numPreload==0 && verbose>=2)
+		cout << "Dropping " << (*curfile)->filename << ' ' << nextTime << ' ' << (*curfile)->lifetime << endl;
+	if(files.size()>MAX_LOAD)
+		(*curfile)->release();
+	else
+		(*curfile)->done();
+	nextTime+=(*curfile)->lifetime;
+	if(++curfile==files.end() && loop) {
+		nextTime+=initialDelay;
+		curfile=files.begin();
+		if(verbose>=3)
+			cout << "Looping file system data source at " << nextTime << " to " << (*curfile)->filename << " (loop time=" << getLoopTime() << ")" << endl;
+	}
+	files_t::iterator it=curfile;
+	for(; numPreload>0 && it!=files.end(); numPreload--) {
+		(*it)->prepare();
+		if(++it==files.end() && loop)
+			it=files.begin();
+	}
+}
+
+float FileSystemDataSource::calcLoopTime() const {
+	if(files.size()==0)
+		return 0;
+	float t=initialDelay;
+	for(files_t::const_iterator it=files.begin(); it!=files.end(); ++it)
+		t+=(*it)->lifetime;
+	return t;
+}
+void FileSystemDataSource::setLoopTime(float t) {
+	if(files.size()==0)
+		return;
+	float remain = t - getLoopTime(true);
+	if(remain + files.back()->lifetime < 0) {
+		std::cerr << "FileSystemDataSource::setLoopTime(" << t << ") would result in a negative frame lifetime" << std::endl;
+		return;
+	}
+	files.back()->lifetime+=remain;
+	actualLoopTime=t;
+}
+
+void FileSystemDataSource::clearFiles() {
+	// FileInfo destructor should take care of deleting data buffers...
+	for(files_t::iterator it=files.begin(); it!=files.end(); ++it)
+		delete *it;
+	files.clear();
+	curfile=files.begin();
+	initialDelay=0;
+	actualLoopTime=naturalLoopTime=0;
+}
+
+void FileSystemDataSource::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&path) {
+		loadFileList();
+	} else {
+		cerr << "FileSystemDataSource didn't handle call to plistValueChanged for " << pl.get() << endl;
+	}
+}
+
+void FileSystemDataSource::loadXML(xmlNode* node) {
+	path.removePrimitiveListener(this);
+	plist::Dictionary::loadXML(node);
+	path.addPrimitiveListener(this);
+	plistValueChanged(path);
+}
+
+void FileSystemDataSource::updateProvidingOutputs() {
+	if(thread!=NULL) {
+		for(unsigned int i=0; i<NumOutputs; i++)
+			providingOutput(i);
+	} else {
+		for(unsigned int i=0; i<NumOutputs; i++)
+			ignoringOutput(i);
+	}
+}
+
+void FileSystemDataSource::loadSingleFile(const std::string& file) {
+	indexed=false;
+	enqueueFile(file,1000.f/framerate);
+}
+
+void FileSystemDataSource::loadFileListFromDirectory() {
+	indexed=false;
+	regex_t re;
+	if(int err=regcomp(&re,filenameFilter.c_str(),REG_EXTENDED | REG_NOSUB)) {
+		char msg[128];
+		regerror(err,&re,msg,128);
+		std::cerr << "Bad filter '" << filenameFilter << "': " << msg << std::endl;
+		regfree(&re);
+		return;
+	}
+	DIR * d=opendir(getUsedPath().c_str());
+	if(d==NULL) {
+		std::cerr << "Could not open directory " << getUsedPath() << std::endl;
+		regfree(&re);
+		return;
+	}
+	struct dirent* res;
+	
+#ifdef HAVE_READDIR_R
+	struct dirent cur;
+	if(readdir_r(d,&cur,&res)) {
+		std::cerr << "Error reading files from " << getUsedPath() << std::endl;
+		closedir(d);
+		regfree(&re);
+		return;
+	}
+#else
+	res=readdir(d);
+#endif
+
+	std::set<std::string> dirfiles;
+	while(res!=NULL) {
+		int match=regexec(&re,res->d_name,0,NULL,0);
+		if(match==0) {
+			dirfiles.insert(res->d_name);
+		} else if(match!=REG_NOMATCH) {
+			char msg[128];
+			regerror(match,&re,msg,128);
+			std::cerr << "Regex error on '" << res->d_name << "': " << msg << std::endl;
+		} // else std::cout << "Skipping " << res->d_name << std::endl;
+#ifdef HAVE_READDIR_R
+		if(readdir_r(d,&cur,&res)) {
+			std::cerr << "Error reading files from " << getUsedPath() << std::endl;
+			closedir(d);
+			regfree(&re);
+			return;
+		}
+#else
+		res=readdir(d);
+#endif
+	}
+	closedir(d);
+	regfree(&re);
+	
+	//std::cout << "Processing " << getUsedPath() << std::endl;
+	float tinc=1000.f/framerate;
+	for(std::set<std::string>::const_iterator it=dirfiles.begin(); it!=dirfiles.end(); ++it) {
+		//std::cout << "Enqueuing " << *it << std::endl;
+		enqueueFile((getUsedPath()+"/")+(*it),tinc);
+	}
+}
+
+bool FileSystemDataSource::loadFileListFromIndex() {
+	indexed=(indexed || files.size()==0);
+	regex_t re;
+	if(int err=regcomp(&re,filenameFilter.c_str(),REG_EXTENDED | REG_NOSUB)) {
+		char msg[128];
+		regerror(err,&re,msg,128);
+		std::cerr << "Bad filter '" << filenameFilter << "': " << msg << std::endl;
+		regfree(&re);
+		return false;
+	}
+	
+	ifstream in(getUsedPath().c_str());
+	string cur;
+	getline(in,cur);
+	if(cur.find("First frame ")==0) //skip the header line from the GUI, e.g. 'First frame 42898 timestamp: 1439018'
+		getline(in,cur);
+	
+	float tinc=1000.f/framerate;
+	float lasttime=-tinc;
+	while(in) {
+		string fn = cur.substr(0,cur.find('\t'));
+		int match=regexec(&re,fn.c_str(),0,NULL,0);
+		if(match==0) {
+			float curtime=lasttime+tinc;
+			if(fn.size()!=cur.size()) {
+				const char * timep=cur.c_str()+cur.rfind('\t');
+				char * endp=NULL;
+				curtime=strtof(timep,&endp);
+				if(timep==endp) {
+					std::cerr << "ERROR: '" << getUsedPath() << "' does not seem to be a valid index file." << std::endl;
+					std::cerr << "       Use output from VisionGUI, or use format 'filename <tab> time'" << std::endl;
+					std::cerr << "       Where 'time' is the time in milliseconds at which the file should be processed, relative" << std::endl;
+					std::cerr << "       to the time at which the index file is loaded." << std::endl;
+					regfree(&re);
+					return false;
+				}
+				if(lasttime>=0) {
+					files.back()->lifetime=curtime-lasttime;
+					//std::cout << "(previous frame lifetime " << files.back()->lifetime << ") ";
+				} else if(files.size()>0) {
+					files.back()->lifetime+=curtime;
+					//std::cout << "(previous frame increased lifetime to " << files.back()->lifetime << ") ";
+				} else {
+					initialDelay=curtime;
+					nextTime=get_time()+curtime;
+					//std::cout << "nextTime set to " << nextTime << " ";
+				}
+			}
+			if(fn[0]!='/') { // if not absolute path, tack on path to index file (*do this after previous check*!)
+				string::size_type srcdir=getUsedPath().rfind('/');
+				if(srcdir!=string::npos)
+					fn=getUsedPath().substr(0,srcdir+1)+fn;
+			}
+			//std::cout << "Enqueuing " << fn << " at " << curtime << endl;
+			enqueueFile(fn,tinc);
+			lasttime=curtime;
+		} else if(match!=REG_NOMATCH) {
+			char msg[128];
+			regerror(match,&re,msg,128);
+			std::cerr << "Regex error on '" << fn << "': " << msg << std::endl;
+		} // else std::cout << "Skipping " << res->d_name << std::endl;
+		getline(in,cur);
+	}
+	regfree(&re);
+	return true;
+}
+
+char * FileSystemDataSource::loadData(const std::string& file) {
+	struct stat statbuf;
+	if(stat(file.c_str(),&statbuf)!=0) {
+		perror("LoadDataThread::loadData");
+		return NULL;
+	}
+	FILE * f=fopen(file.c_str(),"rb");
+	if(f==NULL) {
+		std::cerr << "LoadDataThread::loadData(): File open failed" << std::endl;
+		return NULL;
+	}
+	char* buf=new char[statbuf.st_size];
+	int nread=fread(buf,1,statbuf.st_size,f);;
+	fclose(f);
+	f=NULL;
+	if(nread!=statbuf.st_size) {
+		std::cerr << "LoadDataThread::,datagram(): failed to load entire file, "<<nread<<" read, "<<statbuf.st_size<<" requested" << std::endl;
+		return NULL;
+	}
+	return buf;
+}
+
+void FileSystemDataSource::FileInfo::prepare() {
+	if(prepared)
+		return;
+	if(data==NULL) {
+		struct stat statbuf;
+		if(stat(filename.c_str(),&statbuf)!=0) {
+			std::string err="FileSystemDataSource::FileInfo::prepare() failed to stat file ";
+			err+=filename;
+			perror(err.c_str());
+			return;
+		}
+		int fd=open(filename.c_str(),O_RDONLY);
+		if(fd<0) {
+			std::string err="FileSystemDataSource::FileInfo::prepare() unable to open file ";
+			err+=filename;
+			perror(err.c_str());
+			return;
+		}
+		size=statbuf.st_size;
+		data=static_cast<char*>(mmap(NULL,size,PROT_READ,MAP_PRIVATE|MAP_FILE,fd,0));
+		if(data==MAP_FAILED) {
+			data=NULL;
+			size=0;
+			std::string err="FileSystemDataSource::FileInfo::prepare() unable to mmap file ";
+			err+=filename;
+			perror(err.c_str());
+			return;
+		}
+		if(close(fd)!=0) {
+			std::string err="FileSystemDataSource::FileInfo::prepare() unable to close file ";
+			err+=filename;
+			perror(err.c_str());
+			return;
+		}
+	}
+	if(mlock(data,size)!=0) {
+		if(errno==ENOMEM) {
+			static bool firsterr=true; // give a warning just the first time if mlock fails because RLIMIT_MEMLOCK is too low
+			if(firsterr) {
+				firsterr=false;
+				rlimit rl;
+#ifndef __CYGWIN__
+				getrlimit(RLIMIT_MEMLOCK,&rl);
+				cerr << "Notice: mlock() failed because RLIMIT_MEMLOCK is too low, limited to " << (rl.rlim_cur/1024) << "KB\n"
+				     << "Increasing this limit can smooth logged data I/O in low memory situations. (see ulimit/limit commands)" << endl;
+#endif
+			}
+		} else {
+			std::string err="FileSystemDataSource::FileInfo::prepare() unable to mlock file ";
+			err+=filename;
+			perror(err.c_str());
+		}
+		return;
+	}
+	prepared=true;
+}
+
+void FileSystemDataSource::FileInfo::done() {
+	if(data==NULL || !prepared)
+		return;
+	prepared=false;
+	if(munlock(data,size)!=0) {
+		std::string err="FileSystemDataSource::FileInfo::prepare() unable to munlock file ";
+		err+=filename;
+		perror(err.c_str());
+	}
+}
+
+void FileSystemDataSource::FileInfo::release() {
+	if(data==NULL)
+		return;
+	done();
+	if(munmap(data,size)!=0) {
+		std::string err="FileSystemDataSource::FileInfo::prepare() unable to munmap file ";
+		err+=filename;
+		perror(err.c_str());
+	}
+	data=NULL;
+	size=0;
+}
+
+/*! @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:05 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSources/FileSystemDataSource.h ./local/DataSources/FileSystemDataSource.h
--- ../Tekkotsu_3.0/local/DataSources/FileSystemDataSource.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSources/FileSystemDataSource.h	2007-11-10 17:58:12.000000000 -0500
@@ -0,0 +1,155 @@
+//-*-c++-*-
+#ifndef INCLUDED_FileSystemDataSource_h_
+#define INCLUDED_FileSystemDataSource_h_
+
+#include "local/DataSource.h"
+#include "Shared/plist.h"
+#include "Shared/get_time.h"
+#include <list>
+#include <iostream>
+
+class LoggedDataDriver;
+
+//! Manages the loading of a series of files from disk
+/*! Can handle an index file listing other data files and their timestamps,
+ *  a directory holding a set of files, or a single explicit file. */
+class FileSystemDataSource : public virtual DataSource, public virtual plist::Dictionary, public virtual plist::PrimitiveListener {
+public:
+	//! constructor
+	FileSystemDataSource(LoggedDataDriver& p, const std::string& filter)
+		: DataSource(), plist::Dictionary(), PrimitiveListener(), path(), filenameFilter(filter), loop(true), files(), curfile(files.begin()),
+		initialDelay(0), nextTime(0), indexed(true), sn(0), freezeTime(), parent(p), actualLoopTime(0), naturalLoopTime(0)
+	{
+		setLoadSavePolicy(FIXED,SYNC);
+		addEntry("Path",path,"If set, overrides the common LoggedData driver path.  In addition to directory or index file, can also be set to a single input data file.");
+		addEntry("FileFilter",filenameFilter,"If Source is a directory or index file, only files matching the filter will be loaded from it.");
+		addEntry("Loop",loop,"If true, restart file list at the beginning when the end is reached; otherwise just stop loading data");
+	}
+
+	//! destructor
+	~FileSystemDataSource();
+	
+	virtual unsigned int nextTimestamp();
+	virtual const std::string& nextName();
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* th);
+	virtual void setDataSourceFramerate(float fr);
+	
+	//! sets the next frame to be sent (e.g. pass 0 to reset to the first frame)
+	/*! prepares (pre-loads) @a numPreload frames from the new #curfile onward */
+	virtual void setFrame(unsigned int f, unsigned int numPreload=2);
+	
+	//! increments #curfile to the next frame, preparing (pre-loads) @a numPreload frames from the new #curfile onward
+	virtual void nextFrame(unsigned int numPreload=2);
+	
+	//! returns the total time taken to loop over the files
+	/*! @param actual if false, will return the "natural" time of a loop, ignoring setLoopTime() effects */
+	virtual float getLoopTime(bool actual=true) const { return actual ? actualLoopTime : naturalLoopTime; }
+	virtual void setLoopTime(float t); //!< adds time to the final frame to increase total sequence time to @a t milliseconds
+	
+	virtual bool usingIndexFile() const { return indexed; } //!< returns #indexed
+	
+	//! empties #files
+	void clearFiles();
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	virtual void loadXML(xmlNode* node);
+	
+	//! returns the target path, either #path, or parent.path if #path is empty
+	virtual const std::string& getUsedPath() const;
+	
+	//! call this to (re)load the list of available file names from disk
+	/*! If @a clearCurrent is set, then the current file list will be cleared;
+	 *  otherwise, the loaded files will be appended to the current queue */
+	virtual void loadFileList(bool clearCurrent=true, bool reportMissing=true);
+	
+	//! The directory, data file, or index file from which to load via call to loadFileListFromDirectory(), loadSingleFile(), or loadFileListFromIndex()
+	/*! A single file can be either a single data file (e.g. sensor or camera image), or an index file as output by VisionGUI, or in the format 'filename \<tab\> time', where 'filename' is an absolute path or relative to the directory containing the index file, and 'time' is in milliseconds, relative to the time at which the index file is loaded.\n In the future, this could also be network addresses for teleoperation and remote processing. */
+	plist::Primitive<std::string> path;
+	
+	//! a regular expression (POSIX.2 extended format) to select which files to load from #path, if #path is a directory or index file
+	plist::Primitive<std::string> filenameFilter;
+	
+	//! controls whether to restart #curfile at the beginning of #files when it reaches the end
+	plist::Primitive<bool> loop;
+	
+protected:
+	virtual void doFreeze() { freezeTime=get_time(); }
+	virtual void doUnfreeze() { nextTime+=get_time()-freezeTime; }
+	
+	//! if thread is NULL, mark all outputs as ignored, and if thread is non-NULL, mark them all as provided
+	virtual void updateProvidingOutputs();
+	
+	//! load a single file
+	virtual void loadSingleFile(const std::string& file);
+	//! load a list of files from a directory specified by #path
+	virtual void loadFileListFromDirectory();
+	//! load a list of files from an index file specified by #path
+	/*! This supports either the format produced by VisionGUI, or a simplier '<code>filename [\<tab\> time]\\n</code>' format,
+	 *  where if @c time is unspecified, the frame's time is incremented by the #framerate from the previously listed file.
+	 *  Filenames should either be either absolute paths or relative to the directory which contains the index file.*/
+	virtual bool loadFileListFromIndex();
+	
+	//! adds up the lifetime of all #files, plus #initialDelay
+	virtual float calcLoopTime() const;
+
+	//! does the actual work of loading and processing data from disk, subclasses should override this if they want to decompress/pre-parse the data
+	/*! This implementation merely loads the data directly into memory with no processing or parsing.
+	 *  @param[in] file full path of file to load
+	 *  @return pointer to the data, or NULL if error */
+	virtual char* loadData(const std::string& file);
+	
+	//! stores basic information regarding each file in the queue, including routines for loading to and from disk
+	struct FileInfo {
+		//! default constructor
+		FileInfo() : filename(), lifetime(0), data(NULL), size(0), prepared(false) {}
+		//! basic constructor, provide name and lifetime, data and size are left empty until later prepare() is called
+		FileInfo(const std::string& name, float time) : filename(name), lifetime(time), data(NULL), size(0), prepared(false) {}
+		//! shallow copy constructor -- doesn't copy #data (have to call prepare() to reload)
+		FileInfo(const FileInfo& fi) : filename(fi.filename), lifetime(fi.lifetime), data(NULL), size(0), prepared(false) { }
+		//! shallow assignment -- doesn't copy #data (have to call prepare() to reload)
+		FileInfo& operator=(const FileInfo& fi) { release(); filename=fi.filename; lifetime=fi.lifetime; return *this; }
+		//! destructor
+		virtual ~FileInfo() { release(); }
+		
+		virtual void prepare(); //!< make sure data is in physical memory for imminent usage
+		virtual void done(); //!< we can let the data out of memory if needed
+		virtual void release(); //!< if data is in an allocated region, free it
+		
+		std::string filename; //!< the path to the file to load
+		float lifetime; //!< time for which this frame is "current", before next frame should be sent
+		char* data; //!< loaded/parsed contents of #filename, all ready to send, just need to copy into message
+		unsigned int size; //!< size of buffer pointed to by #data (may be decompressed/processed, different than file size...)
+		bool prepared; //!< true if prepare() has been called
+	};
+	
+	//! creates a new entry on #files, virtual to allow subclasses to use a FileInfo subclass with more meta data (e.g. see FileSystemImageSource::ImageInfo)
+	virtual void enqueueFile(const std::string& name, float lifetime) { files.push_back(new FileInfo(name,lifetime)); } 
+	
+	static const unsigned int MAX_LOAD=4000; //!< maximum number of data elements to try to keep 'active'.  If there's more than this in #files, we'll only load one at time, and immediately release it afterward
+	typedef std::list<FileInfo*> files_t; //!< type of #files, the list of files to load
+	files_t files; // collection of FileInfo entries
+	files_t::iterator curfile; //!< an iterator referencing #files -- indicates next file to send
+	float initialDelay; //!< milliseconds to wait before sending first frame
+	float nextTime; //!< timestamp that #curfile should be sent
+	bool indexed; //!< true if the file list was specified by an index file
+	unsigned int sn; //!< frame serial number, incremented by getData()
+	unsigned int freezeTime; //!< time at which doFreeze was called
+	LoggedDataDriver& parent; //!< device driver this is a member of
+	float actualLoopTime; //!< time it would take to run through all of the loaded frames
+	float naturalLoopTime; //!< time it would take to run through all of the frames as set immediately after load (i.e. no setLoopTime())
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.5 $
+ * $State: Exp $
+ * $Date: 2007/11/10 22:58:12 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSources/FileSystemImageSource.cc ./local/DataSources/FileSystemImageSource.cc
--- ../Tekkotsu_3.0/local/DataSources/FileSystemImageSource.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSources/FileSystemImageSource.cc	2007-06-22 14:33:52.000000000 -0400
@@ -0,0 +1,83 @@
+#include "FileSystemImageSource.h"
+#include "Shared/ImageUtil.h"
+#include "Shared/debuget.h"
+#include <sys/types.h>
+#include <sys/mman.h>
+
+//better to put this here instead of the header
+using namespace std; 
+
+void FileSystemImageSource::ImageInfo::prepare() {
+	if(prepared)
+		return;
+	if(data==NULL) {
+		// load the file from disk
+		FileInfo::prepare();
+		if(data==NULL)
+			return;
+		
+		// get the image info
+		width=height=components=0;
+		size_t totalSize=0;
+		char * imgbuf = ((char*)NULL)-1;
+		image_util::decodeImage(data,size,width,height,components,imgbuf,totalSize); // this call fails (no allocation), but sets image info
+		size_t headerSize=getHeaderSize();
+		totalSize = headerSize + width*height*components;
+		// using mmap to allocate space so we can still use mlock/munlock on it later
+		imgbuf = static_cast<char*>(mmap(NULL,totalSize,PROT_READ|PROT_WRITE,MAP_PRIVATE|MAP_ANON,-1,0));
+		if(imgbuf==MAP_FAILED) {
+			std::string err="FileSystemImageSource::ImageInfo::prepare() unable to mmap allocation for image decompression of ";
+			err+=filename;
+			perror(err.c_str());
+			FileInfo::release();
+			return;
+		}
+		if(writeHeader(imgbuf,headerSize)==0) {
+			cerr << "FileSystemImageSource::ImageInfo::prepare(): Ran out of space writing image header" << endl;
+			munmap(imgbuf,totalSize); // error, give up and clear our memory usage
+			FileInfo::release();
+			return;
+		}
+		
+		// decompress the image for real this time:
+		char * img=imgbuf+headerSize;
+		size_t imgSize=totalSize-headerSize;
+		if(!image_util::decodeImage(data,size,width,height,components,img,imgSize)) {
+			cerr << "Image decompression failed for " << filename << endl;
+			munmap(imgbuf,totalSize); // error, give up and clear our memory usage
+			FileInfo::release();
+			return; // don't fall through to the prepare() below!
+		}
+		
+		// replace the raw compressed data with the uncompressed image
+		FileInfo::release();
+		data=imgbuf;
+		size=totalSize;
+	}
+	FileInfo::prepare();
+}
+
+size_t FileSystemImageSource::ImageInfo::getHeaderSize() const {
+	return LoadSave::getSerializedSize<unsigned int>()*4;
+}
+
+size_t FileSystemImageSource::ImageInfo::writeHeader(char* buf, size_t sz) const {
+	unsigned int remain=sz;
+	if(!LoadSave::encodeInc(*dataSource.layer,buf,remain)) return 0;
+	if(!LoadSave::encodeInc(width,buf,remain)) return 0;
+	if(!LoadSave::encodeInc(height,buf,remain)) return 0;
+	if(!LoadSave::encodeInc(components,buf,remain)) return 0;
+	ASSERT(remain==0,"FileSystemImageSource::ImageInfo::writeHeader(): Leftover bytes in header? getHeaderSize() is wrong\n");
+	return sz-remain;
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/06/22 18:33:52 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DataSources/FileSystemImageSource.h ./local/DataSources/FileSystemImageSource.h
--- ../Tekkotsu_3.0/local/DataSources/FileSystemImageSource.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DataSources/FileSystemImageSource.h	2007-11-09 14:01:13.000000000 -0500
@@ -0,0 +1,66 @@
+//-*-c++-*-
+#ifndef INCLUDED_FileSystemImageSource_h_
+#define INCLUDED_FileSystemImageSource_h_
+
+#include "FileSystemDataSource.h"
+
+//! Extends FileSystemDataSource to decompress image data
+class FileSystemImageSource : public FileSystemDataSource {
+public:
+	//! constructor
+	FileSystemImageSource(LoggedDataDriver& p, const std::string& filter)
+		: FileSystemDataSource(p,filter), layer(0)
+	{
+		addEntry("Layer",layer,"Controls the resolution layer at which the image should be processed.\n0 indicates \"automatic\" mode (picks layer closest to image's resolution), positive numbers indicate the resolution layer directly.\nNegative values are relative to the number of layers marked available by the vision setup, so that typically -1 would correspond to the \"double\" layer, and -2 would correspond to the \"full\" layer.");
+	}
+
+	//! Controls the resolution layer at which the image should be processed
+	/*! 0 indicates "automatic" mode (picks layer closest to image's resolution), positive
+	 *  numbers indicate the resolution layer directly.
+	 *  
+	 *  Negative values are relative to the number of layers marked available by the
+	 *  vision setup, so that typically -1 would correspond to the "double" layer, and -2
+	 *  would correspond to the "full" layer. */
+	plist::Primitive<int> layer;
+
+protected:
+	
+	//! ignores call -- images don't provide outputs
+	virtual void updateProvidingOutputs() {}
+	
+	//! extends FileInfo to provide image decompression and some additional fields for image meta-data
+	class ImageInfo : public FileInfo {
+	public:
+		//! constructor
+		ImageInfo(const FileSystemImageSource& ds, const std::string& name, float time) : FileInfo(name,time), dataSource(ds), width(), height(), components() {}
+		
+		//! uses FileInfo's prepare to load file into memory, and then replaces with a decompressed version
+		virtual void prepare();
+		
+		//! size of the header containing image meta data
+		virtual size_t getHeaderSize() const;
+		//! encodes the file meta-data into the buffer: FileSystemImageSource::layer, #width, #height, #components; raw image data will then follow
+		virtual size_t writeHeader(char* buf, size_t size) const;
+		
+		//! reference back to the containing data source so we can access FileSystemImageSource::layer
+		const FileSystemImageSource& dataSource;
+		size_t width; //!< width of image
+		size_t height; //!< height of image
+		size_t components; //!< number of color channels
+	};
+	
+	virtual void enqueueFile(const std::string& name, float lifetime) { files.push_back(new ImageInfo(*this,name,lifetime)); } 
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/11/09 19:01:13 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDriver.h ./local/DeviceDriver.h
--- ../Tekkotsu_3.0/local/DeviceDriver.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDriver.h	2007-08-22 21:12:53.000000000 -0400
@@ -0,0 +1,88 @@
+//-*-c++-*-
+#ifndef INCLUDED_DeviceDriver_h_
+#define INCLUDED_DeviceDriver_h_
+
+#include "Shared/InstanceTracker.h"
+#include "Shared/plistCollections.h"
+#include <set>
+class MotionHook;
+class DataSource;
+
+//! description of DeviceDriver
+class DeviceDriver : public virtual plist::Dictionary {
+public:
+	//! destructor, removes from registry in case we're deleting it from some other source than registry's own destroy()
+	virtual ~DeviceDriver() { getRegistry().destroy(instanceName); }
+	
+	//! Returns the name of the class (aka its type)
+	/*! Suggested implementation is to declare a static string member, set it to the result of
+	 *  calling the registry's registerType, and then return that member here */
+	virtual std::string getClassName() const=0;
+	
+	virtual MotionHook* getMotionSink() { return NULL; }
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) { sources.clear(); }
+	virtual void getImageSources(std::map<std::string,DataSource*>& sources) { sources.clear(); }
+	
+	typedef InstanceTracker<DeviceDriver,std::string,Factory1Arg<DeviceDriver,std::string> > registry_t;
+	static registry_t& getRegistry() { static registry_t registry; return registry; }
+	
+	//! allows LoadDataThreads to be notified when a data source is added or removed
+	class SourceListener {
+	public:
+		virtual ~SourceListener() {}; //!< destructor
+		virtual void dataSourcesUpdated()=0; //!< indicates a data source has been added or removed
+	};
+	
+	//! add a listener to #sourceListeners
+	virtual void addSourceListener(SourceListener* l) { if(l!=NULL) sourceListeners.insert(l); }
+	//! remove a listener from #sourceListeners
+	virtual void removeSourceListener(SourceListener* l) { sourceListeners.erase(l); }
+	
+protected:
+	//! constructor, pass the name of the class's type so we can use it in error messages, and a name for the instance so we can register it for MotionHook's to lookup
+	DeviceDriver(const std::string& /*classname*/, const std::string& instancename)
+	: plist::Dictionary(), instanceName(instancename), sourceListeners()
+	{
+		setLoadSavePolicy(FIXED,SYNC);
+	}
+
+	//! To be called be "deepest" subclass constructor at the end of construction
+	/*! Don't want to register until completed construction!  plist::Collection listeners would be
+	 *  triggered and might start performing operations on instance while partially constructed */
+	virtual void registerInstance() {
+		if(DeviceDriver * inst=getRegistry().getInstance(instanceName)) {
+			if(inst==this)
+				return; // duplicate registration, skip it
+			std::cerr << "Warning: registration of DeviceDriver " << getClassName() << " named " << instanceName << " @ " << this
+			<< " blocked by previous " << inst->getClassName() << " instance of same name @ " << inst << std::endl;
+		}
+		if(!getRegistry().registerInstance(getClassName(),instanceName,this))
+			std::cerr << "Error: failed to register " << getClassName() << " named " << instanceName << " @ " << this;
+		//addEntry(".type",new plist::Primitive<std::string>(className),"Stores the typename of the device driver so it can be re-instantiated on load.\n** Do not edit ** ");
+	}
+	
+	//! calls SourceListener::dataSourcesUpdated() for entries registered in #sourceListeners
+	virtual void fireDataSourcesUpdated() {
+		std::set<SourceListener*> notify=sourceListeners;
+		for(std::set<SourceListener*>::const_iterator it=notify.begin(); it!=notify.end(); ++it) {
+			if(sourceListeners.find(*it)!=sourceListeners.end()) // check that it hasn't been removed during course of processing...
+				(*it)->dataSourcesUpdated();
+		}
+	}
+	
+	const std::string instanceName; //!< holds the name of this instance of CommPort (mainly for error message reporting by the class itself)
+	std::set<SourceListener*> sourceListeners; //!< list (of LoadDataThreads) to be notified when a data source is added or removed
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.7 $
+ * $State: Exp $
+ * $Date: 2007/08/23 01:12:53 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverOSX.cc ./local/DeviceDrivers/CameraDriverOSX.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverOSX.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CameraDriverOSX.cc	2007-11-12 23:16:06.000000000 -0500
@@ -0,0 +1,191 @@
+#if defined(__APPLE__) && !defined(__x86_64__)
+
+#include "CameraDriverOSX.h"
+#include "local/DataSources/CameraSourceOSX.h"
+#include "Shared/get_time.h"
+#include "Shared/debuget.h"
+
+#include <sstream>
+
+using namespace std; 
+
+const std::string CameraDriver::autoRegisterCameraDriver = DeviceDriver::getRegistry().registerType<CameraDriver>("Camera");
+
+void CameraDriver::dumpLiteral(OSType t) {
+	union {
+		OSType v;
+		char s[4];
+	} x;
+	x.v=t;
+	cout << x.s[3] << x.s[2] << x.s[1] << x.s[0];
+}
+
+void CameraDriver::updateCameraList() {
+	if(!checkQTThreadInit()) {
+		cerr << "CameraDriver: Couldn't initialize QuickTime" << endl;
+		return;
+	}
+	
+	// open the sequence grabber, assuming there's only ever one component of this type listed
+	SeqGrabComponent sg = OpenDefaultComponent(SeqGrabComponentType, 0);
+	if(sg==NULL) {
+		cerr << "CameraDriver: Couldn't open sequence grabber" << endl;
+		return;
+	}
+	
+	OSErr err;
+	SGChannel sgChan=NULL; // temporary channel just to get device list
+	SGDeviceList devList = NULL; // list of capture devices
+	try {
+		// initialize the default sequence grabber component
+		err = SGInitialize(sg);
+		if(err!=noErr) throw "SGInitialize";
+		
+		err = SGNewChannel(sg, VideoMediaType, &sgChan);
+		if(err!=noErr) throw "SGNewChannel";
+		
+		//err = SGSetChannelBounds(sgChan, &bounds);
+		//if(err!=noErr) throw "SGSetChannelBounds";
+		
+		err = SGSetChannelUsage(sgChan, seqGrabRecord | seqGrabLowLatencyCapture /* | seqGrabPreview | seqGrabAlwaysUseTimeBase */);
+		if(err!=noErr) throw "SGSetChannelUsage";
+		
+		// just for debugging info
+		/*CodecNameSpecListPtr codecs;
+		err = GetCodecNameList(&codecs,0);
+		if(err!=noErr) cerr << "Could not get codec list" << endl;
+		else {
+			cout << "Codec names: " << endl;
+			for(int i=0; i<codecs->count; ++i) {
+				cout << '\t' << codecs->list[i].codec << ' ';
+				dumpLiteral(codecs->list[i].cType);
+				cout << ' ' << p2c(codecs->list[i].typeName) << endl;
+			}
+			DisposeCodecNameList(codecs);
+		}*/
+		
+		
+		// thanks Harald ( hxr AT users sourceforge net ) for 'wacaw' source to demonstrate
+		// how to get the device list via sequence grabber...
+		err = SGGetChannelDeviceList(sgChan, sgDeviceListDontCheckAvailability | sgDeviceListIncludeInputs, &devList);
+		if(err!=noErr) throw "SGGetChannelDeviceList";
+		
+		// we got our list, close the channel so whatever default device it grabbed is available for the CameraSource
+		// (we can open SequenceGrabber component multiple times, but each channel/device only open from one place...)
+		if(sgChan!=NULL)
+			SGDisposeChannel(sg,sgChan);
+		sgChan=NULL;
+		
+		map<string,unsigned int> nameCnt;
+		SGDeviceListRecord& list = **devList;
+		
+		storage_t olddict; // need to backup old dictionary so we can delete unused entries
+		dict.swap(olddict);
+		storage_t::const_iterator it = olddict.find(".type");
+		if(it!=olddict.end())
+			dict.insert(*it);
+		myRef.clear(); // we'll rebuild these in the following loop
+		comments.clear();
+		
+		for(int i = 0; i<list.count; i++) {
+			string devName = p2c(list.entry[i].name);
+			//cout << "Device: " << devName << ' ' << (list.entry[i].flags & sgDeviceNameFlagDeviceUnavailable) << ' ' << (list.entry[i].flags & sgDeviceNameFlagShowInputsAsDevices) << endl;
+			
+			SGDeviceInputList inputList = list.entry[i].inputs;
+			if(inputList != NULL) {
+				SGDeviceInputListRecord& inputs = **inputList;
+				//if(inputs.count==0)
+					//cout << "    (no inputs)" << endl;
+				//cout << "    There are " << inputs.count << " inputs for this device." << endl;
+				//cout << "    The current selection is " << inputs.selectedIndex << endl;
+				for (int j = 0; j < inputs.count; j++) {
+					string inputName = p2c(inputs.entry[j].name);
+					//cout << "    Input: " << inputName << ' ' << (inputs.entry[j].flags & sgDeviceInputNameFlagInputUnavailable) << endl;
+					// heuristic hack -- take the last word which starts with an alphabet character as the "short" input name
+					unsigned int x;
+					for(x=inputName.size(); x>0; --x)
+						if(isspace(inputName[x-1]) && x<inputName.size() && isalpha(inputName[x]))
+							break;
+					string name;
+					while(x<inputName.size() && !isspace(inputName[x]))
+						name+=inputName[x++];
+					if(nameCnt[name]++ > 0) {
+						stringstream uniqname;
+						uniqname << name << "-" << nameCnt[name];
+						name = uniqname.str();
+					}
+					//cout << "    I shall call you '" << name << "'" << endl;
+					
+					bool found; // go through all of the current sources looking for this input
+					for(it=olddict.begin(); it!=olddict.end(); ++it) {
+						if(it->first==".type")
+							continue;
+						CameraSource& ds = dynamic_cast<CameraSource&>(*it->second);
+						// have to match the full device and input names, not the "short" name!
+						if(ds.getDeviceName()==devName && ds.getInputName()==inputName) {
+							found=true; // we already have an entry for this input -- reuse that instance instead of making a new one
+							myRef.insert(dict[name] = &ds);
+							break;
+						}
+					}
+					if(!found) { // didn't find a pre-existing CameraSource for this input
+						// make a new one, store it in the dictionary, and add it to myRef:
+						try {
+							CameraSource * cam = new CameraSource(sg, name, devName, inputName, j);
+							myRef.insert(dict[name] = cam);
+						} catch(const pair<OSErr,const char *>& msg) {
+							cerr << "CameraDriver registering: " << inputName << endl;
+							cerr << "   on device: " << devName << endl;
+							cerr << "     call to: " << msg.second << " returned error " << msg.first << " (attempting to continue...)" << endl;
+							continue;
+						}
+					}
+					comments[name]="Device Name: "+devName+"\nInput Name: "+inputName;
+				}
+			}
+			
+			// now go through entries of olddict
+			// anything that isn't in dict nor myRef should be deleted
+			// (entries may be "renamed" if bus topology changes, so might have
+			// old entries not deleted because it's in use under a new name)
+			for(it=olddict.begin(); it!=olddict.end(); ++it) {
+				if(it->first==".type")
+					continue;
+				if(dict.find(it->first)==dict.end()) {
+					if(myRef.find(it->second)==myRef.end())
+						delete it->second;
+				} else {
+					// we shouldn't have any entries which are found in dict (i.e. in use) but not myRef
+					ASSERT(myRef.find(it->second)!=myRef.end(), "Entry in use with unreferenced value...???");
+				}
+			}
+		}
+		
+	} catch(const char* call) {
+		cerr << "CameraDriver: " << call << " returned error " << err << endl;
+	} catch(const pair<OSErr,const char *>& msg) {
+		cerr << "CameraDriver: " << msg.second << " returned error " << msg.first << endl;
+	}
+	if(devList!=NULL)
+		SGDisposeDeviceList(sg, devList);
+	devList=NULL;
+	if(sgChan!=NULL)
+		SGDisposeChannel(sg,sgChan);
+	sgChan=NULL;
+	if(sg!=NULL)
+		CloseComponent(sg);
+	sg=NULL;
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.5 $
+ * $State: Exp $
+ * $Date: 2007/11/13 04:16:06 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverOSX.h ./local/DeviceDrivers/CameraDriverOSX.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverOSX.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CameraDriverOSX.h	2007-09-14 17:29:03.000000000 -0400
@@ -0,0 +1,67 @@
+//-*-c++-*-
+#ifndef INCLUDED_CameraDriver_h_
+#define INCLUDED_CameraDriver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/DataSources/CameraSourceOSX.h"
+#include "Shared/get_time.h"
+
+//! description of CameraDriver
+class CameraDriver : public virtual DeviceDriver, public virtual plist::CollectionListener {
+public:
+	//! constructor, may throw a const char* on error
+	explicit CameraDriver(const std::string& name)
+		: DeviceDriver(autoRegisterCameraDriver,name)
+	{
+		if(!checkQTThreadInit()) {
+			std::cerr << "CameraDriver: Couldn't initialize QuickTime" << std::endl;
+			return;
+		}
+		
+		updateCameraList();
+	}
+	
+	~CameraDriver() {}
+	
+	virtual std::string getClassName() const { return autoRegisterCameraDriver; }
+	
+	virtual void getImageSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		for(const_iterator it=begin(); it!=end(); ++it) {
+			if(it->first==".type")
+				continue;
+			if(CameraSource * ds = dynamic_cast<CameraSource*>(it->second))
+				sources[it->first]=ds;
+			else
+				std::cerr << "WARNING CameraDriver entry " << it->first << " is not actually a CameraSource!!!" << std::endl;
+		}
+	}
+	
+protected:
+	//! converts from pascal-format string to c-format string
+	static std::string p2c(unsigned char pascalStr[]) {
+		unsigned char len = *pascalStr++;
+		return std::string(reinterpret_cast<char*>(pascalStr),len);
+	}
+	
+	static void dumpLiteral(OSType t);
+	
+	void updateCameraList();
+	
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterCameraDriver;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/09/14 21:29:03 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverV4L.cc ./local/DeviceDrivers/CameraDriverV4L.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverV4L.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CameraDriverV4L.cc	2007-08-31 02:16:07.000000000 -0400
@@ -0,0 +1,386 @@
+#ifdef __linux__
+
+#include "CameraDriverV4L.h"
+#include "Shared/debuget.h"
+//#include "Shared/TimeET.h"
+#include "Shared/MarkScope.h"
+
+#include <fcntl.h>
+#include <sys/ioctl.h>
+
+using namespace std; 
+
+const std::string CameraDriver::autoRegisterCameraDriver = DeviceDriver::getRegistry().registerType<CameraDriver>("Camera");
+const size_t CameraDriver::HEADER_SIZE = LoadSave::getSerializedSize<unsigned int>()*4;
+
+unsigned int CameraDriver::getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name) {
+	//cout << '.' << flush;
+	payload=NULL;
+	payloadSize=0;
+	if(camfd<0)
+		return frameCount;
+
+	curBuf.resize(getBufferSize());
+	
+	// reset non-blocking in case thread was canceled while we were
+	// were in a blocking call...
+	if(blocking) {
+		if( fcntl(camfd,F_SETFL,O_NONBLOCK) != 0) {
+			perror("ioctl set non-blocking mode");
+			blocking = fcntl(camfd,F_GETFL) & O_NONBLOCK;
+		} else
+			blocking=false;
+	}
+
+	unsigned int t=get_time();
+	unsigned int dropped=0;
+	int nbytes;
+	size_t lastread;
+	while(timestamp>t) {
+		//clear any backlog
+		while( (nbytes=read(camfd, &curBuf[HEADER_SIZE], curBuf.size()-HEADER_SIZE)) >= 0) {
+			lastread=nbytes;
+			++dropped;
+			//cout << "clear " << TimeET() << endl;
+		}
+		usleep(static_cast<unsigned int>((timestamp-t)*1000/(getTimeScale()>0?getTimeScale():1.f)));
+		t=get_time();
+	}
+	timestamp = t;
+	// we might've been asleep for a while, so need to double check a few things...
+	if(camfd<0) // in case we shutdown while asleep!
+		return frameCount;
+
+	unsigned int width, height, components=3;
+	{
+		MarkScope l(lock);
+		width=getWidth();
+		height=getHeight();
+		if(curBuf.size()!=getBufferSize()) { // check in case user changed resolution
+			curBuf.resize(getBufferSize());
+			dropped=0;
+		}
+	}
+
+	//get most recent image
+	while( (nbytes=read(camfd, &curBuf[HEADER_SIZE], curBuf.size()-HEADER_SIZE)) >= 0) {
+		lastread=nbytes;
+		++dropped;
+		//cout << "early " << TimeET() << endl;
+	}
+	timestamp = get_time();
+
+	char * buf=reinterpret_cast<char*>(&curBuf[0]);
+	unsigned int remain=curBuf.size();
+	LoadSave::encodeIncT(*layer,buf,remain);
+	LoadSave::encodeIncT(width,buf,remain);
+	LoadSave::encodeIncT(height,buf,remain);
+	LoadSave::encodeIncT(components,buf,remain);
+
+	if(remain<img_size) {
+		// user has changed resolution... skip frame
+		//cerr << "Not enough space in buffer for image! " << remain << " vs " << img_size << endl;
+		return frameCount;
+	}
+	if(dropped==0 || lastread!=img_size) {
+		ASSERTRETVAL(static_cast<size_t>(remain)>=img_size, "Read more than remains in buffer!", frameCount);
+		// disable non-blocking io, we want to wait for the next frame
+		if( fcntl(camfd,F_SETFL,0) != 0) {
+			perror("ioctl set blocking mode");
+			blocking = fcntl(camfd,F_GETFL) & O_NONBLOCK;
+		} else
+			blocking=true;
+		//TimeET bt;
+		//cout << "block " << bt << ' ';
+		nbytes = read(camfd, buf, remain);
+		timestamp = get_time();
+		//cout << bt.Age() << endl;
+		if( fcntl(camfd,F_SETFL,O_NONBLOCK) != 0) {
+			perror("ioctl set non-blocking mode");
+			blocking = fcntl(camfd,F_GETFL) & O_NONBLOCK;
+		} else
+			blocking=false;
+		if ( nbytes<0 ) {
+			perror("Error reading from camera");
+			return frameCount;
+		}
+		lastread=nbytes;
+		++dropped;
+	}
+	
+	MarkScope l(lock);
+	// check if we had a short read or if the desired image size changed while we were blocked
+  if ( lastread!=img_size // short read
+	     || (resolution!=0 && img_size!=width*height*6) // size changed (downsample)
+	     || (resolution==0 && img_size!=width*height*3/2) // size changed (upsample)
+	   )
+	{
+		// short read is relatively normal -- always get this on the first frame for
+		// some reason, and also might have just changed resolution setting and hasn't
+		// taken effect yet.
+    //cerr << "CameraDriver got " << nbytes << " bytes from camera, expected " << img_size << endl;
+		return frameCount;
+	}
+
+	if(resolution==0)
+		interleave_yuv_up();
+	else
+		interleave_yuv_down();
+  
+	if ( autobright )
+    auto_bright();
+	
+	curBuf.swap(lastBuf);
+	payload = reinterpret_cast<char*>(&lastBuf[0]);
+	payloadSize = lastBuf.size();
+	name = nextName();
+	return frameCount+=dropped;
+}
+
+
+void CameraDriver::setDataSourceThread(LoadDataThread* th) {
+	DataSource::setDataSourceThread(th);
+	if(th != NULL) {
+		open_cam();
+		path.addPrimitiveListener(this);
+		resolution.addPrimitiveListener(this);
+	} else {
+		resolution.removePrimitiveListener(this);
+		path.removePrimitiveListener(this);
+		close_cam();
+	}
+}
+
+void CameraDriver::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl == &path) {
+		MarkScope l(lock);
+		open_cam();
+	} else if(&pl == &resolution) {
+		MarkScope l(lock);
+		set_resolution();
+	}
+}
+
+void CameraDriver::close_cam() {
+	if(camfd >= 0) {
+		::close(camfd);
+		camfd=-1;
+	}
+}
+
+void CameraDriver::open_cam() {
+	close_cam();
+	if(path.size() == 0)
+		return;
+	
+  camfd = ::open(path.c_str(), O_RDWR|O_NONBLOCK, 0);
+  if ( camfd < 0 ) {
+    perror("Error on open()");
+		cerr << "Could not open camera device '" << path << "'" << endl;
+		return;
+  }
+	blocking=false;
+  
+	set_resolution();
+
+  if ( ioctl(camfd, VIDIOCGPICT, &vid_pic) == -1 )
+    perror ("ioctl (VIDIOCGPICT) brightness");
+	vid_pic.brightness=128*256; // initialize to middle brightness
+  if ( ioctl(camfd, VIDIOCSPICT, &vid_pic) == -1 )
+    perror ("ioctl (VIDIOCSPICT) brightness");
+
+	// try to switch to YUV mode so we don't have to do color conversion
+	// this is only trying for 4-2-0 planar mode...
+	isYUVMode=false;
+  ioctl(camfd, VIDIOCGPICT, &vid_pic);
+  vid_pic.depth=16;
+  vid_pic.palette=VIDEO_PALETTE_YUV420P;
+  if ( ioctl(camfd, VIDIOCSPICT, &vid_pic) == -1 )
+    perror ("ioctl (VIDIOCSPICT) palette");
+  else {
+    img_size = vid_win.width * vid_win.height + vid_win.width*vid_win.height/2;
+		isYUVMode=true;
+  }
+  
+  /*{
+    struct v4l2_control ctrl;
+    ctrl.id=V4L2_CID_AUTO_WHITE_BALANCE;    ctrl.value=0;    if ( ioctl(camera->fd,VIDIOC_S_CTRL,&ctrl) == -1 )
+      perror ("ioctl (VIDIOC_S_CTRL) disable auto white balance");
+  } */ 
+}
+
+void CameraDriver::get_cam_info() {
+  ioctl(camfd, VIDIOCGCAP, &vid_caps);
+  ioctl(camfd, VIDIOCGWIN, &vid_win);
+  ioctl(camfd, VIDIOCGPICT, &vid_pic);
+}
+
+void CameraDriver::set_cam_info() {
+  if ( ioctl(camfd, VIDIOCSPICT, &vid_pic) == -1 ) {
+    perror ("ioctl (VIDIOCSPICT)");
+		cout << "refreshing settings..." << endl;
+		if ( ioctl(camfd, VIDIOCGPICT, &vid_pic) == -1 )
+			perror ("ioctl (VIDIOCGPICT)");
+	}
+  if ( ioctl(camfd, VIDIOCSWIN, &vid_win) == -1 ) {
+    perror ("ioctl (VIDIOCSWIN)");
+		cout << "refreshing settings..." << endl;
+		if ( ioctl(camfd, VIDIOCGWIN, &vid_win) == -1 )
+			perror ("ioctl (VIDIOCGWIN)");
+	}
+}
+
+void CameraDriver::set_resolution() {
+  get_cam_info();
+  int width = vid_caps.maxwidth >> (resolution==0 ? 0 : resolution-1);
+  int height = vid_caps.maxheight >> (resolution==0 ? 0 : resolution-1);
+  if ( width < vid_caps.minwidth || height < vid_caps.minheight ) {
+		cout << "Warning: requested image " << width<<'x'<<height<<" smaller than camera's minimum size, trying ";
+    width = vid_caps.minwidth;
+    height = vid_caps.minheight;
+		cout << width<<'x'<<height << endl;
+  }
+
+  vid_win.width = width;
+  vid_win.height = height;
+  set_cam_info();
+  width = vid_win.width; // restore in case of error or adjustment of requested values
+  height = vid_win.height; // (camera might only support certain explicit resolutions)
+	
+	if(isYUVMode) {
+    img_size = width * height + width * height / 2;
+	} else {
+		img_size = width * height * 3;
+	}
+		
+	cout << "Camera image size is " << getWidth() << 'x' << getHeight() << endl;
+}
+
+/*! this is run @em after interleaving, so we go through every 3rd byte of the
+ *  entire image to sum the y channel */
+void CameraDriver::auto_bright() {
+  size_t total = 0;
+	unsigned char *pix = &curBuf[HEADER_SIZE];
+	const size_t skip = getWidth() * getHeight() / 719; // actually, only take a subsample
+	const size_t npix = getWidth() * getHeight() / skip; // we want a regular sample stride, so will actually be a bit less
+	const unsigned char *endp = pix + npix*skip*3;
+  for (; pix!=endp; pix+=skip*3) // *3 because of interleaving
+    total += *pix;
+  int average = total / npix;
+  if((average <= 120 || average >= 136)) {
+		int bright = vid_pic.brightness + (128 - average)*256/4;
+		const typeof(vid_pic.brightness) maxBright = numeric_limits<typeof(vid_pic.brightness)>::max();
+		const typeof(vid_pic.brightness) minBright = numeric_limits<typeof(vid_pic.brightness)>::min();
+		if(bright>maxBright)
+			vid_pic.brightness = maxBright;
+		else if(bright<minBright)
+			vid_pic.brightness = minBright;
+		else
+			vid_pic.brightness = bright;
+		//cout << "Autobrightness " << average << " " << vid_pic.brightness << endl;
+    set_cam_info();
+  }
+}
+
+void CameraDriver::interleave_yuv_down() {
+	unsigned char * buffer = &curBuf[HEADER_SIZE];
+	int width = vid_win.width;
+	int height = vid_win.height;
+	
+  //first downsample y channel
+  char tmp[width/2];
+  int x,y=0;
+  for(x=0; x<width; x+=2) {
+    short t=buffer[x+y*width];
+    t+=buffer[x+y*width+1];
+    t+=buffer[x+y*width+width];
+    t+=buffer[x+y*width+width+1];
+    tmp[x/2] = t/4;
+  }
+  for(x=0; x<width/2; x++) {
+    buffer[x*3] = tmp[x];
+  }  
+  for(y=2; y<height; y+=2) {
+    for(x=0; x<width; x+=2) {
+      short t=buffer[x+y*width];
+      t+=buffer[x+y*width+1];
+      t+=buffer[x+y*width+width];
+      t+=buffer[x+y*width+width+1];
+      buffer[y*width/4*3+x/2*3] = t/4;
+    }
+  }
+  // now fill in color components
+  unsigned char * c = &buffer[width*height];
+	buffer = &curBuf[HEADER_SIZE]+1;
+	unsigned char * endp = buffer + width*height/4*3;
+	while(buffer!=endp) { // u/Cr channel
+		*buffer = *c++;
+		buffer+=3;
+	}
+	buffer = &curBuf[HEADER_SIZE]+2;
+	endp = buffer + width*height/4*3;
+	while(buffer!=endp) { // v/Cb channel
+		*buffer = *c++;
+		buffer+=3;
+	}
+}
+
+void CameraDriver::interleave_yuv_up() {
+	unsigned char * buffer = &curBuf[HEADER_SIZE];
+	size_t width = vid_win.width;
+	size_t height = vid_win.height;
+	tmpBuf.resize(getBufferSize());
+	memcpy(&tmpBuf[0],&curBuf[0],HEADER_SIZE);
+	unsigned char * out = &tmpBuf[HEADER_SIZE];
+
+  //first copy over y channel
+  unsigned char * i = buffer;
+  unsigned char * o = out;
+	unsigned char * e = i + width*height;
+	while(i!=e) {
+		*o=*i++;
+		o+=3;
+	}
+  
+	//now u channel
+	o = out+1;
+	buffer+=width*height;
+	for(size_t y=0; y<height/2; ++y) {
+		i = buffer+width/2*y;
+		e = i + width/2;
+		while(i!=e) {
+			*o=*(o+3)=*(o+width*3)=*(o+width*3+3)=*i++;
+			o+=6;
+		}
+		o+=width*3;
+	}
+  
+	//and now v channel
+	o = out+2;
+	buffer+=width*height/4;
+	for(size_t y=0; y<height/2; ++y) {
+		i = buffer+width/2*y;
+		e = i + width/2;
+		while(i!=e) {
+			*o=*(o+3)=*(o+width*3)=*(o+width*3+3)=*i++;
+			o+=6;
+		}
+		o+=width*3;
+	}
+  
+	curBuf.swap(tmpBuf);
+}
+ 
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/08/31 06:16:07 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverV4L.h ./local/DeviceDrivers/CameraDriverV4L.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/CameraDriverV4L.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CameraDriverV4L.h	2007-11-09 14:56:07.000000000 -0500
@@ -0,0 +1,114 @@
+//-*-c++-*-
+#ifndef INCLUDED_CameraDriver_h_
+#define INCLUDED_CameraDriver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/DataSource.h"
+#include "Shared/get_time.h"
+#include "IPC/Thread.h"
+
+#include <linux/types.h> 
+#include <linux/videodev.h>
+
+#include <map>
+#include <vector>
+
+//! description of CameraDriver
+class CameraDriver : public virtual DeviceDriver, public virtual plist::PrimitiveListener, public DataSource {
+public:
+	explicit CameraDriver(const std::string& name)
+		: DeviceDriver(autoRegisterCameraDriver,name), DataSource(),
+			path("/dev/video0"), resolution(1), layer(0), autobright(true),
+			camfd(-1), img_size(0), vid_caps(), vid_win(), vid_pic(), frameCount(0), isYUVMode(false), blocking(false),
+			curBuf(), lastBuf(), tmpBuf(), lock()
+	{
+		addEntry("Path",path,"Path to the video device, e.g. /dev/video0");
+		addEntry("Downsample",resolution,"The downsampling level, each increment cuts the image in half (0 is full-size)");
+		addEntry("Layer",layer,"Controls the resolution layer at which the image should be processed.\n"
+		          "0 indicates \"automatic\" mode (picks layer closest to image's resolution), positive numbers indicate the resolution layer directly.\n"
+		          "Negative values are relative to the number of layers marked available by the vision setup, so that typically -1 would correspond to the \"double\" layer, and -2 would correspond to the \"full\" layer.");
+		addEntry("Autobright",autobright,"If true, will automatically adjust camera gain");
+	}
+	
+	~CameraDriver() {
+		resolution.removePrimitiveListener(this);
+		path.removePrimitiveListener(this);
+	}
+	
+	virtual std::string getClassName() const { return autoRegisterCameraDriver; }
+	
+	virtual void getImageSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear(); sources.insert(std::make_pair("Camera",this));
+	}
+
+	virtual unsigned int nextTimestamp() { return get_time(); }
+	virtual const std::string& nextName() { return instanceName; }
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* th);
+
+	//! watches #path, triggers a close() and re-open() if it changes
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+
+	plist::Primitive<std::string> path;
+	plist::Primitive<unsigned int> resolution;
+	plist::Primitive<int> layer; //!< Controls the resolution layer at which the image should be processed.\n 0 indicates "automatic" mode (picks layer closest to image's resolution), positive numbers indicate the resolution layer directly.\n Negative values are relative to the number of layers marked available by the vision setup, so that typically -1 would correspond to the "double" layer, and -2 would correspond to the "full" layer.
+	plist::Primitive<bool> autobright;
+
+protected:
+	void close_cam();
+	void open_cam();
+	void get_cam_info();
+	void set_cam_info();
+	void set_resolution();
+	void auto_bright();
+	void interleave_yuv_down();
+	void interleave_yuv_up();
+
+	size_t getWidth() const { return (resolution==0 ? vid_win.width : vid_win.width/2); }
+	size_t getHeight() const { return (resolution==0 ? vid_win.height : vid_win.height/2); }
+	size_t getBufferSize() const { size_t a=vid_win.width*vid_win.height; return HEADER_SIZE+(resolution==0 ? a*3 : a*3/2); }
+
+	static const size_t HEADER_SIZE;
+
+	int camfd;
+  size_t img_size;
+  struct video_capability vid_caps;
+  struct video_window vid_win;
+  struct video_picture vid_pic;
+  unsigned int frameCount;
+	bool isYUVMode;
+	bool blocking;
+
+	std::vector<unsigned char> curBuf; //!< the buffer to write the image into
+	std::vector<unsigned char> lastBuf; //!< the buffer we returned last time (might still be in use while writing #curBuf)
+	std::vector<unsigned char> tmpBuf; //!< used during interleave_yuv_up(), swapped back and forth with #curBuf
+	ThreadNS::Lock lock; // buffer/img_size lock so we can't change resolution while reading
+
+	/*class GrabThread : public Thread {
+	public:
+		GrabThread(std::vector<unsigned char>& buf, int cameraFD) : Thread(), curBuf(buf), camfd(cameraFD), lock() {}
+		ThreadNS::Lock& getLock() { return lock; }
+		void setImageSize(size_t imageSize) { image_size = imageSize; }
+	protected:
+		std::vector<unsigned char>& curBuf;
+		int camfd;
+		ThreadNS::Lock lock;
+		};*/
+
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterCameraDriver;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.4 $
+ * $State: Exp $
+ * $Date: 2007/11/09 19:56:07 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CreateCommands.h ./local/DeviceDrivers/CreateCommands.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/CreateCommands.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CreateCommands.h	2007-11-18 14:16:10.000000000 -0500
@@ -0,0 +1,82 @@
+//-*-c++-*-
+#ifndef INCLUDED_CreateCommands_h_
+#define INCLUDED_CreateCommands_h_
+
+// Create Commands
+const char CREATE_START               = 128;
+const char CREATE_BAUD                = 129;
+const char CREATE_SAFE_OLD            = 130;
+const char CREATE_SAFE                = 131;
+const char CREATE_FULL                = 132;
+const char CREATE_COVER               = 135;
+const char CREATE_DEMO                = 136;
+const char CREATE_SPOT                = 134;
+const char CREATE_DRIVE               = 137;
+const char CREATE_LSD                 = 138;
+const char CREATE_LEDS                = 139;
+const char CREATE_SONG                = 140;
+const char CREATE_PLAY_SONG           = 141;
+const char CREATE_SENSORS             = 142;
+const char CREATE_COVER_AND_DOCK      = 143;
+const char CREATE_PWM_LSD             = 144;
+const char CREATE_DRIVE_DIRECT        = 145;
+const char CREATE_DIGITAL_OUT         = 147;
+const char CREATE_STREAM              = 148;
+const char CREATE_QUERY_LIST          = 149;
+const char CREATE_PAUSE_RESUME_STREAM = 150;
+const char CREATE_SCRIPT              = 152;
+const char CREATE_SEND_IR             = 151;
+const char CREATE_PLAY_SCRIPT         = 153;
+const char CREATE_SHOW_SCRIPT         = 154;
+const char CREATE_WAIT_TIME           = 155;
+const char CREATE_WAIT_DISTANCE       = 156;
+const char CREATE_WAIT_ANGLE          = 157;
+const char CREATE_WAIT_EVENT          = 158;
+
+// Create sensor packet code
+const char CREATE_SENSOR_GROUP_0            = 0;
+const char CREATE_SENSOR_GROUP_1            = 1;
+const char CREATE_SENSOR_GROUP_2            = 2;
+const char CREATE_SENSOR_GROUP_3            = 3;
+const char CREATE_SENSOR_GROUP_4            = 4;
+const char CREATE_SENSOR_GROUP_5            = 5;
+const char CREATE_SENSOR_GROUP_6            = 6;
+
+const char CREATE_SENSOR_DROP               = 7;
+const char CREATE_SENSOR_WALL               = 8;
+const char CREATE_SENSOR_CLIFF_LEFT         = 9;
+const char CREATE_SENSOR_CLIFF_FRONT_LEFT   = 10;
+const char CREATE_SENSOR_CLIFF_FRONT_RIGHT  = 11;
+const char CREATE_SENSOR_CLIFF_RIGHT        = 12;
+const char CREATE_SENSOR_VIRTUAL_WALL       = 13;
+const char CREATE_SENSOR_OVERCURRENT        = 14;
+const char CREATE_SENSOR_UNUSED_1           = 15;
+const char CREATE_SENSOR_UNUSED_2           = 16;
+const char CREATE_SENSOR_IR                 = 17;
+const char CREATE_SENSOR_BUTTONS            = 18;
+const char CREATE_SENSOR_DISTANCE           = 19;
+const char CREATE_SENSOR_ANGLE              = 20;
+const char CREATE_SENSOR_CHANGING_STATE     = 21;
+const char CREATE_SENSOR_VOLTAGE            = 22;
+const char CREATE_SENSOR_CURRENT            = 23;
+const char CREATE_SENSOR_BATTERY_TEMP       = 24;
+const char CREATE_SENSOR_BATTERY_CHARGE     = 25;
+const char CREATE_SENSOR_BATTERY_CAPACITY   = 26;
+const char CREATE_SENSOR_WALL_SIGNAL        = 27;
+const char CREATE_SENSOR_CLIFF_L_SIGNAL     = 28;
+const char CREATE_SENSOR_CLIFF_FL_SIGNAL    = 29;
+const char CREATE_SENSOR_CLIFF_FR_SIGNAL    = 30;
+const char CREATE_SENSOR_CLIFF_R_SIGNAL     = 31;
+const char CREATE_SENSOR_DIGITAL_IN         = 32;
+const char CREATE_SENSOR_ANALOG             = 33;
+const char CREATE_SENSOR_CAN_CHARGE         = 34;
+const char CREATE_SENSOR_OI_MODE            = 35;
+const char CREATE_SENSOR_SONG_NUMBER        = 36;
+const char CREATE_SENSOR_SONG_PLAYING       = 37;
+const char CREATE_SENSOR_STREAM_SIZE        = 38;
+const char CREATE_SENSOR_REQ_VELOCITY       = 39;
+const char CREATE_SENSOR_REQ_RADIUS         = 40;
+const char CREATE_SENSOR_REQ_RIGHT_VELOCITY = 41;
+const char CREATE_SENSOR_REQ_LEFT_VELOCITY  = 42;
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CreateDriver.cc ./local/DeviceDrivers/CreateDriver.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/CreateDriver.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CreateDriver.cc	2007-11-18 14:16:10.000000000 -0500
@@ -0,0 +1,546 @@
+#include <arpa/inet.h>
+#include <stdio.h>
+#include "CreateCommands.h"
+#include "CreateDriver.h"
+#include "Shared/RobotInfo.h"
+#include "Shared/MarkScope.h"
+#include "Shared/get_time.h"
+#include "Shared/debuget.h"
+
+using namespace std; 
+
+const std::string CreateDriver::autoRegisterCreateDriver = DeviceDriver::getRegistry().registerType<CreateDriver>("Create");
+
+void CreateDriver::motionStarting() {
+	std::cout << "motionStarting called!" << std::endl;
+	MotionHook::motionStarting();
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm!=NULL){
+		comm->open();
+
+		std::cout << "Motion Starting Connect" << std::endl;
+		// connect :D
+		connect();
+	}
+	motionActive=true;
+	commName.addPrimitiveListener(this);
+}
+
+void CreateDriver::motionStopping() {
+	motionActive=false;
+	if(!sensorsActive) // listener count is not recursive, so only remove if we're the last one
+		commName.removePrimitiveListener(this);
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm!=NULL)
+		comm->close(); // this *is* recursive, so we always close it to match our open() in motionStarting()
+	MotionHook::motionStopping();
+}
+
+void CreateDriver::motionCheck(const float outputs[][NumOutputs]) {
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isWriteable())
+		return;
+
+	stringstream ss;
+
+	unsigned short output;
+
+	ss << CREATE_DRIVE_DIRECT;
+
+	//output = htons((short)outputs[NumFrames-1][1]);
+	output = (unsigned short)(outputs[NumFrames-1][1] * 10);
+	//output = -100;
+	ss << (char)(output >> 8);
+	ss << (char)(output & 0xFF);
+
+	//output = htons((short)outputs[NumFrames-1][0]);
+	output = (unsigned short)(outputs[NumFrames-1][0] * 10);
+	//output = -100;
+	ss << (char)(output >> 8);
+	ss << (char)(output & 0xFF);
+
+	//std::cout << "MOTION CHECK DATA: " << (short) outputs[NumFrames-1][1] << " " << (short)outputs[NumFrames-1][0] << std::endl;
+
+	string s=ss.str();
+	if(s.size()>0) { // if sparse and no changes, skip update altogether
+		ThreadNS::Lock& l = comm->getLock();
+		unsigned int t=get_time();
+		// keep trying to get the lock, sleeping 1 ms each time, until 3/4 the frame time is gone (then give up)
+		unsigned int dt = static_cast<unsigned int>(NumFrames*FrameTime/((getTimeScale()>0)?getTimeScale():1.f));
+		unsigned int giveup = t+dt*3/4;
+		t+=dt;
+		while(!l.trylock()) {
+			if(get_time()>=giveup) {
+				/*
+				if(MotionHook::verbose>0)
+					cerr << "Dropping motion update: couldn't get lock on comm port" << endl;
+				*/
+				return;
+			}
+			usleep(1000);
+		}
+		MarkScope autolock(l); l.unlock(); //transfer lock to MarkScope
+		std::ostream os(&comm->getWriteStreambuf());
+		dt=t-get_time();
+		os << s << flush;
+	}
+	
+	MotionHook::motionCheck(outputs); // updates lastOutputs and isFirstCheck, we ignore its motionUpdated() call
+}
+
+// htonl (long)
+// htons (short)
+void CreateDriver::connect(){
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	ThreadNS::Lock& l = comm->getLock();
+	unsigned int t=get_time();
+	unsigned int giveup = t+3000000;
+	while(!l.trylock()) {
+		if(get_time()>=giveup) {
+			if(MotionHook::verbose>0)
+				cerr << "Unable to connect: couldn't get lock on comm port" << endl;
+			return;
+		}
+		usleep(1000);
+	}
+	MarkScope autolock(l); l.unlock(); //transfer lock to MarkScope
+
+	std::cout << "SENDING START/SAFE COMMANDS" << std::endl;
+	std::ostream os(&comm->getWriteStreambuf());
+	os << CREATE_START << std::flush; // send the start command
+	os << CREATE_SAFE  << std::flush; // send the safe mode
+
+	// start stream for _everything_
+	os << CREATE_STREAM << (char)1 << CREATE_SENSOR_GROUP_6 << std::flush;
+}
+
+unsigned int CreateDriver::nextTimestamp() {
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isReadable())
+		return -1U;
+	return get_time();
+}
+
+unsigned char CreateDriver::readChar(std::istream &is){
+	return (unsigned char) is.get();
+}
+
+short CreateDriver::readShort(std::istream &is){
+	return ((short) is.get() << 8) | ((short) is.get());
+}
+
+int CreateDriver::readPacket(std::istream &is, const char &type){
+	int total = 0;
+	switch(type){
+	case CREATE_SENSOR_GROUP_0:
+		total += readPacket(is, CREATE_SENSOR_DROP);
+		total += readPacket(is, CREATE_SENSOR_WALL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_LEFT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FRONT_LEFT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FRONT_RIGHT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_RIGHT);
+		total += readPacket(is, CREATE_SENSOR_VIRTUAL_WALL);
+		total += readPacket(is, CREATE_SENSOR_OVERCURRENT);
+		total += readPacket(is, CREATE_SENSOR_UNUSED_1);
+		total += readPacket(is, CREATE_SENSOR_UNUSED_2);
+		total += readPacket(is, CREATE_SENSOR_IR);
+		total += readPacket(is, CREATE_SENSOR_BUTTONS);
+		total += readPacket(is, CREATE_SENSOR_DISTANCE);
+		total += readPacket(is, CREATE_SENSOR_ANGLE);
+		total += readPacket(is, CREATE_SENSOR_CHANGING_STATE);
+		total += readPacket(is, CREATE_SENSOR_VOLTAGE);
+		total += readPacket(is, CREATE_SENSOR_CURRENT);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_TEMP);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_CHARGE);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_CAPACITY);
+		break; 
+	case CREATE_SENSOR_GROUP_1:
+		total += readPacket(is, CREATE_SENSOR_DROP);
+		total += readPacket(is, CREATE_SENSOR_WALL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_LEFT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FRONT_LEFT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FRONT_RIGHT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_RIGHT);
+		total += readPacket(is, CREATE_SENSOR_VIRTUAL_WALL);
+		total += readPacket(is, CREATE_SENSOR_OVERCURRENT);
+		total += readPacket(is, CREATE_SENSOR_UNUSED_1);
+		total += readPacket(is, CREATE_SENSOR_UNUSED_2);
+		break;
+	case CREATE_SENSOR_GROUP_2:
+		total += readPacket(is, CREATE_SENSOR_IR);
+		total += readPacket(is, CREATE_SENSOR_BUTTONS);
+		total += readPacket(is, CREATE_SENSOR_DISTANCE);
+		total += readPacket(is, CREATE_SENSOR_ANGLE);
+		break;
+	case CREATE_SENSOR_GROUP_3:
+		total += readPacket(is, CREATE_SENSOR_CHANGING_STATE);
+		total += readPacket(is, CREATE_SENSOR_VOLTAGE);
+		total += readPacket(is, CREATE_SENSOR_CURRENT);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_TEMP);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_CHARGE);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_CAPACITY);
+		break;
+	case CREATE_SENSOR_GROUP_4:
+		total += readPacket(is, CREATE_SENSOR_WALL_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_L_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FL_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FR_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_R_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_DIGITAL_IN);
+		total += readPacket(is, CREATE_SENSOR_ANALOG);
+		total += readPacket(is, CREATE_SENSOR_CAN_CHARGE);
+		break;
+	case CREATE_SENSOR_GROUP_5:
+		total += readPacket(is, CREATE_SENSOR_OI_MODE);
+		total += readPacket(is, CREATE_SENSOR_SONG_NUMBER);
+		total += readPacket(is, CREATE_SENSOR_SONG_PLAYING);
+		total += readPacket(is, CREATE_SENSOR_STREAM_SIZE);
+		total += readPacket(is, CREATE_SENSOR_REQ_VELOCITY);
+		total += readPacket(is, CREATE_SENSOR_REQ_RADIUS);
+		total += readPacket(is, CREATE_SENSOR_REQ_RIGHT_VELOCITY);
+		total += readPacket(is, CREATE_SENSOR_REQ_LEFT_VELOCITY);
+		break;
+	case CREATE_SENSOR_GROUP_6:
+		total += readPacket(is, CREATE_SENSOR_DROP);
+		total += readPacket(is, CREATE_SENSOR_WALL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_LEFT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FRONT_LEFT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FRONT_RIGHT);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_RIGHT);
+		total += readPacket(is, CREATE_SENSOR_VIRTUAL_WALL);
+		total += readPacket(is, CREATE_SENSOR_OVERCURRENT);
+		total += readPacket(is, CREATE_SENSOR_UNUSED_1);
+		total += readPacket(is, CREATE_SENSOR_UNUSED_2);
+		total += readPacket(is, CREATE_SENSOR_IR);
+		total += readPacket(is, CREATE_SENSOR_BUTTONS);
+		total += readPacket(is, CREATE_SENSOR_DISTANCE);
+		total += readPacket(is, CREATE_SENSOR_ANGLE);
+		total += readPacket(is, CREATE_SENSOR_CHANGING_STATE);
+		total += readPacket(is, CREATE_SENSOR_VOLTAGE);
+		total += readPacket(is, CREATE_SENSOR_CURRENT);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_TEMP);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_CHARGE);
+		total += readPacket(is, CREATE_SENSOR_BATTERY_CAPACITY);
+		total += readPacket(is, CREATE_SENSOR_WALL_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_L_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FL_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_FR_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_CLIFF_R_SIGNAL);
+		total += readPacket(is, CREATE_SENSOR_DIGITAL_IN);
+		total += readPacket(is, CREATE_SENSOR_ANALOG);
+		total += readPacket(is, CREATE_SENSOR_CAN_CHARGE);
+		total += readPacket(is, CREATE_SENSOR_OI_MODE);
+		total += readPacket(is, CREATE_SENSOR_SONG_NUMBER);
+		total += readPacket(is, CREATE_SENSOR_SONG_PLAYING);
+		total += readPacket(is, CREATE_SENSOR_STREAM_SIZE);
+		total += readPacket(is, CREATE_SENSOR_REQ_VELOCITY);
+		total += readPacket(is, CREATE_SENSOR_REQ_RADIUS);
+		total += readPacket(is, CREATE_SENSOR_REQ_RIGHT_VELOCITY);
+		total += readPacket(is, CREATE_SENSOR_REQ_LEFT_VELOCITY);
+		break;
+	case CREATE_SENSOR_STREAM_SIZE:
+		total = 1;
+		readChar(is);
+		break;
+	case CREATE_SENSOR_DROP:
+		total = 1;
+		createStatus.bumpsWheelDrops = readChar(is);
+		break;
+	case CREATE_SENSOR_WALL:
+		total = 1;
+		createStatus.wall = readChar(is);
+		break;
+	case CREATE_SENSOR_CLIFF_LEFT:
+		total = 1;
+		createStatus.cliffLeft = readChar(is);
+		break;
+	case CREATE_SENSOR_CLIFF_FRONT_LEFT:
+		total = 1;
+	  createStatus.cliffFrontLeft = readChar(is);
+		break;
+	case CREATE_SENSOR_CLIFF_FRONT_RIGHT:
+		total = 1;
+		createStatus.cliffFrontRight = readChar(is);
+		break;
+	case CREATE_SENSOR_CLIFF_RIGHT:
+		total = 1;
+		createStatus.cliffRight = readChar(is);
+		break;
+	case CREATE_SENSOR_VIRTUAL_WALL:
+		total = 1;
+		createStatus.virtualWall = readChar(is);
+		break;
+	case CREATE_SENSOR_OVERCURRENT:
+		total = 1;
+		createStatus.overcurrents = readChar(is);
+		break;
+	case CREATE_SENSOR_IR:
+		total = 1;
+		createStatus.ir = readChar(is);
+		break;
+	case CREATE_SENSOR_BUTTONS:
+		total = 1;
+		createStatus.buttons = readChar(is);
+		break;
+	case CREATE_SENSOR_DISTANCE:
+		total = 2;
+		createStatus.distance = readShort(is);
+		break;
+	case CREATE_SENSOR_ANGLE:
+		total = 2;
+		createStatus.angle = readShort(is);
+		break;
+	case CREATE_SENSOR_CHANGING_STATE:
+		total = 1;
+		createStatus.chargingState = readChar(is);
+		break;
+	case CREATE_SENSOR_VOLTAGE:
+		total = 2;
+		createStatus.voltage = readShort(is);
+		break;
+	case CREATE_SENSOR_CURRENT:
+		total = 2;
+		createStatus.current = readShort(is);
+		break;
+	case CREATE_SENSOR_BATTERY_TEMP:
+		total = 1;
+		createStatus.batteryTemperature = readChar(is);
+		break;
+	case CREATE_SENSOR_BATTERY_CHARGE:
+		total = 2;
+		createStatus.batteryCharge = readShort(is);
+		break;
+	case CREATE_SENSOR_BATTERY_CAPACITY:
+		total = 2;
+		createStatus.batteryCapacity = readShort(is);
+		break;
+	case CREATE_SENSOR_WALL_SIGNAL:
+		total = 2;
+		createStatus.wallSignal = readShort(is);
+		break;
+	case CREATE_SENSOR_CLIFF_L_SIGNAL:
+		total = 2;
+		createStatus.cliffLeftSignal = readShort(is);
+		break;
+	case CREATE_SENSOR_CLIFF_FL_SIGNAL:
+		total = 2;
+		createStatus.cliffFrontLeftSignal = readShort(is);
+		break;
+	case CREATE_SENSOR_CLIFF_FR_SIGNAL:
+		total = 2;
+		createStatus.cliffFrontRightSignal = readShort(is);
+		break;
+	case CREATE_SENSOR_CLIFF_R_SIGNAL:
+		total = 2;
+		createStatus.cliffRightSignal = readShort(is);
+		break;
+	case CREATE_SENSOR_DIGITAL_IN:
+		total = 1;
+	  createStatus.userDigitalInputs= readChar(is);
+		break;
+	case CREATE_SENSOR_ANALOG:
+		total = 2;
+		createStatus.userAnalogInput = readShort(is);
+		break;
+	case CREATE_SENSOR_CAN_CHARGE:
+		total = 1;
+		createStatus.chargingSourcesAvailable = readChar(is);
+		break;
+	case CREATE_SENSOR_OI_MODE:
+		total = 1;
+		createStatus.oiMode = readChar(is);
+		break;
+	case CREATE_SENSOR_SONG_NUMBER:
+		total = 1;
+		createStatus.songNumber = readChar(is);
+		break;
+	case CREATE_SENSOR_SONG_PLAYING:
+		total = 1;
+		createStatus.songPlay = readChar(is);
+		break;
+	case CREATE_SENSOR_REQ_VELOCITY:
+		total = 2;
+	  createStatus.velocity = readShort(is);
+		break;
+	case CREATE_SENSOR_REQ_RADIUS:
+		total = 2;
+		createStatus.radius = readShort(is);
+		break;
+	case CREATE_SENSOR_REQ_RIGHT_VELOCITY:
+		total = 2;
+	  createStatus.rightVelocity = readShort(is);
+		break;
+	case CREATE_SENSOR_REQ_LEFT_VELOCITY:
+		total = 2;
+		createStatus.leftVelocity = readShort(is);
+		break;
+	case CREATE_SENSOR_UNUSED_1:
+	case CREATE_SENSOR_UNUSED_2:
+		total = 1;
+		readChar(is);
+		break;
+	default:
+		std::cerr << "CREATE DRIVER: unknown packet type " << (int) type << std::endl;
+		break;
+	}
+
+	return total;
+}
+
+unsigned int CreateDriver::getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name) {
+	std::cout << "getData call!" << std::endl;
+	payload=NULL; payloadSize=0; // in case of error
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isReadable() || !comm->isWriteable())
+		return frameNumber;
+	unsigned int t=get_time();
+	if(timestamp>t)
+		usleep(static_cast<unsigned int>((timestamp-t)*1000/(getTimeScale()>0?getTimeScale():1.f)));
+	if(thread==NULL) // in case we shut down while waiting
+		return frameNumber;
+	stringstream ss;
+	timestamp=get_time();
+	ss << "#POS\n";
+	ss << "condensed " << RobotInfo::RobotName << "\n";
+	ss << "meta-info = ";
+	ss << t;
+	ss << " ";
+	ss << t;
+	ss << "\n";
+	std::cout << "begin read" << std::endl;
+	{
+		MarkScope autolock(comm->getLock());
+		std::ostream os(&comm->getWriteStreambuf());
+		std::istream is(&comm->getReadStreambuf());
+		
+		os << CREATE_STREAM << (char)1 << CREATE_SENSOR_GROUP_6 << std::flush;
+		
+		// Begin packet reading...
+		unsigned char in=0;
+		unsigned char type=0;
+		unsigned char numPackets = 0;
+		int i;
+
+
+		while(1){
+			type = readChar(is);
+			if(type == 19){
+				numPackets = readChar(is);
+				printf("reading %d packets\n", numPackets);
+				for(i = 0; i < numPackets; i+=in){
+					type = readChar(is);
+					printf("reading type %d\n", type);
+					in = readPacket(is, type) + 1;
+					printf("read %d packets\n", in);
+				}
+				if(i != numPackets){
+					std::cerr << "CREATE DRIVER: read in more than expected! Read " << i << " Expected " << (int)numPackets << std::endl;
+				}
+				printf("CREATE DRIVER: checksum %d\n", readChar(is));
+				break;
+			}
+			else{
+				std::cerr << "CREATE DRIVER: did not get packet with data '19' as expected! Got: " << (unsigned short) type << std::endl;
+			}
+		}
+
+	}
+	ss << "outputs =" << createStatus.leftVelocity << " " << createStatus.rightVelocity << " 0 0" << "\n";
+	ss << "sensors =";
+	ss << (createStatus.userDigitalInputs & 0x1) << " ";
+	ss << ((createStatus.userDigitalInputs >> 1) & 0x1) << " ";
+	ss << ((createStatus.userDigitalInputs >> 2) & 0x1) << " ";
+	ss << ((createStatus.userDigitalInputs >> 3) & 0x1) << " ";
+	ss << createStatus.userAnalogInput << " ";
+	ss << createStatus.wallSignal << " ";
+	ss << createStatus.ir << " ";
+	ss << createStatus.cliffLeftSignal << " ";
+	ss << createStatus.cliffFrontLeftSignal << " ";
+	ss << createStatus.cliffFrontRightSignal << " ";
+	ss << createStatus.cliffRightSignal << " ";
+	ss << createStatus.distance << " ";
+	ss << createStatus.angle << " ";
+	ss << "0 0 0 0 0\n";
+	ss << "#END\n";
+	lastSensor=ss.str();
+	//cerr << lastSensor << endl;
+	payload=lastSensor.c_str();
+	payloadSize=lastSensor.size();
+	name=nextName();
+	std::cout << "finish getData!" << std::endl;
+	return frameNumber++;
+}
+
+void CreateDriver::setDataSourceThread(LoadDataThread* th) {
+	std::cout << "setDataSounceThread called!!" << std::endl;
+	if(thread==NULL && th!=NULL) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL){
+			comm->open();
+			
+			std::cout << "set data sounce thread" << std::endl;
+			// connect :D
+			connect();
+		}
+		sensorsActive=true;
+		commName.addPrimitiveListener(this);
+	}
+	if(thread!=NULL && th==NULL) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL)
+			comm->close();
+		sensorsActive=false;
+		if(!motionActive) // listener count is not recursive, so only remove if we're the last one
+			commName.removePrimitiveListener(this);
+
+	}
+	DataSource::setDataSourceThread(th);
+}
+
+void CreateDriver::plistValueChanged(const plist::PrimitiveBase& pl) {
+	std::cout << "plistvalueChanged Called!" << std::endl;
+	if(&pl==&commName) {
+		// if here, then motionStarted or setDataSourceThread has been called, thus when commName changes,
+		// need to close old one and reopen new one
+		CommPort * comm = CommPort::getRegistry().getInstance(commName.getPreviousValue());
+		if(comm!=NULL) {
+			// close each of our old references
+			if(sensorsActive)
+				comm->close();
+			if(motionActive)
+				comm->close();
+		}
+		comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL) {
+			// open each of our new references
+			if(sensorsActive)
+				comm->open();
+			if(motionActive)
+				comm->open();
+
+			// connect :D
+			connect();
+		}
+	}
+}
+
+float CreateDriver::getAnalog(unsigned int /*inputIdx*/, unsigned char s) {
+	return s*5.f/256;
+}
+
+float CreateDriver::getDigital(unsigned int /*inputIdx*/, unsigned char cur, unsigned char latch) {
+	if(cur=='0')
+		return 0;
+	return (latch=='0') ? 0.5f : 1;
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: bensont $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.7 $
+ * $State: Exp $
+ * $Date: 2007/11/18 19:16:10 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/CreateDriver.h ./local/DeviceDrivers/CreateDriver.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/CreateDriver.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/CreateDriver.h	2007-11-18 14:16:10.000000000 -0500
@@ -0,0 +1,172 @@
+//-*-c++-*-
+#ifndef INCLUDED_CreateDriver_h_
+#define INCLUDED_CreateDriver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/MotionHook.h"
+#include "local/DataSource.h"
+#include "local/CommPort.h"
+#include "Shared/plist.h"
+#include <iostream>
+
+/*
+Specs
+Big Endian <---!!!!!
+
+
+Motors: 5
+0 - LD1          - 0.5A
+1 - LD0          - 0.5A
+2 - LD2          - 1.6A
+3 - Right Wheel  - 1.0A
+4 - Left Wheel   - 1.0A
+
+Digital Inputs: 4
+
+Digital Outputs: 3
+
+LEDs: 2 (Play + Advanced)
+
+Buttons: 2 (Play + Advanced)
+
+Sensors: 5
+0 - bump right
+1 - bump left
+2 - wheeldrop right
+3 - wheeldrop left
+4 - wheeldrop caster
+
+Wall Sensor
+
+Cliff Left
+
+Cliff Right
+
+Cliff Front Left
+
+Cliff Front Right
+
+Distance (per wheel) -- capped if not polled frequent enough
+
+Angle (per wheel) -- capped if not polled frequent enough
+
+Voltage
+
+Current
+
+Battery Temperature
+
+Battery Charge
+
+Battery Capacity (not accurate for alkaline)
+*/
+
+typedef struct CreateStatus_t{
+	unsigned char bumpsWheelDrops;
+	unsigned char wall;
+	unsigned char cliffLeft;
+	unsigned char cliffFrontLeft;
+	unsigned char cliffFrontRight;
+	unsigned char cliffRight;
+  unsigned char virtualWall;
+	unsigned char overcurrents;
+	unsigned char ir;
+	unsigned char buttons;
+	short distance;
+	short angle;
+	unsigned char chargingState;
+	short voltage;
+	short current;
+	unsigned char batteryTemperature;
+	short batteryCharge;
+	short batteryCapacity;
+	short wallSignal;
+	short cliffLeftSignal;
+	short cliffFrontLeftSignal;
+	short cliffFrontRightSignal;
+	short cliffRightSignal;
+	unsigned char userDigitalInputs;
+	short userAnalogInput;
+	unsigned char chargingSourcesAvailable;
+	unsigned char oiMode;
+	unsigned char songNumber;
+	unsigned char songPlay;
+	short velocity;
+	short radius;
+	short rightVelocity;
+	short leftVelocity;
+} CreateStatus;
+
+//! description of CreateDriver
+class CreateDriver : public virtual DeviceDriver, public MotionHook, public DataSource, public virtual plist::PrimitiveListener {
+public:
+	explicit CreateDriver(const std::string& name)
+		: DeviceDriver(autoRegisterCreateDriver,name), MotionHook(), DataSource(),
+			commName(), motionActive(false), sensorsActive(false), lastSensor(), frameNumber(0), createStatus()
+	{
+		addEntry("CommPort",commName,"The name of the comm port where output will be sent");
+	}
+	virtual ~CreateDriver() {}
+	
+	virtual std::string getClassName() const { return autoRegisterCreateDriver; }
+	
+	virtual MotionHook* getMotionSink() { return dynamic_cast<MotionHook*>(this); }
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		sources["Sensors"]=dynamic_cast<DataSource*>(this);
+	}
+	
+	virtual void motionStarting();
+	virtual void motionStopping();
+	virtual void motionCheck(const float outputs[][NumOutputs]);
+
+	virtual unsigned int nextTimestamp();
+	virtual const std::string& nextName() { return instanceName; }
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* th);
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	plist::Primitive<std::string> commName;
+	
+protected:
+	virtual void connect();
+
+	virtual unsigned char readChar(std::istream &is);
+	virtual short readShort(std::istream &is);
+	virtual int readPacket(std::istream &is, const char &type);
+	
+	//! forwards call to DataSource::providingOutput() if the index is valid
+	void provideOutput(unsigned int idx) { if(idx<NumOutputs) providingOutput(idx); }
+	//! forwards call to DataSource::ignoringOutput() if the index is valid
+	void ignoreOutput(unsigned int idx) { if(idx<NumOutputs) ignoringOutput(idx); }
+	
+	//! converts the value @a s from specified input's signal to voltage
+	virtual float getAnalog(unsigned int inputIdx, unsigned char s);
+	//! converts the value @a cur and @a latch to the output format (0 if low, 0.5 if high but has been low, 1 if consistent high)
+	virtual float getDigital(unsigned int inputIdx, unsigned char cur, unsigned char latch);
+	
+	bool motionActive;
+	bool sensorsActive;
+	std::string lastSensor;
+	unsigned int frameNumber;
+	
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterCreateDriver;
+
+	CreateStatus createStatus;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: bensont $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.3 $
+ * $State: Exp $
+ * $Date: 2007/11/18 19:16:10 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/Dynamixel.cc ./local/DeviceDrivers/Dynamixel.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/Dynamixel.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/Dynamixel.cc	2007-11-04 19:20:11.000000000 -0500
@@ -0,0 +1,233 @@
+#include "Dynamixel.h"
+#include "Shared/get_time.h"
+#include "Shared/MarkScope.h"
+#include "Shared/debuget.h"
+
+using namespace std; 
+
+const char * DynamixelDriver::protocolNames[] = { "BINARY", "CM-5", "" };
+INSTANTIATE_NAMEDENUMERATION_STATICS(DynamixelDriver::protocol_t);
+
+const std::string DynamixelDriver::autoRegisterDynamixelDriver = DeviceDriver::getRegistry().registerType<DynamixelDriver>("Dynamixel");
+
+static char nchecksum(const char* p, size_t len, size_t off=0) {
+	const char* end=p+len;
+	p+=off;
+	char c=0;
+	while(p!=end) {
+		//debuget::charhexout(*p); cout << ' '; debuget::charhexout(c+*p); cout << endl;
+		c+=*p++;
+	}
+	return c;
+}
+
+struct GenericCmdHeader {
+	GenericCmdHeader(unsigned char bytelen, unsigned char instruction)
+	: markerA(0xFF), markerB(0xFF), servoid(0xFE), cmdlen(bytelen),  cmdid(instruction) {}
+	operator const char*() const { return reinterpret_cast<const char*>(&markerA); }
+	unsigned char markerA;
+	unsigned char markerB;
+	unsigned char servoid;
+	unsigned char cmdlen;
+	unsigned char cmdid;
+};
+static char nchecksum(const struct GenericCmdHeader& p, size_t len) { return nchecksum(p,len,2); }
+
+template<class T>
+struct SyncWriteHeader : public GenericCmdHeader {
+	SyncWriteHeader(unsigned char len)
+	: GenericCmdHeader(sizeof(T)*len+4,0x83), addr(T::ADDRESS), writelen(sizeof(T)-1) {}
+	unsigned char addr;
+	unsigned char writelen;
+};
+struct WriteHeader : public GenericCmdHeader {
+	WriteHeader(unsigned char address, unsigned char len)
+	: GenericCmdHeader(len+3,0x3), addr(address) {}
+	unsigned char addr;
+};
+struct SyncWritePosSpeedEntry {
+	SyncWritePosSpeedEntry() : servoid(), posl(), posh(), speedl(), speedh() {}
+	SyncWritePosSpeedEntry(unsigned char sid, unsigned short pos, unsigned short speed)
+	: servoid(sid), posl(pos), posh(pos>>8), speedl(speed), speedh(speed>>8) {}
+	static const unsigned char ADDRESS=0x1E;
+	operator const char*() const { return reinterpret_cast<const char*>(&servoid); }
+	unsigned char servoid;
+	unsigned char posl;
+	unsigned char posh;
+	unsigned char speedl;
+	unsigned char speedh;
+};
+struct BroadcastTorqueCmd : public WriteHeader {
+	BroadcastTorqueCmd(bool enable)
+	: WriteHeader(0x18,1), torqueEnable(enable?1:0), checksum(0) { updateChecksum(); }
+	void updateChecksum() { checksum=~nchecksum(*this,sizeof(*this)-1); }
+	unsigned char torqueEnable;
+	char checksum;
+};
+
+void DynamixelDriver::motionStarting() {
+	MotionHook::motionStarting();
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm!=NULL) {
+		if(comm->open()) {
+			if(!comm->isWriteable()) {
+				std::cerr << "Dynamixel unable to send initialization" << std::endl;
+			} else {
+				MarkScope autolock(*comm);
+				std::ostream os(&comm->getWriteStreambuf());
+				//printf("\nHEADER: ");
+				//debuget::hexout(BroadcastTorqueCmd(true),sizeof(BroadcastTorqueCmd));
+				os.write(BroadcastTorqueCmd(true),sizeof(BroadcastTorqueCmd)).flush();
+			}
+		}
+	}
+	motionActive=true;
+	commName.addPrimitiveListener(this);
+}
+
+void DynamixelDriver::motionStopping() {
+	motionActive=false;
+	if(!sensorsActive) // listener count is not recursive, so only remove if we're the last one
+		commName.removePrimitiveListener(this);
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm!=NULL)
+		comm->close(); // this *is* recursive, so we always close it to match our open() in motionStarting()
+	MotionHook::motionStopping();
+}
+
+void DynamixelDriver::motionCheck(const float outputs[][NumOutputs]) {
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isWriteable())
+		std::cerr << "Bad comm!" << std::endl;
+	if(comm==NULL || !comm->isWriteable())
+		return;
+	
+	SyncWritePosSpeedEntry packets[servos.size()];
+	unsigned int packetsUsed=0;
+	for(servo_iterator it=servos.begin(); it!=servos.end(); ++it) {
+		int idx=it->second->output;
+		if(idx<0 || static_cast<unsigned int>(idx)>=NumOutputs) {
+			if(idx!=ServoInfo::UNUSED)
+				std::cerr << "Warning: Dynamixel driver mapping servo " << it->first << " to invalid output index " << idx << std::endl;
+			continue; // invalid/unused servo
+		}
+		if(isFirstCheck || lastOutputs[idx]!=outputs[NumFrames-1][idx])
+			setServo(packets[packetsUsed++], it, outputs[NumFrames-1][idx]);
+	}
+	if(packetsUsed>0) { // if no changes, skip update altogether
+		ThreadNS::Lock& l = comm->getLock();
+		unsigned int t=get_time();
+		// keep trying to get the lock, sleeping 1 ms each time, until 3/4 the frame time is gone (then give up)
+		unsigned int dt = static_cast<unsigned int>(NumFrames*FrameTime/((getTimeScale()>0)?getTimeScale():1.f));
+		unsigned int giveup = t+dt*3/4;
+		while(!l.trylock()) {
+			if(get_time()>=giveup) {
+				if(MotionHook::verbose>0)
+					cerr << "Dropping dynamixel motion update: couldn't get lock on comm port" << endl;
+				return;
+			}
+			usleep(1000);
+		}
+		MarkScope autolock(l); l.unlock(); //transfer lock to MarkScope
+		std::ostream os(&comm->getWriteStreambuf());
+		SyncWriteHeader<SyncWritePosSpeedEntry> header(packetsUsed);
+		char checksum=nchecksum(header,sizeof(header));
+		checksum+=nchecksum(packets[0],packetsUsed*sizeof(SyncWritePosSpeedEntry));
+		checksum=~checksum;
+		os.write(header,sizeof(header));
+		os.write(packets[0],packetsUsed*sizeof(SyncWritePosSpeedEntry));
+		os.put(checksum);
+		os.flush();
+		printf("\nHEADER: ");
+		debuget::hexout(reinterpret_cast<char*>(&header),sizeof(header));
+		printf("\nBODY: ");
+		debuget::hexout(packets[0],packetsUsed*sizeof(SyncWritePosSpeedEntry));
+		printf("\nCHECKSUM: ");
+		debuget::hexout(&checksum,1);
+		printf("\n");
+	}
+	
+	MotionHook::motionCheck(outputs); // updates lastOutputs and isFirstCheck, we ignore its motionUpdated() call
+}
+
+void DynamixelDriver::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&commName) {
+		// if here, then motionStarted or setDataSourceThread has been called, thus when commName changes,
+		// need to close old one and reopen new one
+		CommPort * comm = CommPort::getRegistry().getInstance(commName.getPreviousValue());
+		if(comm!=NULL) {
+			// close each of our old references
+			if(sensorsActive)
+				comm->close();
+			if(motionActive)
+				comm->close();
+		}
+		comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL) {
+			// open each of our new references
+			if(sensorsActive)
+				comm->open();
+			if(motionActive)
+				comm->open();
+		}
+	} else if(&pl==&queryServos) {
+		// if here, LoadDataThread has been assigned, need to update providing/ignoring outputs
+		// (and maintain listeners for individual servos while providing)
+		if(queryServos) {
+			for(servo_iterator it=servos.begin(); it!=servos.end(); ++it) {
+				provideOutput(it->second->output);
+				it->second->output.addPrimitiveListener(this);
+			}
+		} else {
+			for(servo_iterator it=servos.begin(); it!=servos.end(); ++it) {
+				it->second->output.removePrimitiveListener(this);
+				ignoreOutput(it->second->output);
+			}
+		}
+	} else {
+		// check if it's one of the individual servos... if it is, means we're providing servo feedback,
+		// need to call providingOutput/ignoringOutput as appropriate
+		for(servo_iterator it=servos.begin(); it!=servos.end(); ++it) {
+			if(&pl==&it->second->output) {
+				ignoreOutput(it->second->output.getPreviousValue());
+				provideOutput(it->second->output);
+				return; // found it, DON'T fall through to error message below...
+			}
+		}
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+void DynamixelDriver::setServo(SyncWritePosSpeedEntry& packet, const servo_iterator& servo, float v) {
+	unsigned int servoIdx = atoi(servo->first.c_str());
+	if(servoIdx>255)
+		return;
+	unsigned int outputIdx = servo->second->output;
+	// get output's range in radians
+	float outRange = outputRanges[outputIdx][MaxRange]-outputRanges[outputIdx][MinRange];
+	// get servo's range in pulse width (ms)
+	unsigned int servoRange = 1023;
+	// get commanded position as percent of range of motion
+	float cmd = (v-outputRanges[outputIdx][MinRange])/outRange;
+	// do conversion from radians (output domain) to pulse width (servo domain)
+	float pw = cmd*servoRange;
+	// round to int
+	int bpw = static_cast<int>(pw+0.5);
+	// check bounds
+	if(bpw<0)
+		bpw=0;
+	if(bpw>1023)
+		bpw=1023;
+	packet = SyncWritePosSpeedEntry(servoIdx,bpw,0);
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/11/05 00:20:11 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/Dynamixel.h ./local/DeviceDrivers/Dynamixel.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/Dynamixel.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/Dynamixel.h	2007-11-01 16:27:04.000000000 -0400
@@ -0,0 +1,118 @@
+//-*-c++-*-
+#ifndef INCLUDED_Dynamixel_h_
+#define INCLUDED_Dynamixel_h_
+
+#include "local/DeviceDriver.h"
+#include "local/MotionHook.h"
+#include "local/DataSource.h"
+#include "local/CommPort.h"
+#include "Shared/plist.h"
+#include <iostream>
+#include <sstream>
+
+//! description of Dynamixel
+class DynamixelDriver : public virtual DeviceDriver, public MotionHook, /*public DataSource,*/ public virtual plist::PrimitiveListener {
+public:
+	explicit DynamixelDriver(const std::string& name)
+		: DeviceDriver(autoRegisterDynamixelDriver,name), /*MotionHook(), DataSource(),*/
+		protocol(CM5,protocolNames), servos(), commName(), queryServos(false), 
+		motionActive(false), sensorsActive(false), lastSensor(), frameNumber(0)
+	{
+		addEntry("Protocol",protocol,"Indicates whether to send CM-5 controller commands or direct binary commands\n"
+				 "(latter can only be used if you have a direct connection to the Dynamixel TTL bus)\n"+protocol.getDescription());
+		addEntry("Servos",servos,"Maps servo IDs to Tekkotsu output offsets, use command line new/delete commands to add/remove mappings.");
+		addEntry("CommPort",commName,"The name of the comm port where output will be sent");
+		addEntry("QueryServos",queryServos,"If set to true, will attempt to query the servo positions with each sensor update.\nThis may decrease the sampling frequency");
+		for(unsigned int i=0; i<NumPIDJoints; ++i) {
+			std::stringstream bio_id; bio_id<<i+1; // bioloid sets start the id count at 1
+			servos[bio_id.str()]=ServoInfo(i);
+		}
+	}
+	virtual ~DynamixelDriver() {}
+	
+	virtual std::string getClassName() const { return autoRegisterDynamixelDriver; }
+	
+	virtual MotionHook* getMotionSink() { return dynamic_cast<MotionHook*>(this); }
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		sources["Sensors"]=dynamic_cast<DataSource*>(this);
+	}
+	
+	virtual void motionStarting();
+	virtual void motionStopping();
+	virtual void motionCheck(const float outputs[][NumOutputs]);
+	
+	/*virtual unsigned int nextTimestamp();
+	virtual const std::string& nextName() { return instanceName; }
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* th);*/
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	static const char * protocolNames[];
+	enum protocol_t {
+		BINARY,
+		CM5
+	};
+	plist::NamedEnumeration<protocol_t> protocol;
+	
+	class ServoInfo : public virtual plist::Dictionary {
+	public:
+		static const int UNUSED=-1;
+		ServoInfo(int i=UNUSED)
+			: plist::Dictionary(false), output(i<(int)NumPIDJoints?i:UNUSED), led(i<(int)NumLEDs?i:UNUSED), freeSpin(false)
+		{
+			setLoadSavePolicy(FIXED,SYNC);
+			addEntry("Output",output,"Tekkotsu offset to pull servo positions from, relative to PIDJointOffset");
+			addEntry("LED",led,"Tekkotsu offset to pull LED values from, relative to LEDOffset");
+			addEntry("FreeSpin",freeSpin,"If true, servo will spin freely, interpreting output value as rotation speed");
+		}
+		plist::Primitive<int> output;
+		plist::Primitive<int> led;
+		plist::Primitive<bool> freeSpin;
+	};
+	
+	plist::DictionaryOf< ServoInfo > servos;
+	typedef plist::DictionaryOf< ServoInfo >::const_iterator servo_iterator;
+	
+	plist::Primitive<std::string> commName;
+	plist::Primitive<bool> queryServos;
+	
+protected:
+	//! forwards call to DataSource::providingOutput() if the index is valid
+		void provideOutput(unsigned int idx) {}//{ if(idx<NumOutputs) providingOutput(idx); }
+	//! forwards call to DataSource::ignoringOutput() if the index is valid
+		void ignoreOutput(unsigned int idx) {}//{ if(idx<NumOutputs) ignoringOutput(idx); }
+	
+	//! converts the value @a v from radians into the specified servo's pulse width range
+	virtual void setServo(struct SyncWritePosSpeedEntry& packet, const servo_iterator& servo, float v);
+	/*
+	//! converts the value @a pw from specified servo's pulse width range into radians
+	virtual float getServo(unsigned int servoIdx, unsigned int pw);
+	//! converts the value @a s from specified input's signal to voltage
+	virtual float getAnalog(unsigned int inputIdx, unsigned char s);
+	//! converts the value @a cur and @a latch to the output format (0 if low, 0.5 if high but has been low, 1 if consistent high)
+	virtual float getDigital(unsigned int inputIdx, unsigned char cur, unsigned char latch);
+	*/
+	bool motionActive;
+	bool sensorsActive;
+	std::string lastSensor;
+	unsigned int frameNumber;
+	
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterDynamixelDriver;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/11/01 20:27:04 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/ImageStreamDriver.cc ./local/DeviceDrivers/ImageStreamDriver.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/ImageStreamDriver.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/ImageStreamDriver.cc	2007-11-04 19:20:11.000000000 -0500
@@ -0,0 +1,411 @@
+#include "ImageStreamDriver.h"
+#include "Shared/get_time.h"
+#include "Shared/MarkScope.h"
+#include "Shared/RobotInfo.h"
+#include "Shared/Config.h"
+#include "Shared/ImageUtil.h"
+#include "Shared/debuget.h"
+
+using namespace std; 
+
+const char * ImageStreamDriver::formatNames[NUM_FORMATS+1] = { "yuv", "png", "jpeg", "tekkotsu", "" };
+//declare explicit instances of the NamedEnumerations we're using
+//(cuts down on some pretty significant binary size / debugging symbol bloat)
+INSTANTIATE_NAMEDENUMERATION_STATICS(ImageStreamDriver::format_t);
+
+const std::string ImageStreamDriver::autoRegisterImageStreamDriver = DeviceDriver::getRegistry().registerType<ImageStreamDriver>("ImageStream");
+
+unsigned int ImageStreamDriver::nextTimestamp() {
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isReadable())
+		return -1U;
+	return get_time();
+}
+
+unsigned int ImageStreamDriver::getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name) {
+	payload=NULL; payloadSize=0; // in case of error
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isReadable())
+		return frameNumber;
+	/*unsigned int t=get_time();
+	if(timestamp>t)
+		usleep(static_cast<unsigned int>((timestamp-t)*1000/(getTimeScale()>0?getTimeScale():1.f)));
+	if(thread==NULL) // in case we shut down while waiting
+		return frameNumber;*/
+
+	unsigned int layer=0;
+	unsigned int width=CameraResolutionX;
+	unsigned int height=CameraResolutionY;
+	unsigned int components=3;
+	{
+		MarkScope autolock(*comm);
+		//std::ostream os(&comm->getWriteStreambuf());
+		std::istream is(&comm->getReadStreambuf());
+		switch(*format) {
+			case FORMAT_YUV: {
+				unsigned int remain = LoadSave::getSerializedSize<unsigned int>()*4+width*height*components;
+				buffer.resize(remain);
+				char * buf=&buffer.front();
+				if(!LoadSave::encodeInc(layer,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(width,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(height,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(components,buf,remain)) return frameNumber;
+				is.read(buf,remain);
+				++frameNumber;
+			} break;
+				
+			case FORMAT_PNG: {
+				size_t w,h,c;
+				bool isFirst=(img==NULL);
+				if(!image_util::decodePNG(is,w,h,c,img,imgSize)) {
+					cerr << "ImageStreamDriver PNG decompression failed" << endl;
+					return frameNumber;
+				}
+				width=w;
+				height=h;
+				components=c;
+				
+				ASSERT(imgSize==width*height*components,"image size doesn't match expected size");
+				unsigned int remain = LoadSave::getSerializedSize<unsigned int>()*4+width*height*components;
+				buffer.resize(remain);
+				char * buf=&buffer.front();
+				if(!LoadSave::encodeInc(layer,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(width,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(height,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(components,buf,remain)) return frameNumber;
+				if(isFirst) {
+					memcpy(buf,img,imgSize);
+					delete [] img;
+					img=buf;
+				}
+				
+				++frameNumber;
+			} break;
+				
+			case FORMAT_JPEG: {
+				size_t w,h,c;
+				bool isFirst=(img==NULL);
+				if(!image_util::decodeJPEG(is,w,h,c,img,imgSize)) {
+					cerr << "ImageStreamDriver JPEG decompression failed" << endl;
+					return frameNumber;
+				}
+				width=w;
+				height=h;
+				components=c;
+				
+				ASSERT(imgSize==width*height*components,"image size doesn't match expected size");
+				unsigned int remain = LoadSave::getSerializedSize<unsigned int>()*4+width*height*components;
+				buffer.resize(remain);
+				char * buf=&buffer.front();
+				if(!LoadSave::encodeInc(layer,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(width,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(height,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(components,buf,remain)) return frameNumber;
+				if(isFirst) {
+					memcpy(buf,img,imgSize);
+					delete [] img;
+					img=buf;
+				}
+				
+				++frameNumber;
+			} break;
+				
+			case FORMAT_TEKKOTSU: {
+				// ugh, LoadSave handles FILE* and char*, but not iostreams...
+				// gonna be a little ugly :(
+				
+				// RAW CAM BEHAVIOR HEADER
+				char tmp[256];
+				unsigned int len;
+				string fmt;
+				is.read(tmp,LoadSave::getSerializedSize(len));
+				LoadSave::decode(len,tmp,LoadSave::getSerializedSize(len));
+				if(len!=13) {
+					cerr << "Expecting Tekkotsu image format, but image header doesn't match! (len==" << len << ")" << endl;
+					return frameNumber;
+				}
+				is.read(tmp,len+1);
+				if(strncmp(tmp,"TekkotsuImage",len+1)!=0) {
+					tmp[len+2]='\0';
+					cerr << "Expecting Tekkotsu image format, but image header doesn't match! (" << tmp << ")" << endl;
+					return frameNumber;
+				}
+				
+				int encoding; //Config::vision_config::RawCamConfig::encoding_t
+				is.read(tmp,LoadSave::getSerializedSize(encoding));
+				LoadSave::decode(encoding,tmp,LoadSave::getSerializedSize(encoding));
+				if(encoding==Config::vision_config::RawCamConfig::ENCODE_SINGLE_CHANNEL)
+					components=1;
+				int compression; //Config::vision_config::RawCamConfig::compression_t
+				is.read(tmp,LoadSave::getSerializedSize(compression));
+				LoadSave::decode(compression,tmp,LoadSave::getSerializedSize(compression));
+				is.read(tmp,LoadSave::getSerializedSize(width));
+				LoadSave::decode(width,tmp,LoadSave::getSerializedSize(width));
+				is.read(tmp,LoadSave::getSerializedSize(height));
+				LoadSave::decode(height,tmp,LoadSave::getSerializedSize(height));
+				unsigned int remote_timestamp;
+				is.read(tmp,LoadSave::getSerializedSize(remote_timestamp));
+				LoadSave::decode(remote_timestamp,tmp,LoadSave::getSerializedSize(remote_timestamp));
+				unsigned int fnum;
+				is.read(tmp,LoadSave::getSerializedSize(fnum));
+				LoadSave::decode(fnum,tmp,LoadSave::getSerializedSize(fnum));
+				
+				// have everything we need to set up output header...
+				unsigned int remain = LoadSave::getSerializedSize<unsigned int>()*4+width*height*components;
+				buffer.resize(remain);
+				char * buf=&buffer.front();
+				if(!LoadSave::encodeInc(layer,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(width,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(height,buf,remain)) return frameNumber;
+				if(!LoadSave::encodeInc(components,buf,remain)) return frameNumber;
+				
+				for(unsigned int i=0; i<components; ++i) {
+					// FILTER BANK GENERATOR HEADER
+					is.read(tmp,LoadSave::getSerializedSize(len));
+					LoadSave::decode(len,tmp,LoadSave::getSerializedSize(len));
+					if(len!=8) {
+						cerr << "Expecting FbkImage image format, but header doesn't match! (len==" << len << ")" << endl;
+						return frameNumber;
+					}
+					is.read(tmp,len+1);
+					if(strncmp(tmp,"FbkImage",len+1)!=0) {
+						tmp[len+2]='\0';
+						cerr << "Expecting FbkImage image format, but image header doesn't match! (" << tmp << ")" << endl;
+						return frameNumber;
+					}
+					unsigned int lwidth;
+					is.read(tmp,LoadSave::getSerializedSize(lwidth));
+					LoadSave::decode(lwidth,tmp,LoadSave::getSerializedSize(lwidth));
+					unsigned int lheight;
+					is.read(tmp,LoadSave::getSerializedSize(lheight));
+					LoadSave::decode(lheight,tmp,LoadSave::getSerializedSize(lheight));
+					unsigned int lyr;
+					is.read(tmp,LoadSave::getSerializedSize(lyr));
+					LoadSave::decode(lyr,tmp,LoadSave::getSerializedSize(lyr));
+					unsigned int chan_id;
+					is.read(tmp,LoadSave::getSerializedSize(chan_id));
+					LoadSave::decode(chan_id,tmp,LoadSave::getSerializedSize(chan_id));
+					
+					// GENERATOR SUBCLASS HEADER
+					is.read(tmp,LoadSave::getSerializedSize(len));
+					LoadSave::decode(len,tmp,LoadSave::getSerializedSize(len));
+					is.read(tmp,len+1);
+					if(strcmp(tmp,"blank")==0) {
+						int useChan=(components==1)?i:chan_id;
+						int off=useChan;
+						for(unsigned int y=0; y<height; y++) {
+							for(unsigned int x=0; x<width; x++) {
+								buf[off]=128;
+								off+=components;
+							}
+						}
+					} else if(strcmp(tmp,"RawImage")==0) {
+						int useChan=(components==1)?i:chan_id;
+						vector<char> chan(lwidth*lheight);
+						is.read(&chan.front(),chan.size());
+						copyImage(buf,width,height,components,&chan.front(),lwidth,lheight,useChan);
+						
+					} else if(strcmp(tmp,"JPEGGrayscale")==0) {
+						int useChan=(components==1)?i:chan_id;
+						is.read(tmp,LoadSave::getSerializedSize(len));
+						LoadSave::decode(len,tmp,LoadSave::getSerializedSize(len));
+						vector<char> jpeg(len);
+						is.read(&jpeg.front(),jpeg.size());
+						size_t jwidth,jheight,jcomp;
+						image_util::decodeJPEG(&jpeg.front(), jpeg.size(), jwidth, jheight, jcomp);
+						if(jcomp!=1) {
+							cerr << "Got color image where grayscale was expected" << endl;
+							return frameNumber;
+						}
+						vector<char> chan(jwidth*jheight);
+						size_t tsize=chan.size();
+						char* tchan=&chan.front();
+						if(!image_util::decodeJPEG(&jpeg.front(), jpeg.size(), jwidth, jheight, jcomp, tchan, tsize)) {
+							cerr << "JPEG decompression failed" << endl;
+							return frameNumber;
+						}
+						copyImage(buf,width,height,components,&chan.front(),lwidth,lheight,useChan);
+						
+					} else if(strcmp(tmp,"JPEGColor")==0) {
+						is.read(tmp,LoadSave::getSerializedSize(len));
+						LoadSave::decode(len,tmp,LoadSave::getSerializedSize(len));
+						vector<char> jpeg(len);
+						is.read(&jpeg.front(),jpeg.size());
+						size_t jwidth,jheight,jcomp;
+						size_t tsize=remain;
+						if(!image_util::decodeJPEG(&jpeg.front(), jpeg.size(), jwidth, jheight, jcomp, buf, tsize)) {
+							cerr << "JPEG decompression failed" << endl;
+							return frameNumber;
+						}
+						i=components;
+						
+					} else {
+						cerr << "Unknown image generator " << tmp << endl;
+						return frameNumber;
+					}
+				}
+				
+				if(!is)
+					return frameNumber;
+				frameNumber=fnum;
+			} break;
+		}
+	}
+	payload = &buffer.front();
+	payloadSize = buffer.size();
+	timestamp=get_time();
+	name=instanceName;
+	return frameNumber;
+}
+
+void ImageStreamDriver::setDataSourceThread(LoadDataThread* th) {
+	if(thread==NULL && th!=NULL) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL)
+			comm->open();
+		commName.addPrimitiveListener(this);
+	}
+	if(thread!=NULL && th==NULL) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL)
+			comm->close();
+		commName.removePrimitiveListener(this);
+	}
+	DataSource::setDataSourceThread(th);
+}
+
+void ImageStreamDriver::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&commName) {
+		// if here, then setDataSourceThread has been called, thus when commName changes,
+		// need to close old one and reopen new one
+		CommPort * comm = CommPort::getRegistry().getInstance(commName.getPreviousValue());
+		if(comm!=NULL)
+			comm->close();
+		comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL)
+			comm->open();
+	} else if(&pl==&format) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName.getPreviousValue());
+		if(comm!=NULL) {
+			MarkScope autolock(*comm);
+			delete [] img;
+			img=NULL;
+			imgSize=0;
+		} else {
+			delete [] img;
+			img=NULL;
+			imgSize=0;
+		}
+	} else {
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+void ImageStreamDriver::copyImage(char * buf, unsigned int width, unsigned int height, unsigned int channels, const char * chan, unsigned int lwidth, unsigned int lheight, unsigned int c) {
+	if(lwidth==width && lheight==height) {
+		// same size, straight copy
+		for(unsigned int y=0;y<height;y++) {
+			unsigned int datarowstart=y*width*channels+c;
+			unsigned int tmprowstart=y*lwidth;
+			for(unsigned int x=0;x<width;x++)
+				buf[datarowstart+x*channels]=chan[tmprowstart+x];
+		}
+	} else {
+		// upsample image
+		
+		//we'll linearly interpolate between pixels
+		//METHOD A:
+		//hold edges, interpolate through middle:
+		//  if we have 2 samples, scaling up to 4
+		//   index: 0   1    2   3
+		// maps to: 0  1/3  2/3  1
+		float xsc=(lwidth-1)/(float)(width-1);
+		float ysc=(lheight-1)/(float)(height-1);
+		for(unsigned int y=0;y<height-1;y++) {
+			unsigned int datarowstart=y*width*channels+c;
+			float ty=y*ysc;
+			unsigned int ly=(int)ty; //lower pixel index
+			float fy=ty-ly; //upper pixel weight
+			unsigned int tmprowstart=ly*lwidth;
+			for(unsigned int x=0;x<width-1;x++) {
+				float tx=x*xsc;
+				unsigned int lx=(int)tx; //lower pixel index
+				float fx=tx-lx; //upper pixel weight
+				
+				float lv=((int)chan[tmprowstart+lx]&0xFF)*(1-fx)+((int)chan[tmprowstart+lx+1]&0xFF)*fx;
+				float uv=((int)chan[tmprowstart+lx+lwidth]&0xFF)*(1-fx)+((int)chan[tmprowstart+lx+1+lwidth]&0xFF)*fx;
+				buf[datarowstart+x*channels]=(char)(lv*(1-fy)+uv*fy);
+			}
+			buf[datarowstart+(width-1)*channels]=chan[tmprowstart+lwidth-1];
+		}
+		unsigned int datarowstart=width*(height-1)*channels+c;
+		unsigned int tmprowstart=lwidth*(lheight-1);
+		for(unsigned int x=0;x<width-1;x++) {
+			float tx=x*xsc;
+			unsigned int lx=(int)tx; //lower pixel index
+			float fx=tx-lx; //upper pixel weight
+			buf[datarowstart+x*channels]=(char)(((int)chan[tmprowstart+lx]&0xFF)*(1-fx)+((int)chan[tmprowstart+lx+1]&0xFF)*fx);
+		}
+		buf[datarowstart+(width-1)*channels]=chan[tmprowstart+lwidth-1];
+		
+		//Unfortunately, pixels are simply interleaved, starting at the
+		//top right.  So, Method A will stretch things to the bottom-right
+		//a bit.  This method holds left edge and spacing, so it lines up
+		//better with what's being transmitted (but the bottom right edges
+		//wind up smeared)
+		//METHOD B:
+		//  if we have 2 samples, scaling up to 4
+		//   index: 0   1    2   3
+		// maps to: 0  1/2   1   1  <-- this last one would be 3/2, so we have to replicate 1
+		/*float xsc=(chanW)/(float)(width);
+		float ysc=(chanH)/(float)(height);
+		unsigned int xgap=(unsigned int)roundf(1.0f/xsc);
+		unsigned int ygap=(unsigned int)roundf(1.0f/ysc);
+		for(unsigned int y=0;y<height-ygap;y++) {
+			unsigned int datarowstart=y*width*channels+c;
+			float ty=y*ysc;
+			unsigned int ly=(int)ty; //lower pixel index
+			float fy=ty-ly; //upper pixel weight
+			unsigned int tmprowstart=ly*chanW;
+			for(unsigned int x=0;x<width-xgap;x++) {
+				float tx=x*xsc;
+				unsigned int lx=(int)tx; //lower pixel index
+				float fx=tx-lx; //upper pixel weight
+				
+				float lv=(chan[tmprowstart+lx]&0xFF)*(1-fx)+(chan[tmprowstart+lx+1]&0xFF)*fx;
+				float uv=(chan[tmprowstart+lx+chanW]&0xFF)*(1-fx)+(chan[tmprowstart+lx+1+chanW]&0xFF)*fx;
+				buf[datarowstart+x*channels]=(char)(lv*(1-fy)+uv*fy);
+			}
+			for(unsigned int x=width-xgap;x<width;x++) {
+				float lv=(chan[tmprowstart+chanW-1]&0xFF);
+				float uv=(chan[tmprowstart+chanW-1+chanW]&0xFF);
+				buf[datarowstart+x*channels]=(char)(lv*(1-fy)+uv*fy);
+			}
+		}
+		for(unsigned int y=height-ygap;y<height;y++) {
+			unsigned int datarowstart=y*width*channels+c;
+			unsigned int tmprowstart=chanW*(chanH-1);
+			for(unsigned int x=0;x<width-xgap;x++) {
+				float tx=x*xsc;
+				unsigned int lx=(int)tx; //lower pixel index
+				float fx=tx-lx; //upper pixel weight
+				
+				float lv=(chan[tmprowstart+lx]&0xFF)*(1-fx)+(chan[tmprowstart+lx+1]&0xFF)*fx;
+				buf[datarowstart+x*channels]=(byte)(lv);
+			}
+			for(unsigned int x=width-xgap;x<width;x++)
+				buf[datarowstart+x*channels]=chan[tmprowstart+chanW-1];
+		}*/
+	}
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.4 $
+ * $State: Exp $
+ * $Date: 2007/11/05 00:20:11 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/ImageStreamDriver.h ./local/DeviceDrivers/ImageStreamDriver.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/ImageStreamDriver.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/ImageStreamDriver.h	2007-07-19 19:14:50.000000000 -0400
@@ -0,0 +1,86 @@
+//-*-c++-*-
+#ifndef INCLUDED_ImageStreamDriver_h_
+#define INCLUDED_ImageStreamDriver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/DataSource.h"
+#include "local/CommPort.h"
+#include "Shared/plist.h"
+#include <iostream>
+
+//! description of ImageStreamDriver
+class ImageStreamDriver : public virtual DeviceDriver, public DataSource, public virtual plist::PrimitiveListener {
+public:
+	explicit ImageStreamDriver(const std::string& name)
+	: DeviceDriver(autoRegisterImageStreamDriver,name), DataSource(),
+	commName(), format(FORMAT_JPEG,formatNames), frameNumber(0), buffer(), img(NULL), imgSize(0)
+	{
+		format.addNameForVal("jpg",FORMAT_JPEG);
+		addEntry("CommPort",commName,"The name of the comm port from which data will be read.");
+		addEntry("Format",format,"The type of format to expect from the comm port.\n"
+				 "'YUV' expects interleaved components 'CameraResolutionX' wide and 'CameraResolutionY' high\n"
+				 "(defined in target's RobotInfo namespace)");
+		format.addPrimitiveListener(this);
+	}
+	virtual ~ImageStreamDriver() {
+		format.removePrimitiveListener(this);
+	}
+
+	virtual std::string getClassName() const { return autoRegisterImageStreamDriver; }
+
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		//sources["Sensors"]=sensors;
+	}
+	virtual void getImageSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		sources["Camera"]=this;
+	}
+	
+	virtual unsigned int nextTimestamp();
+	virtual const std::string& nextName() { return instanceName; }
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* th);
+
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+
+	plist::Primitive<std::string> commName;
+	
+	enum format_t {
+		FORMAT_YUV=0,
+		FORMAT_PNG,
+		FORMAT_JPEG,
+		FORMAT_TEKKOTSU
+	};
+	static const size_t NUM_FORMATS = 4;
+	static const char * formatNames[NUM_FORMATS+1];
+	plist::NamedEnumeration<format_t> format;
+
+protected:
+	void copyImage(char * buf, unsigned int width, unsigned int height, unsigned int channels, const char * chan, unsigned int lwidth, unsigned int lheight, unsigned int chan);
+	
+	//BufferSource sensors; //!< separate DataSource for sensor frames, if embedded in image stream
+	unsigned int frameNumber; //!< image frame number
+	std::vector<char> buffer; //!< image buffer
+	char * img; //!< temporary storage for jpeg/png decompression
+	size_t imgSize; //!< size of allocation of #img
+
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterImageStreamDriver;
+	ImageStreamDriver(const ImageStreamDriver&); //!< no call
+	ImageStreamDriver operator=(const ImageStreamDriver&); //!< no call
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.5 $
+ * $State: Exp $
+ * $Date: 2007/07/19 23:14:50 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/LoggedDataDriver.cc ./local/DeviceDrivers/LoggedDataDriver.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/LoggedDataDriver.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/LoggedDataDriver.cc	2007-06-03 13:03:30.000000000 -0400
@@ -0,0 +1,16 @@
+#include "LoggedDataDriver.h"
+
+using namespace std; 
+
+const std::string LoggedDataDriver::autoRegisterLoggedDataDriver = DeviceDriver::getRegistry().registerType<LoggedDataDriver>("LoggedData");
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:30 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/LoggedDataDriver.h ./local/DeviceDrivers/LoggedDataDriver.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/LoggedDataDriver.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/LoggedDataDriver.h	2007-06-06 14:00:59.000000000 -0400
@@ -0,0 +1,79 @@
+//-*-c++-*-
+#ifndef INCLUDED_LoggedDataDriver_h_
+#define INCLUDED_LoggedDataDriver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/DataSources/FileSystemImageSource.h"
+
+//! description of LoggedDataDriver
+class LoggedDataDriver : public virtual DeviceDriver, public virtual plist::PrimitiveListener {
+public:
+	LoggedDataDriver(const std::string& name) : DeviceDriver(autoRegisterLoggedDataDriver,name),
+		path(), fsSensorSrc(*this, ".*\\.pos$"), fsImageSrc(*this, ".*\\.(jpg|jpeg|png)$")
+	{
+		addEntry("Path",path,"The directory from which data samples should be loaded, or a single specific file.\nA single file can be either a single data file (e.g. sensor or camera image), or an index file as output by VisionGUI, or in the format 'filename <tab> time', where 'filename' is an absolute path or relative to the directory containing the index file, and 'time' is in milliseconds, relative to the time at which the index file is loaded.\nIn the future, this could also be network addresses for teleoperation and remote processing.");
+		addEntry("Sensors",fsSensorSrc,"Settings for loading logged sensor readings (stored in PostureEngine format)");
+		addEntry("Camera",fsImageSrc,"Settings for loading logged camera images (stored as either JPEG or PNG)");
+		path.addPrimitiveListener(this);
+		fsSensorSrc.path.addPrimitiveListener(this);
+		fsImageSrc.path.addPrimitiveListener(this);
+	}
+	
+	virtual std::string getClassName() const { return autoRegisterLoggedDataDriver; }
+	
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		sources["Sensors"]=&fsSensorSrc;
+	}
+	virtual void getImageSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		sources["Camera"]=&fsImageSrc;
+	}
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl) {
+		if(&pl==&path) {
+			// reload file lists for data sources which aren't overriding the common path
+			if(fsSensorSrc.path.size()==0)
+				fsSensorSrc.loadFileList();
+			if(fsImageSrc.path.size()==0)
+				fsImageSrc.loadFileList();
+		}
+		if(&pl==&fsSensorSrc.path || &pl==&fsImageSrc.path || &pl==&path) {
+			// if both streams are using the same source...
+			if(fsSensorSrc.getUsedPath()==fsImageSrc.getUsedPath()) {
+				//keep them in sync across loops, smooth offset between end times
+				//std::cout << "SYNCING LOOP TIMES" << std::endl;
+				float looptime=std::max(fsSensorSrc.getLoopTime(false),fsImageSrc.getLoopTime(false));
+				if(looptime>0) { // if negative, indicates neither in use by LoadDataThread, framerates are unknown
+					fsSensorSrc.setLoopTime(looptime);
+					fsImageSrc.setLoopTime(looptime);
+				}
+			}
+		} else {
+			std::cerr << "LoggedDataDriver didn't handle call to plistValueChanged for " << pl.get() << std::endl;
+		}
+	}
+	
+	plist::Primitive<std::string> path;
+	
+protected:
+	FileSystemDataSource fsSensorSrc;
+	FileSystemImageSource fsImageSrc;
+	
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterLoggedDataDriver;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/06/06 18:00:59 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/SSC32Driver.cc ./local/DeviceDrivers/SSC32Driver.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/SSC32Driver.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/SSC32Driver.cc	2007-11-01 16:25:05.000000000 -0400
@@ -0,0 +1,342 @@
+#include "SSC32Driver.h"
+#include "Shared/MarkScope.h"
+#include "Shared/get_time.h"
+#include "Shared/debuget.h"
+
+using namespace std; 
+
+const unsigned int SSC32Driver::NUM_SERVO;
+const int SSC32Driver::UNUSED;
+const std::string SSC32Driver::autoRegisterSSC32Driver = DeviceDriver::getRegistry().registerType<SSC32Driver>("SSC32");
+
+void SSC32Driver::motionStarting() {
+	MotionHook::motionStarting();
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm!=NULL)
+		comm->open();
+	motionActive=true;
+	commName.addPrimitiveListener(this);
+}
+
+void SSC32Driver::motionStopping() {
+	motionActive=false;
+	if(!sensorsActive) // listener count is not recursive, so only remove if we're the last one
+		commName.removePrimitiveListener(this);
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm!=NULL)
+		comm->close(); // this *is* recursive, so we always close it to match our open() in motionStarting()
+	MotionHook::motionStopping();
+}
+
+void SSC32Driver::motionCheck(const float outputs[][NumOutputs]) {
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isWriteable())
+		return;
+	
+	stringstream ss;
+	for(unsigned int i=0; i<NUM_SERVO; i++) {
+		int idx=servos[i];
+		if(idx<0 || static_cast<unsigned int>(idx)>=NumOutputs) {
+			if(idx!=UNUSED)
+				std::cerr << "Warning: SSC32 driver mapping servo " << i << " to invalid output index " << idx << std::endl;
+			continue; // invalid/unused servo
+		}
+		if(isFirstCheck || !sparse || lastOutputs[idx]!=outputs[NumFrames-1][idx])
+			setServo(ss, i, outputs[NumFrames-1][idx]);
+	}
+	string s=ss.str();
+	if(s.size()>0) { // if sparse and no changes, skip update altogether
+		ThreadNS::Lock& l = comm->getLock();
+		unsigned int t=get_time();
+		// keep trying to get the lock, sleeping 1 ms each time, until 3/4 the frame time is gone (then give up)
+		unsigned int dt = static_cast<unsigned int>(NumFrames*FrameTime/((getTimeScale()>0)?getTimeScale():1.f));
+		unsigned int giveup = t+dt*3/4;
+		t+=dt;
+		while(!l.trylock()) {
+			if(get_time()>=giveup) {
+				if(MotionHook::verbose>0)
+					cerr << "Dropping SSC32 motion update: couldn't get lock on comm port" << endl;
+				return;
+			}
+			usleep(1000);
+		}
+		MarkScope autolock(l); l.unlock(); //transfer lock to MarkScope
+		std::ostream os(&comm->getWriteStreambuf());
+		unsigned int curt = get_time();
+		if(curt>=t) // too late!
+			os << s << '\r' << flush;
+		else {
+			dt=t-curt;
+			os << s << 'T' << dt << '\r' << flush; // indicate time until next update
+		}
+	}
+	
+	MotionHook::motionCheck(outputs); // updates lastOutputs and isFirstCheck, we ignore its motionUpdated() call
+}
+
+
+unsigned int SSC32Driver::nextTimestamp() {
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isReadable())
+		return -1U;
+	return get_time();
+}
+
+unsigned int SSC32Driver::getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name) {
+	payload=NULL; payloadSize=0; // in case of error
+	CommPort * comm = CommPort::getRegistry().getInstance(commName);
+	if(comm==NULL || !comm->isReadable() || !comm->isWriteable())
+		return frameNumber;
+	unsigned int t=get_time();
+	if(timestamp>t)
+		usleep(static_cast<unsigned int>((timestamp-t)*1000/(getTimeScale()>0?getTimeScale():1.f)));
+	if(thread==NULL) // in case we shut down while waiting
+		return frameNumber;
+	stringstream ss;
+	timestamp=get_time();
+	ss << "#POS\n";
+	{
+		MarkScope autolock(comm->getLock());
+		std::ostream os(&comm->getWriteStreambuf());
+		std::istream is(&comm->getReadStreambuf());
+		// generally, bad idea to request servo position before position has been sent
+		// But if the arm is still powered, it'll know it's position.  If the user has set WaitForSensors,
+		// then DataSource::requiresFirstSensor will be set, otherwise we skip queries until we've sent
+		// a servo position (and thus set the isFirstCheck flag
+		if((!isFirstCheck || DataSource::requiresFirstSensor) && queryServos) {
+			// check joint positions
+			stringstream q;
+			for(unsigned int i=0; i<NUM_SERVO; i++) {
+				int idx=servos[i];
+				if(idx<0 || static_cast<unsigned int>(idx)>=NumOutputs)
+					continue; // invalid/unused servo
+				q << "QP " << i << ' ';
+			}
+			os << q.rdbuf() << '\r' << flush;
+			for(unsigned int i=0; i<NUM_SERVO; i++) {
+				int idx=servos[i];
+				if(idx<0 || static_cast<unsigned int>(idx)>=NumOutputs)
+					continue; // invalid/unused servo
+				int check=is.get();
+				if(check==-1) {
+					cerr << "SSC32Driver: bad read!" << endl;
+					return frameNumber;
+				}
+				unsigned int v=(unsigned char)check;
+				ss << outputNames[idx] << '\t' << getServo(i,v*10) << "\t1\n";
+			}
+		}
+		stringstream aq,dq;
+		bool acnt=0,dcnt=0;
+		for(unsigned int i=0; i<NUM_INPUT; i++) {
+			int idx=inputs[i];
+			if(!buttonMode[i]) {
+				if(idx<0 || static_cast<unsigned int>(idx)>=NumSensors) {
+					if(idx!=UNUSED)
+						std::cerr << "Warning: SSC32 driver mapping input " << i << " to invalid sensor index " << idx << std::endl;
+					continue; // invalid/unused servo
+				}
+				++acnt;
+				aq << 'V' << char('A'+i) << ' ';
+			} else {
+				if(idx<0 || static_cast<unsigned int>(idx)>=NumButtons) {
+					if(idx!=UNUSED)
+						std::cerr << "Warning: SSC32 driver mapping input " << i << " to invalid button index " << idx << std::endl;
+					continue; // invalid/unused servo
+				}
+				++dcnt;
+				dq << char('A'+i) << ' ' << char('A'+i) << "L ";
+			}
+		}
+		// send both queries now, we can process first response while SSC is processing second query
+		if(dcnt>0)
+			os << dq.rdbuf() << '\r';
+		if(acnt>0)
+			os << aq.rdbuf() << '\r';
+		if(dcnt>0 || acnt>0)
+			os << flush;
+		// store responses
+		if(dcnt>0) {
+			ss << "<buttons>\n";
+			for(unsigned int i=0; i<NUM_INPUT; i++) {
+				int idx=inputs[i];
+				if(idx>=0 && static_cast<unsigned int>(idx)<NumButtons && buttonMode[i]) {
+					int check=is.get();
+					if(check==-1) {
+						cerr << "SSC32Driver: bad read!" << endl;
+						return frameNumber;
+					}
+					unsigned char cur=check;
+					check=is.get();
+					if(check==-1) {
+						cerr << "SSC32Driver: bad read!" << endl;
+						return frameNumber;
+					}
+					unsigned char latch=check;
+					float v=getDigital(i,cur,latch);
+					ss << buttonNames[idx] << '\t' << v << '\n';
+				}
+			}
+			ss << "</buttons>\n";
+		}
+		if(acnt>0) {
+			ss << "<sensors>\n";
+			for(unsigned int i=0; i<NUM_INPUT; i++) {
+				int idx=inputs[i];
+				if(idx>=0 && static_cast<unsigned int>(idx)<NumSensors && !buttonMode[i]) {
+					int check=is.get();
+					if(check==-1) {
+						cerr << "SSC32Driver: bad read!" << endl;
+						return frameNumber;
+					}
+					float v=getAnalog(i,check);
+					ss << sensorNames[idx] << '\t' << v << '\n';
+				}
+			}
+			ss << "</sensors>\n";
+		}
+	}
+	ss << "#END\n";
+	lastSensor=ss.str();
+	//cerr << lastSensor << endl;
+	payload=lastSensor.c_str();
+	payloadSize=lastSensor.size();
+	name=nextName();
+	return frameNumber++;
+}
+
+void SSC32Driver::setDataSourceThread(LoadDataThread* th) {
+	if(thread==NULL && th!=NULL) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL)
+			comm->open();
+		queryServos.addPrimitiveListener(this);
+		if(queryServos) {
+			for(unsigned int i=0; i<NUM_SERVO; i++) {
+				provideOutput(servos[i]);
+				servos[i].addPrimitiveListener(this);
+			}
+		}
+		sensorsActive=true;
+		commName.addPrimitiveListener(this);
+	}
+	if(thread!=NULL && th==NULL) {
+		CommPort * comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL)
+			comm->close();
+		if(queryServos) {
+			for(unsigned int i=0; i<NUM_SERVO; ++i) {
+				servos[i].removePrimitiveListener(this);
+				ignoreOutput(servos[i]);
+			}
+		}
+		queryServos.removePrimitiveListener(this);
+		sensorsActive=false;
+		if(!motionActive) // listener count is not recursive, so only remove if we're the last one
+			commName.removePrimitiveListener(this);
+	}
+	DataSource::setDataSourceThread(th);
+}
+
+void SSC32Driver::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&commName) {
+		// if here, then motionStarted or setDataSourceThread has been called, thus when commName changes,
+		// need to close old one and reopen new one
+		CommPort * comm = CommPort::getRegistry().getInstance(commName.getPreviousValue());
+		if(comm!=NULL) {
+			// close each of our old references
+			if(sensorsActive)
+				comm->close();
+			if(motionActive)
+				comm->close();
+		}
+		comm = CommPort::getRegistry().getInstance(commName);
+		if(comm!=NULL) {
+			// open each of our new references
+			if(sensorsActive)
+				comm->open();
+			if(motionActive)
+				comm->open();
+		}
+	} else if(&pl==&queryServos) {
+		// if here, LoadDataThread has been assigned, need to update providing/ignoring outputs
+		// (and maintain listeners for individual servos while providing)
+		if(queryServos) {
+			for(unsigned int i=0; i<NUM_SERVO; i++) {
+				provideOutput(servos[i]);
+				servos[i].addPrimitiveListener(this);
+			}
+		} else {
+			for(unsigned int i=0; i<NUM_SERVO; ++i) {
+				servos[i].removePrimitiveListener(this);
+				ignoreOutput(servos[i]);
+			}
+		}
+	} else {
+		// check if it's one of the individual servos... if it is, means we're providing servo feedback,
+		// need to call providingOutput/ignoringOutput as appropriate
+		for(unsigned int i=0; i<NUM_SERVO; ++i) {
+			if(&pl==&servos[i]) {
+				ignoreOutput(servos[i].getPreviousValue());
+				provideOutput(servos[i]);
+				return; // found it, DON'T fall through to error message below...
+			}
+		}
+		std::cerr << "Unhandled value change in " << getClassName() << ": " << pl.get() << std::endl;
+	}
+}
+
+void SSC32Driver::setServo(std::ostream& ss, unsigned int servoIdx, float v) {
+	unsigned int outputIdx = servos[servoIdx];
+	// get output's range in radians
+	float outRange = outputRanges[outputIdx][MaxRange]-outputRanges[outputIdx][MinRange];
+	// get servo's range in pulse width (ms)
+	unsigned int servoRange = maxPW[servoIdx]-minPW[servoIdx];
+	// get commanded position as percent of range of motion
+	float cmd = (v-outputRanges[outputIdx][MinRange])/outRange;
+	// flip commanded position -- map positive (high) rotation to low pulse width
+	// this is so if you mount a servo "up", coordinate system will work correctly
+	cmd=1-cmd;
+	// do conversion from radians (output domain) to pulse width (servo domain)
+	float pw = cmd*servoRange+minPW[servoIdx];
+	// round to int
+	unsigned int bpw = static_cast<unsigned int>(pw+0.5);
+	// check bounds
+	if(bpw<minPW[servoIdx])
+		bpw=minPW[servoIdx];
+	if(bpw>maxPW[servoIdx])
+		bpw=maxPW[servoIdx];
+	// send to output buffer
+	ss << '#' << servoIdx << " P" << bpw << ' ';
+}
+
+float SSC32Driver::getServo(unsigned int servoIdx, unsigned int pw) {
+	unsigned int outputIdx = servos[servoIdx];
+	// get output's range in radians
+	double outRange = outputRanges[outputIdx][MaxRange]-outputRanges[outputIdx][MinRange];
+	// get servo's range in pulse width (ms)
+	unsigned int servoRange = maxPW[servoIdx]-minPW[servoIdx];
+	// do conversion from pulse width (servo domain) to radians (output domain)
+	return (pw-minPW[servoIdx])*outRange/servoRange + outputRanges[outputIdx][MinRange];
+}
+
+float SSC32Driver::getAnalog(unsigned int /*inputIdx*/, unsigned char s) {
+	return s*5.f/256;
+}
+
+float SSC32Driver::getDigital(unsigned int /*inputIdx*/, unsigned char cur, unsigned char latch) {
+	if(cur=='0')
+		return 0;
+	return (latch=='0') ? 0.5f : 1;
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.6 $
+ * $State: Exp $
+ * $Date: 2007/11/01 20:25:05 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/SSC32Driver.h ./local/DeviceDrivers/SSC32Driver.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/SSC32Driver.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/SSC32Driver.h	2007-06-06 14:00:59.000000000 -0400
@@ -0,0 +1,104 @@
+//-*-c++-*-
+#ifndef INCLUDED_SSC32Driver_h_
+#define INCLUDED_SSC32Driver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/MotionHook.h"
+#include "local/DataSource.h"
+#include "local/CommPort.h"
+#include "Shared/plist.h"
+#include <iostream>
+
+//! description of SSC32Driver
+class SSC32Driver : public virtual DeviceDriver, public MotionHook, public DataSource, public virtual plist::PrimitiveListener {
+public:
+	static const unsigned int NUM_SERVO=32;
+	static const unsigned int NUM_INPUT=4;
+	static const int UNUSED=-1;
+	
+	explicit SSC32Driver(const std::string& name)
+		: DeviceDriver(autoRegisterSSC32Driver,name), MotionHook(), DataSource(),
+		servos(NUM_SERVO,UNUSED), inputs(NUM_INPUT,UNUSED),
+		minPW(NUM_SERVO,500), maxPW(NUM_SERVO,2500), buttonMode(NUM_INPUT,false),
+		sparse(false), commName(), queryServos(false), motionActive(false), sensorsActive(false), lastSensor(), frameNumber(0)
+	{
+		for(unsigned int i=0; i<NumOutputs && i<NUM_SERVO; ++i)
+			servos[i]=i;
+		for(unsigned int i=0; i<NumSensors && i<NUM_INPUT; ++i)
+			inputs[i]=i;
+		addEntry("OutputMap",servos,"For each of the SSC32's servo pins, lists the output index it should take its values from; -1 to mark unused");
+		addEntry("InputMap",inputs,"For each of the SSC32's input pins, lists the sensor index it should send its value to; -1 to mark unused");
+		addEntry("MinPulseWidth",minPW,"The low end of the servo's legal pulse width range (may correspond to unreachable position, use RobotInfo's outputRange[] to limit motion, not this)");	
+		addEntry("MaxPulseWidth",maxPW,"The high end of the servo's legal pulse width range (may correspond to unreachable position, use RobotInfo's outputRange[] to limit motion, not this)");	
+		addEntry("ButtonMode",buttonMode,"Controls interpretation of the input pin.\nFalse means directly measure voltage, true means test for high (1),\nhigh now but low was detected in interval (0.5), or low (0).\nButton mode implies interpreting inputMap value as a button index instead of sensor index.");
+		addEntry("SparseUpdates",sparse,"If true, only send servo positions to SSC when they change, instead of all servos on every update (don't use a lossy transport like UDP if you turn this on!)");
+		addEntry("CommPort",commName,"The name of the comm port where output will be sent");
+		addEntry("QueryServos",queryServos,"If set to true, will attempt to query the servo positions with each sensor update.\nThis may decrease the sampling frequency");
+	}
+	virtual ~SSC32Driver() {}
+	
+	virtual std::string getClassName() const { return autoRegisterSSC32Driver; }
+	
+	virtual MotionHook* getMotionSink() { return dynamic_cast<MotionHook*>(this); }
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		sources["Sensors"]=dynamic_cast<DataSource*>(this);
+	}
+	
+	virtual void motionStarting();
+	virtual void motionStopping();
+	virtual void motionCheck(const float outputs[][NumOutputs]);
+	
+	virtual unsigned int nextTimestamp();
+	virtual const std::string& nextName() { return instanceName; }
+	virtual unsigned int getData(const char *& payload, unsigned int& payloadSize, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* th);
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	plist::ArrayOf<plist::Primitive<int> > servos;
+	plist::ArrayOf<plist::Primitive<int> > inputs;
+	plist::ArrayOf<plist::Primitive<unsigned int> > minPW;
+	plist::ArrayOf<plist::Primitive<unsigned int> > maxPW;
+	plist::ArrayOf<plist::Primitive<bool> > buttonMode;
+	plist::Primitive<bool> sparse;
+	plist::Primitive<std::string> commName;
+	plist::Primitive<bool> queryServos;
+	
+protected:
+	//! forwards call to DataSource::providingOutput() if the index is valid
+	void provideOutput(unsigned int idx) { if(idx<NumOutputs) providingOutput(idx); }
+	//! forwards call to DataSource::ignoringOutput() if the index is valid
+	void ignoreOutput(unsigned int idx) { if(idx<NumOutputs) ignoringOutput(idx); }
+	
+	//! converts the value @a v from radians into the specified servo's pulse width range
+	virtual void setServo(std::ostream& ss, unsigned int servoIdx, float v);
+	//! converts the value @a pw from specified servo's pulse width range into radians
+	virtual float getServo(unsigned int servoIdx, unsigned int pw);
+	//! converts the value @a s from specified input's signal to voltage
+	virtual float getAnalog(unsigned int inputIdx, unsigned char s);
+	//! converts the value @a cur and @a latch to the output format (0 if low, 0.5 if high but has been low, 1 if consistent high)
+	virtual float getDigital(unsigned int inputIdx, unsigned char cur, unsigned char latch);
+	
+	bool motionActive;
+	bool sensorsActive;
+	std::string lastSensor;
+	unsigned int frameNumber;
+	
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterSSC32Driver;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/06/06 18:00:59 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/TeRKDriver.cc ./local/DeviceDrivers/TeRKDriver.cc
--- ../Tekkotsu_3.0/local/DeviceDrivers/TeRKDriver.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/TeRKDriver.cc	2007-11-11 18:57:29.000000000 -0500
@@ -0,0 +1,334 @@
+#ifdef HAVE_ICE
+#include <iostream>
+#include <sstream>
+#include <unistd.h>
+#include "TeRKDriver.h"
+
+using namespace std; 
+
+const std::string TeRKDriver::autoRegisterTeRKDriver = DeviceDriver::getRegistry().registerType<TeRKDriver>("TeRK");
+
+//! this array defines the values for TeRKDriver::TeRKProperties::defaults
+pair<string,string> TeRKDriver::TeRKProperties::defaultValues[NUM_DEFAULT_VALUES] = {
+	make_pair( "Ice.Package.peer", "edu.cmu.ri.mrpl" ),
+	make_pair( "Ice.Package.TeRK", "edu.cmu.ri.mrpl" ),
+	make_pair( "Ice.Default.Package", "edu.cmu.ri.mrpl" ),
+	
+	make_pair( "TerkClient.Client.Endpoints", "tcp" ),
+	
+	// Active connection management must be disabled when using bidirectional connections.
+	make_pair( "Ice.ACM.Client", "0" ),
+	make_pair( "Ice.ACM.Server", "0" ),
+	
+	// Print warning messages for certain exceptional conditions in connections
+	make_pair( "Ice.Warn.Connections", "1" ),
+	
+	make_pair( "Ice.Logger.Timestamp", "1" ),
+	
+	make_pair( "Ice.ThreadPool.Client.Size", "5" ),
+	make_pair( "Ice.ThreadPool.Client.SizeMax", "20" ),
+	make_pair( "Ice.ThreadPool.Server.Size", "5" ),
+	make_pair( "Ice.ThreadPool.Server.SizeMax", "20" ),
+	
+	// protocol and port to use for direct connect
+	make_pair( "TeRK.direct-connect.protocol", "tcp" ),
+	make_pair( "TeRK.direct-connect.port", "10101" ),
+};
+
+void TeRKDriver::motionUpdated(const std::vector<size_t>& changedIndices, const float outputs[][NumOutputs]) {
+	if(qwerk==NULL)
+		return;
+	
+	std::set<size_t> updatedIndices(changedIndices.begin(),changedIndices.end());
+	
+#ifdef TGT_HAS_LEDS
+	for(unsigned int i=LEDOffset; i<LEDOffset+NumLEDs; ++i) {
+		float v = outputs[NumFrames-1][i];
+		if(v>0 && v<1) // intermediate value, need to flicker activation
+			updatedIndices.insert(i);
+	}
+#endif
+	
+	if(updatedIndices.size()==0)
+		return;
+	try {
+		//cout << "Got motor command. " << endl;
+		//QwerkState qstate = qwerk->requestStateFrame();
+		//cout << "Getting state packet with: " << qstate.motor.motorVelocities.size() << " " << qstate.motor.motorVelocities[0] << " " << qstate.motor.motorVelocities[1] << " " << qstate.motor.motorVelocities[2] << " " << qstate.motor.motorVelocities[3] << endl;
+		//cout << "Setting motor to: " << outputs[NumFrames-1][0] << " " << outputs[NumFrames-1][1] << endl;
+		//cout << "Setting servo to: " << outputs[NumFrames-1][2] << " " << outputs[NumFrames-1][3] << endl;
+		
+#ifdef TGT_HAS_WHEELS
+		const int MOTOR_MAX=100000;
+		::TeRK::MotorCommand mc;
+		mc.motorVelocities.assign(NumWheels,0);
+		mc.motorPositions.assign(NumWheels,0);
+		mc.motorAccelerations.assign(NumWheels,1000000);
+		mc.motorMask.assign(NumWheels,false); // will set to true for the motors being updated
+		mc.motorModes.assign(NumWheels,::TeRK::MotorSpeedControl);
+#endif
+		
+#ifdef TGT_HAS_LEDS
+		::TeRK::LEDCommand ledc;
+		ledc.ledMask.assign(NumLEDs,false);
+		ledc.ledModes.assign(NumLEDs,::TeRK::LEDOff);
+#endif
+		
+		const int SERVO_MAX=255;
+		const int NUM_SERVOS = NumOutputs-NumWheels-NumLEDs;
+		::TeRK::ServoCommand sc;
+		sc.servoPositions.assign(NUM_SERVOS,0);
+		sc.servoSpeeds.assign(NUM_SERVOS,INT_MAX);
+		sc.servoMask.assign(NUM_SERVOS,false);
+		sc.servoModes.assign(NUM_SERVOS,::TeRK::ServoMotorPositionControl);
+		
+		for(std::set<size_t>::const_iterator it=updatedIndices.begin(); it!=updatedIndices.end(); ++it) {
+#ifdef TGT_HAS_WHEELS
+			if(WheelOffset<=*it && *it<WheelOffset+NumWheels) {
+				const unsigned int motorIdx=(*it-WheelOffset);
+				float scale=outputRanges[*it][MaxRange]*3; // assuming symmetric range!
+				mc.motorVelocities[motorIdx]=static_cast<int>(MOTOR_MAX*outputs[NumFrames-1][*it]/scale);
+				mc.motorMask[motorIdx]=true;
+				cout << "Setting " << outputNames[*it] << " (motor " << motorIdx << ") to: " << outputs[NumFrames-1][*it] << " (" << mc.motorVelocities[motorIdx] << ")" << endl;
+			} else
+#endif
+#ifdef TGT_HAS_LEDS
+			if(LEDOffset<=*it && *it<LEDOffset+NumLEDs){
+				const unsigned int ledIdx = (*it-LEDOffset);
+				ledc.ledMask[ledIdx] = true;
+				ledc.ledModes[ledIdx] = calcLEDValue(ledIdx,outputs[NumFrames-1][*it]);
+			} else
+#endif
+			{
+				// if it's not a wheel or LED, treat it as a servo
+				unsigned int servoIdx=*it;
+#ifdef TGT_HAS_WHEELS
+				if(servoIdx>WheelOffset)
+					servoIdx-=NumWheels;
+#endif
+#ifdef TGT_HAS_LEDS
+				if(servoIdx>LEDOffset)
+					servoIdx-=NumLEDs;
+#endif
+				const float range = outputRanges[*it][MaxRange]-outputRanges[*it][MinRange];
+				sc.servoPositions[servoIdx]=(int)(SERVO_MAX*(outputs[NumFrames-1][*it]-outputRanges[*it][MinRange])/range);
+				//int cur=(SERVO_MAX*(lastOutputs[*it]-outputRanges[*it][MinRange])/range);
+				//sc.servoSpeeds[servoIdx]=abs(sc.servoPositions[servoIdx]-cur)*1000/(FrameTime*NumFrames);
+				sc.servoMask[servoIdx]=true;
+				cout << "Setting " << outputNames[*it] << " (servo " << servoIdx << ") to: " << outputs[NumFrames-1][*it] << " (" << sc.servoPositions[servoIdx] << ")" << endl;
+			}
+		}
+		
+		// push the state to the qwerk
+#ifdef TGT_HAS_WHEELS
+		qwerk->motorControl->execute(mc);
+#endif
+#ifdef TGT_HAS_LEDS
+		qwerk->ledControl->execute(ledc);
+#endif
+		qwerk->servoControl->execute(sc);
+	} catch(...) {
+		std::cerr << "TerkMotionHook::motionCheck caught exception -- communication lost?" << std::endl;
+		close();
+
+		while(qwerk==NULL){
+			std::cerr << "Reconnecting in 10 seconds..." << std::endl;
+			sleep(10);
+			this->connect();
+		}
+	}
+}
+
+
+void TeRKDriver::plistValueChanged(const plist::PrimitiveBase& pl) {
+	this->connect();
+}
+
+void TeRKDriver::connect(){
+	bool wasConnected=(qwerk!=NULL);
+	close();
+
+	if(host.size()!=0) {
+		string port = properties->getProperty("TeRK.direct-connect.port");
+		try {
+			qwerk = connectToPeer();
+		} catch(const Ice::Exception& e) {
+			std::cerr << "TeRKDriver threw exception '" << e << "' when connecting to " << host << " on port " << port << std::endl;
+		} catch(const std::string& e) {
+			std::cerr << "TeRKDriver threw exception string '" << e << "' when connecting to " << host << " on port " << port << std::endl;
+		} catch(const char* e) {
+			std::cerr << "TeRKDriver threw exception cstring '" << e << "' when connecting to " << host << " on port " << port << std::endl;
+		} catch(...) {
+			std::cerr << "TeRKDriver threw unknown exception when connecting to " << host << " on port " << port << std::endl;
+		}
+		if(qwerk==NULL) {
+			std::cerr << "TeRKDriver could not connect to " << host << " on port " << port << std::endl;
+			close();
+			return;
+		}
+	}
+	
+	bool isConnected=(qwerk!=NULL);
+	if(wasConnected!=isConnected) // if we changed connection status...
+		fireDataSourcesUpdated(); // ...either new data sources are available, or old ones are gone
+}
+
+QwerkBot* TeRKDriver::connectToPeer() {
+  if(ic)
+    ic->destroy();
+  Ice::InitializationData iceData;
+  iceData.properties = properties;
+  ic = Ice::initialize(iceData);
+
+
+  ostringstream uuidSS;
+  uuidSS << "direct_connect_client|";
+  uuidSS << IceUtil::generateUUID();
+  uuidSS << "|" << idcount;
+  uuid = uuidSS.str();
+  idcount++;
+
+	string port = properties->getProperty("TeRK.direct-connect.port");
+	cout << "Connecting to " << host << ":" << port << endl;
+	
+	::Ice::Identity peerIdentity;
+	peerIdentity.name = "::TeRK::TerkUser";
+	peerIdentity.category = "";
+	
+	::Ice::ObjectPrx objectPrx = getPeerProxy(peerIdentity);
+	cout << "objectPrx: " << objectPrx << endl;
+	::TeRK::TerkUserPrx peerProxy = ::TeRK::TerkUserPrx::checkedCast(objectPrx);
+	
+	::Ice::ObjectAdapterPtr adapter = ic->createObjectAdapter("TerkClient.Client");
+
+	peerProxy->ice_getConnection()->setAdapter(adapter);
+	
+	::Ice::Identity callbackReceiverIdent;
+	callbackReceiverIdent.name = "terkCallbackReceiver";
+	callbackReceiverIdent.category = "";
+	
+	TerkUserI* terkUserI = new TerkUserI();
+	::TeRK::TerkClientPrx qwerkServantPrx = ::TeRK::TerkClientPrx::checkedCast(adapter->add(terkUserI, callbackReceiverIdent));
+	cout << "qwerkServantPrx: " << qwerkServantPrx << endl;
+	
+	adapter->activate();
+	
+	// Clean up old ping thread if exists
+	if(ping) ping->destroy();
+	// Starting ping thread - to make sure connection is still alive
+	ping = new ObjectPingThread(peerProxy);
+	ping->start();
+	
+	// Validate it is a qwerk proxy 
+	::TeRK::QwerkPrx peer = ::TeRK::QwerkPrx::checkedCast(peerProxy);
+	cout << "Casting to qwerkPrx: " << peer << endl;
+	
+	// now tell the bot that we're connected.
+	peerProxy->peerConnected(uuid, ::peer::AccessLevelOwner, qwerkServantPrx);
+	
+	cout << "Told bot I exist..." << endl;
+	QwerkBot *qb = new QwerkBot(this, peerProxy, peer);
+	cout << "Created QwerkBot" << endl;
+	terkUserI->setImageCache(qb->imageCache);
+	cout << "Set image cache to bot" << endl;
+	if(qb->video){
+		printf("Starting Video...\n");
+		// first time we connect to "fake qwerk" throws an internal Ice exception on startVideoStream()
+		// this is apparently supposed to indicate you should try again, so we do.
+		// (this whole issue may be an Ice bug that we're even seeing the exception)
+		const unsigned int TRIES=5;
+		for(unsigned int i=0; i<TRIES; i++) {
+			try {
+				qb->video->startVideoStream();
+				break; // no exception? leave retry loop...
+			} catch(const Ice::Exception& e) {
+				std::cerr << "TeRKDriver threw exception '" << e << "' connecting to video on " << host << " port " << port << " (attempt " << i+1 << " of " << TRIES << ")" << std::endl;
+			} catch(const std::string& e) {
+				std::cerr << "TeRKDriver threw exception string '" << e << "' connecting to video on " << host << " port " << port << " (attempt " << i+1 << " of " << TRIES << ")" << std::endl;
+			} catch(const char* e) {
+				std::cerr << "TeRKDriver threw exception cstring '" << e << "' connecting to video on " << host << " port " << port << " (attempt " << i+1 << " of " << TRIES << ")" << std::endl;
+			} catch(...) {
+				std::cerr << "TeRKDriver threw unknown exception connecting to video on " << host << " port " << port << " (attempt " << i+1 << " of " << TRIES << ")" << std::endl;
+			}
+			usleep(10000);
+		}
+	}
+	return qb;
+}
+
+Ice::ObjectPrx TeRKDriver::getPeerProxy(Ice::Identity proxyIdentity) const {
+	// doesn't work... ?
+	//Ice::ObjectPrx objectPrx = peerProxy->ice_getConnection()->getAdapter()->createProxy(proxyIdentity);
+	
+	// instead:
+	string port = properties->getProperty("TeRK.direct-connect.port");
+	string protocol = properties->getProperty("TeRK.direct-connect.protocol");
+	// I can't find a way to create proxies (attempt above) without using this "build a stringified command line" interface.  Sigh.
+	string proxyString = "'" + ic->identityToString(proxyIdentity) + "':" + protocol + " -h " + host + " -p " + port;
+	Ice::ObjectPrx objectPrx = ic->stringToProxy(proxyString);
+
+	// now define a custom context for interacting with this proxy
+	::Ice::Context context;
+	// not sure this first property is really necessary -- for now it's not being used.
+	// if it could be taken out, we could set the other two as the "defaultContext" and not have to make each context unique.
+	context["__peerProxyIdentity"] = ic->identityToString(objectPrx->ice_getIdentity()); // e.g. "::TeRK::TerkUser"
+	context["__peerUserId"] = uuid;
+	context["__isDirectConnect"] = "true";
+		
+	return objectPrx->ice_context(context); // get a new proxy with the specified context
+}
+
+
+
+// CONFIGURATION STUFF
+// TeRKDriver::TeRKProperties gives an Ice interface to the tekkotsu configuration system (plist)
+
+::std::string TeRKDriver::TeRKProperties::getPropertyWithDefault(const ::std::string& key, const ::std::string& def) {
+	const_iterator dit = findEntry(key);
+	if(dit!=end())
+		return dit->second->toString();
+	::Ice::PropertyDict::const_iterator it = defaults.find(key);
+	return it==defaults.end() ? def : it->second;
+}
+
+::Ice::Int TeRKDriver::TeRKProperties::getPropertyAsIntWithDefault(const ::std::string& key, ::Ice::Int def) {
+	const_iterator dit = findEntry(key);
+	if(dit!=end())
+		return dit->second->toLong();
+	::Ice::PropertyDict::const_iterator it = defaults.find(key);
+	return it==defaults.end() ? def : atoi(it->second.c_str());
+}
+
+::Ice::PropertyDict TeRKDriver::TeRKProperties::getPropertiesForPrefix(const ::std::string& prefix) {
+	::Ice::PropertyDict ans;
+	for(const_iterator it=begin(); it!=end(); ++it)
+		if(it->first.compare(0, prefix.size(), prefix) == 0)
+			ans.insert(make_pair(it->first,it->second->toString()));
+	// remember that map::insert ignores the call if it already exists...
+	// so these defaults below won't override explicitly set values which have just been added
+	for(::Ice::PropertyDict::const_iterator it=defaults.begin(); it!=defaults.end(); ++it)
+		if(it->first.compare(0, prefix.size(), prefix) == 0)
+			ans.insert(*it);
+	return ans;
+}
+
+void TeRKDriver::TeRKProperties::load(const ::std::string& filename) {
+	if(!loadFile(filename.c_str())) {
+		::Ice::FileException ex(__FILE__, __LINE__);
+		ex.path = filename;
+		ex.error = getSystemErrno();
+		throw ex;
+	}
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.12 $
+ * $State: Exp $
+ * $Date: 2007/11/11 23:57:29 $
+ */
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/DeviceDrivers/TeRKDriver.h ./local/DeviceDrivers/TeRKDriver.h
--- ../Tekkotsu_3.0/local/DeviceDrivers/TeRKDriver.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/DeviceDrivers/TeRKDriver.h	2007-11-11 18:57:29.000000000 -0500
@@ -0,0 +1,215 @@
+//-*-c++-*-
+#ifndef INCLUDED_TeRKDriver_h_
+#define INCLUDED_TeRKDriver_h_
+
+#include "local/DeviceDriver.h"
+#include "local/MotionHook.h"
+
+#include "local/terk/ObjectPingThread.h"
+#include "local/terk/QwerkBot.h"
+
+#include "IceUtil/UUID.h"
+#include "Ice/ProxyHandle.h"
+#include "Ice/Identity.h"
+
+//! Provides access to the Telepresence Robotics Kit, which specifies an ICE (Internet Communications Engine) based protocol for robotics control
+/*!
+ *  TeRK information:http://www.terk.ri.cmu.edu/
+ *  ICE information: http://www.zeroc.com/
+ *
+ *  To use this driver, you must install ICE, and cause the HAVE_ICE compiler flag to be set.
+ *  This is most easily done by the Tekkotsu Environment.conf, set the ICE_ROOT parameter to
+ *  the location of the Ice libraries.  This will automatically cause HAVE_ICE to be set by the
+ *  Makefiles whenever ICE_ROOT is a valid filesystem path.
+ */
+class TeRKDriver : public virtual DeviceDriver, public MotionHook, public virtual plist::PrimitiveListener {
+public:
+	//! constructor
+	explicit TeRKDriver(const std::string& name)
+		: DeviceDriver(autoRegisterTeRKDriver,name), MotionHook(), 
+		host(), uuid("direct_connect_client|"+IceUtil::generateUUID()), properties(), ic(), 
+		  ping(), qwerk(NULL), idcount(0)
+	{
+		for(unsigned int i=0; i<NumLEDs; ++i)
+			ledActivation[i]=0;
+		TeRKProperties* tprop = new TeRKProperties;
+		addEntry("Host",host,"Hostname of the robot");
+		//addEntry("Port",port,"Port number of the robot's ICE server");
+		addEntry("IceConfig",*tprop,"Settings for ICE protocol");
+		Ice::InitializationData iceData;
+		iceData.properties = properties = tprop;
+		ic = Ice::initialize(iceData);
+		host.addPrimitiveListener(this);
+	}
+	
+	//! destructor
+	virtual ~TeRKDriver() {
+		host.removePrimitiveListener(this);
+		close();
+		if(ic)
+			ic->destroy();
+		// don't need to delete properties, smart pointer
+	}
+
+	virtual std::string getClassName() const { return autoRegisterTeRKDriver; }
+
+	virtual MotionHook* getMotionSink() { return dynamic_cast<MotionHook*>(this); }
+	virtual void getSensorSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		if(qwerk!=NULL && qwerk->dataCache!=NULL)
+			sources["Sensors"]=qwerk->dataCache;
+	}
+	virtual void getImageSources(std::map<std::string,DataSource*>& sources) {
+		sources.clear();
+		if(qwerk!=NULL && qwerk->imageCache!=NULL)
+			sources["Camera"]=qwerk->imageCache;
+	}
+	
+	virtual void motionStarting() {}
+	virtual void motionUpdated(const std::vector<size_t>& changedIndices, const float outputs[][NumOutputs]);
+	virtual void motionStopping() {}
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+
+	//! creates a proxy for a specified service
+	/*! @todo import QwerkBot and make this protected?) */
+	Ice::ObjectPrx getPeerProxy(Ice::Identity proxyIdentity) const;
+	
+	//! hostname of the qwerk we are connecting to.
+	plist::Primitive<std::string> host;
+	
+protected:
+	//! connect to qwerk
+	virtual void connect();
+
+	//! initializes a connection to #host
+	QwerkBot* connectToPeer();
+	
+	//! closes the current proxies (reuses the communicator instance though)
+	virtual void close() {
+		if(ping){
+			ping->destroy();
+			ping=NULL;
+		}
+		delete qwerk;
+		qwerk=NULL;
+	}
+	
+	//! allows LEDs to flicker at various frequencies to emulate having linear brightness control instead of boolean control
+	inline ::TeRK::LEDMode calcLEDValue(unsigned int i,float x) {
+		if(x<=0.0) {
+			ledActivation[i]*=.9; //decay activation... resets to keeps LEDs in sync, looks a little better
+			return ::TeRK::LEDOff;
+		} else if(x>=1.0) {
+			return ::TeRK::LEDOn;
+		} else {
+			x*=x; // squared to "gamma correct" - we can see a single pulse better than a single flicker - after image and all that
+			ledActivation[i]+=x;
+			if(ledActivation[i]>=1.0) {
+				ledActivation[i]-=1.0;
+				return ::TeRK::LEDOn;
+			} else {
+				return ::TeRK::LEDOff;
+			}
+		}
+	}
+	float ledActivation[NumLEDs]; //!< used to track partial LED activation (see calcLEDValue
+	
+	//! unique identifier, should be different for every active connection
+	/*! This will be constant for the lifetime of the TeRKDriver, as we only ever have one
+	 *  active connection per driver instance.  (If more than one instance, each will have
+	 *  its own uuid however!) */
+	std::string uuid;
+	
+	//! TeRKProperties instance provides Ice configuration values, default values for which are in TeRKDriver.cc.
+	/*! These aren't really user-configurable settings, but are exposed via a Tekkotsu plist entry. */
+	Ice::PropertiesPtr properties;
+	
+	//! The core Ice object, which manages connections, proxies, adapters, etc.
+	/*! We create one instance and reuse it over the life of the driver.
+	 *  (In other words, we shouldn't need to delete/reallocate it every time we
+	 *  switch hosts, although if that winds up being easier, we could certainly
+	 *  do that instead) */
+	Ice::CommunicatorPtr ic;
+	
+	//! tests to make sure the remote host is still alive
+	/*! @todo do we do anything if the remote host goes down? */
+	ObjectPingThreadPtr ping;
+	
+	//! storage class holds proxies for various TeRK services.
+	/*! @todo should be imported and stored directly in driver? */
+	QwerkBot* qwerk;
+		
+  int idcount;
+	//! Grafts a Ice::Properties interface on a plist::Dictionary so we can use the Tekkotsu configuration system to control ICE
+	/*! The constructor assigns various default values to #defaults - these will be used
+	 * unless a value is found in the plist::Dictionary storage.  We keep these values
+	 * separate because they shouldn't be written to persistent storage unless explicitly
+	 * set.  (Default values may change in the future, could break things if the defaults
+	 * were written to file... most of these values are not really configurable by end user) */
+	class TeRKProperties : public virtual ::Ice::Properties, public virtual plist::Dictionary {
+	public:
+		typedef ::Ice::PropertiesPtr PointerType; //!< forwarding typedef for good form
+		typedef plist::Dictionary::iterator iterator; //!< forwarding typedef for good form
+		typedef plist::Dictionary::const_iterator const_iterator; //!< forwarding typedef for good form
+		
+		//! constructor, initialize #defaults from #defaultValues (C++0x will make this much more elegant!)
+		TeRKProperties() : defaults(defaultValues, defaultValues+NUM_DEFAULT_VALUES) {}
+		
+		//! These provide the TeRK configuration parameters for ICE communication, unless overridden by a setting in the class itself (see class notes)
+		/*! These may be changed from the initial #defaultValues settings if a corresponding
+		 *  TeRKDriver setting (e.g. port) is modified.  This is to avoid user confusion with having
+		 *  settings appear twice (once in the more human-readable driver settings, and again
+		 *  in this dictionary.)  So settings stored in TeRKProperties itself is reserved for explicit
+		 *  overrides from the user */
+		::Ice::PropertyDict defaults;
+		
+		//! returns value associated with @a key, or empty string if not found
+		virtual ::std::string getProperty(const ::std::string& key) { return getPropertyWithDefault(key,""); }
+		//! returns value associated with @a key, or @a def if not found
+		virtual ::std::string getPropertyWithDefault(const ::std::string& key, const ::std::string& def);
+		//! returns value associated with @a key, or 0 if not found
+		virtual ::Ice::Int getPropertyAsInt(const ::std::string& key) { return getPropertyAsIntWithDefault(key,0); }
+		//! returns value associated with @a key, or @a def if not found
+		virtual ::Ice::Int getPropertyAsIntWithDefault(const ::std::string& key, ::Ice::Int def);
+		//! returns a sub-map, selecting keys which match the specified prefix
+		virtual ::Ice::PropertyDict getPropertiesForPrefix(const ::std::string& prefix);
+		//! assigns a new value to a @a key
+		virtual void setProperty(const ::std::string& key, const ::std::string& val) { setEntry(key,new plist::Primitive<std::string>(val)); }
+		//! returns an empty sequence
+		virtual ::Ice::StringSeq getCommandLineOptions() { return ::Ice::StringSeq(); }
+		//! returns the same sequence it is passed (doesn't handle parsing command line options, we're not using that interface)
+		virtual ::Ice::StringSeq parseCommandLineOptions(const ::std::string&, const ::Ice::StringSeq& options) { return options; }
+		//! returns the same sequence it is passed (doesn't handle parsing command line options, we're not using that interface)
+		virtual ::Ice::StringSeq parseIceCommandLineOptions(const ::Ice::StringSeq& options) { return options; }
+		//! tries to load the specified file name (assumes plist format, not the ICE format!)
+		virtual void load(const ::std::string& filename);
+		//! makes a copy of the current property list
+		virtual ::Ice::PropertiesPtr clone() { return new TeRKProperties(*this); }
+		virtual TeRKProperties* clone() const { return new TeRKProperties(*this); }
+		
+	protected:
+		static const unsigned int NUM_DEFAULT_VALUES=14;
+		static std::pair<std::string,std::string> defaultValues[NUM_DEFAULT_VALUES];
+	};
+	
+private:
+	//! holds the class name, set via registration with the DeviceDriver registry
+	static const std::string autoRegisterTeRKDriver;
+
+	TeRKDriver(const TeRKDriver&); //!< do not call
+	TeRKDriver& operator=(const TeRKDriver&); //!< do not call
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.13 $
+ * $State: Exp $
+ * $Date: 2007/11/11 23:57:29 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/LoadDataThread.cc ./local/LoadDataThread.cc
--- ../Tekkotsu_3.0/local/LoadDataThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/LoadDataThread.cc	2007-10-12 12:55:04.000000000 -0400
@@ -0,0 +1,351 @@
+#include "LoadDataThread.h"
+#include "Shared/get_time.h"
+#include "Shared/debuget.h"
+#include <sys/stat.h>
+#include <regex.h>
+#include <dirent.h>
+#include <set>
+#include <errno.h>
+
+using namespace std;
+
+// allocated here to avoid creating otherwise empty DataSource.cc
+unsigned int * DataSource::providedOutputs=NULL;
+bool DataSource::requiresFirstSensor=false;
+
+LoadDataThread::~LoadDataThread() {
+	MarkScope l(lock);
+	DeviceDriver::getRegistry().removeCollectionListener(this);
+	framerate.removePrimitiveListener(this);
+	verbose.removePrimitiveListener(this);
+	frozen.removePrimitiveListener(this);
+	while(regions.size()>0) {
+		freeRegion(regions.front());
+		regions.pop_front();
+	}
+}
+
+bool LoadDataThread::advanceFrame(bool forceQueue) {
+	MarkScope l(lock);
+	if(frozen && !forceQueue || curDS==NULL) {
+		if(heartbeat)
+			sendHeartbeat();
+		return false;
+	}
+	
+	// check to see if runloop has a frame in progress -- send that one ASAP, don't cut line
+	if(runloopState==GET_FRAME) {
+		runloopState=ADVANCE_FRAME;
+		return true;
+	} else if(runloopState==GOT_FRAME) {
+		runloopState=ADVANCE_FRAME;
+		interrupt(); //break out of sleep
+		return true;
+	}
+	
+	//! safe to force the next frame ourselves
+	const char* payload;
+	unsigned int sz;
+	unsigned int advTime = get_time();
+	unsigned int timestamp = (forceQueue ? 0 : advTime);
+	std::string name;
+	unsigned int sn=curDS->getData(payload, sz, timestamp, name);
+	if(payload==NULL) {
+		if(heartbeat)
+			sendHeartbeat();
+		return false;
+	} else {
+		if(verbose>=1 && sn!=sourceSN+1 && sourceSN!=0)
+			std::cout << "Data Source dropped " << (sn-sourceSN-1) << " frames"  << std::endl;
+		sourceSN=sn;
+	}
+	if(verbose>=2)
+		std::cout << "Advancing frame: \"" << name << "\" (advanced at " << advTime << ')' << std::endl;
+	RCRegion * r=firstUnusedRegion();
+	char * buf=setupRegion(r,name,sz,curDS->nextTimestamp()!=-1U);
+	ASSERTRETVAL(buf!=NULL,"setupRegion returned null region",false);
+	memcpy(buf,payload,sz);
+	msgr.sendMessage(r);
+	regions.push_back(r);
+	lastSent=advTime;
+	return true;
+}
+
+void LoadDataThread::plistValueChanged(const plist::PrimitiveBase& pl) {
+	MarkScope l(lock);
+	if(&pl==&source) {
+		std::string::size_type dot=source.find('.');
+		DeviceDriver* dd=DeviceDriver::getRegistry().getInstance(source.substr(0,dot));
+		if(dd==NULL) {
+			if(source.size()!=0)
+				std::cerr << "Could not find driver named '" << source << "' for LoadDataThread" << std::endl;
+			setDataSource(dd, NULL);
+		} else {
+			std::map<std::string,DataSource*> dsmap;
+			(dd->*getDataSources)(dsmap);
+			if(dsmap.size()==0)
+				setDataSource(dd, NULL);
+			else if(dot==std::string::npos)
+				setDataSource(dd, dsmap.begin()->second);
+			else {
+				std::map<std::string,DataSource*>::const_iterator ds=dsmap.find(source.substr(dot+1));
+				setDataSource(dd, ds==dsmap.end() ? NULL : ds->second);
+			}
+		}
+	} else if(&pl==&framerate) {
+		if(curDS!=NULL)
+			curDS->setDataSourceFramerate(framerate);
+	} else if(&pl==&verbose) {
+		msgr.setReportDroppings(verbose>=1);
+		if(curDS!=NULL)
+			curDS->setDataSourceVerbose(verbose);
+	} else if(&pl==&frozen) {
+		if(curDS!=NULL)
+			curDS->setFrozen(frozen);
+		if(enabled) {
+			if(!frozen) {
+				start();
+			} else if(isStarted() && !heartbeat) {
+				stop();
+				enabled=true; // retain enabled setting
+			}
+		}
+	} else if(&pl==&heartbeat) {
+		if(enabled) {
+			if(heartbeat) {
+				start();
+			} else if(isStarted() && frozen) {
+				stop();
+				enabled=true; // retain enabled setting
+			}
+		}
+	} else {
+		cerr << "LoadDataThread didn't handle call to plistValueChanged for " << pl.get() << endl;
+	}
+}
+
+void LoadDataThread::start() {
+	enabled=true;
+	if(!isStarted() && getTimeScale()>0 && (!frozen || heartbeat) )
+		PollThread::start();
+}
+void LoadDataThread::stop() {
+	enabled=false;
+	runloopState=INTERFRAME;
+	PollThread::stop();
+}
+
+RCRegion* LoadDataThread::firstUnusedRegion() {
+	for(msgbuf_t::iterator it=regions.begin();it!=regions.end(); ++it) {
+		if((*it)->NumberOfReference()==1) {
+			RCRegion * ans=*it;
+			regions.erase(it);
+			return ans;
+		}
+	}
+	return NULL;
+}
+
+char* LoadDataThread::setupRegion(RCRegion*& region, const std::string& filename, unsigned int payload, bool hasMoreData) {
+	// header fields: bool:verbose, uint:frameSN, str:filename, uint:payload
+	const unsigned int FILE_HEADER_SIZE=LoadSave::getSerializedSize<unsigned int>() + LoadSave::getSerializedSize(frameSN) + LoadSave::getSerializedSize(filename) + LoadSave::getSerializedSize<bool>() + LoadSave::getSerializedSize(payload);
+	if(region==NULL)
+		region=new RCRegion(FILE_HEADER_SIZE+payload+sizeof(char)*filename.size()*2); //triple the allocation for filename so we don't have to resize if we get a longer name later
+	else if(region->Size()<FILE_HEADER_SIZE+payload) {
+		//too small -- free it, we'll drop it and make a bigger one
+		freeRegion(region);
+		region=new RCRegion(FILE_HEADER_SIZE+payload+sizeof(char)*filename.size()*2); //triple the allocation for filename so we don't have to resize if we get a longer name later
+	}
+	char* buf=region->Base();
+	unsigned int remain=FILE_HEADER_SIZE;
+	if(!LoadSave::encodeInc((unsigned int)verbose,buf,remain)) return NULL;
+	if(!LoadSave::encodeInc(frameSN++,buf,remain)) return NULL;
+	if(!LoadSave::encodeInc(filename,buf,remain)) return NULL;
+	if(!LoadSave::encodeInc(hasMoreData,buf,remain)) return NULL;
+	if(!LoadSave::encodeInc(payload,buf,remain)) return NULL;
+	ASSERT(remain==0,"LoadDataThread::setupRegion(): Leftover bytes in header? FILE_HEADER_SIZE is wrong\n");
+	return buf;
+}
+
+char* LoadDataThread::deserializeHeader(char* buf, unsigned int size, unsigned int* verbose, unsigned int* sn, std::string* filename, bool* dataInQueue, unsigned int* payloadSize) {
+	if(verbose!=NULL) { if(!LoadSave::decodeInc(*verbose,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*verbose);
+	if(sn!=NULL) { if(!LoadSave::decodeInc(*sn,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*sn);
+	if(filename!=NULL) { if(!LoadSave::decodeInc(*filename,buf,size)) return NULL; } else {
+		unsigned int len=0;
+		if(!LoadSave::decodeInc(len,buf,size)) return NULL;
+		buf+=len+1;
+	}
+	if(dataInQueue!=NULL) { if(!LoadSave::decodeInc(*dataInQueue,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*dataInQueue);
+#ifndef DEBUG
+	if(payloadSize!=NULL) { if(!LoadSave::decodeInc(*payloadSize,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*payloadSize);
+#else
+	unsigned int lPayloadSize; // want to error check payloadSize regardless of whether caller wants the info
+	if(payloadSize==NULL)
+		payloadSize=&lPayloadSize;
+	if(!LoadSave::decodeInc(*payloadSize,buf,size)) return NULL;
+	ASSERT(size>=*payloadSize,"short payload (" << size << " vs expected " << *payloadSize << ")");
+	// this is normal (regions are generated a little bigger than they need to be to allow recycling)
+	//ASSERT(size<=*payloadSize,"unhandled bytes after payload (" << size << " vs expected " << *payloadSize << ")");
+#endif
+	return buf;
+}
+
+void LoadDataThread::sendHeartbeat(unsigned int curt) {
+	RCRegion *unused=firstUnusedRegion();
+	char * buf=setupRegion(unused,"heartbeat",0,curDS!=NULL && curDS->nextTimestamp()!=-1U);
+	if(unused==NULL || buf==NULL)
+		return;
+	if(verbose>=3)
+		std::cout << "Sending heartbeat at " << curt << std::endl;
+	msgr.sendMessage(unused);
+	regions.push_back(unused);
+	lastSent=curt;
+}
+
+unsigned int LoadDataThread::calcNextHeartbeat(unsigned int curt) const {
+	unsigned int skip=static_cast<unsigned int>((curt-lastSent)*framerate/1000);
+	return static_cast<unsigned int>(lastSent+(skip+1)*1000.f/framerate);
+}
+
+std::string LoadDataThread::getAvailableDataSources() {
+	std::string str;
+	for(DeviceDriver::registry_t::const_iterator dit=DeviceDriver::getRegistry().begin(); dit!=DeviceDriver::getRegistry().end(); ++dit) {
+		DeviceDriver * dd=DeviceDriver::getRegistry().getInstance(dit->first);
+		if(dd!=NULL) {
+			std::map<std::string,DataSource*> srcmap;
+			(dd->*getDataSources)(srcmap);
+			for(std::map<std::string,DataSource*>::const_iterator sit=srcmap.begin(); sit!=srcmap.end(); ++sit)
+				str+=dit->first+'.'+sit->first+' ';
+		}
+	}
+	std::string sourcehelp="Names a DeviceDriver instance from which data will be taken.\n"
+		"Can be either just the driver name (use first data source), or 'DriverName.QueueName'.\n"
+		"Available data sources: ";
+	if(str.size()==0)
+		sourcehelp+="(none available, see 'new' command to instantiate drivers)";
+	else
+		sourcehelp+=str;
+	setComment("Source",sourcehelp);
+	if(str.size()>0) // we actually want the extra space at the end in the plist::Dictionary comments, but we'll remove it before we return
+		str.resize(str.size()-1);
+	plistValueChanged(source); // check that our source is still valid (or if it wasn't valid, perhaps now it is)
+	return str;
+}
+
+void LoadDataThread::setDataSource(DeviceDriver* dd, DataSource* ds) {
+	if(curDS==ds && dsDriver==dd)
+		return;
+	if(dsDriver!=NULL)
+		dsDriver->removeSourceListener(this);
+	if(dd!=NULL)
+		dd->addSourceListener(this);
+	dsDriver=dd;
+	if(curDS!=NULL) {
+		curDS->setDataSourceThread(NULL);
+		curDS=NULL;
+		if(isStarted()) {
+			stop();
+			enabled=true; // retain enabled setting
+			for(unsigned int checks=0; checks<8 && isStarted(); checks++)
+				usleep(250*1000);
+			if(isStarted()) {
+				cerr << "Trying to close LoadDataThread's data source, looks like it's blocked, killing..." << endl;
+				kill();
+				join();
+			}
+		}
+	}
+	curDS=ds;
+	sourceSN=0;
+	lastSent=-1;
+	if(curDS!=NULL) {
+		curDS->setDataSourceThread(this);
+		curDS->setDataSourceVerbose(verbose);
+		curDS->setDataSourceFramerate(framerate);
+		curDS->setFrozen(frozen);
+		if(enabled)
+			start();
+	}
+}
+
+unsigned int LoadDataThread::runloop() {
+	float nextT = (lastSent<0) ? get_time() : (lastSent+1000.f/framerate);
+	const char* payload;
+	unsigned int sz;
+	unsigned int timestamp=static_cast<unsigned int>(nextT+.5f);
+	std::string name;
+	{
+		MarkScope l(lock);
+		unsigned int curt=get_time();
+		if(frozen || curDS==NULL) {
+			if(heartbeat && curt>=nextT)
+				sendHeartbeat(curt);
+			return calcSleepTime();
+		}
+		runloopState=GET_FRAME;
+	}
+	unsigned int sn=curDS->getData(payload, sz, timestamp, name);
+	if(curDS==NULL) // broke out, our source has been marked invalid by another thread
+		return -1U;
+	unsigned int curt;
+	if(payload!=NULL) {
+		if(verbose>=1 && sn!=sourceSN+1 && sourceSN!=0)
+			std::cout << "Data Source dropped " << (sn-sourceSN-1) << " frames"  << std::endl;
+		sourceSN=sn;
+		// if we have a payload and timestamp is still in the future, wait for it
+		{
+			MarkScope l(lock); // don't hold lock throughout sleep, just on updating runloopState
+			runloopState=GOT_FRAME;
+		}
+		while(timestamp>(curt=get_time()) && runloopState!=ADVANCE_FRAME) {
+			//cout << "size " << sz << " timestamp " << timestamp << " vs " << curt << " name " << name << endl;
+			int res=usleep(static_cast<unsigned int>((timestamp-curt)*1000/getTimeScale()));
+			if(res!=0) {
+				if(errno==EINTR && runloopState==ADVANCE_FRAME) {
+					break;
+				} else {
+					perror("LoadDataThread::runloop() nanosleep");
+					break;
+				}
+			}
+		}
+	}
+	{
+		MarkScope l(lock);
+		curt=get_time(); //recheck time, lock might've taken a while
+		if(payload==NULL) {
+			if(heartbeat && curt>=nextT)
+				sendHeartbeat(curt);
+			runloopState=INTERFRAME;
+			return calcSleepTime();
+		}
+		if(verbose>=2)
+			std::cout << "Sending frame: \"" << name << "\" (req. " << static_cast<unsigned int>(nextT+.5f) << ", sched. " << timestamp << ", now " << curt << ')' << std::endl;
+		RCRegion * r=firstUnusedRegion();
+		char * buf=setupRegion(r,name,sz,curDS->nextTimestamp()!=-1U);
+		ASSERTRETVAL(buf!=NULL,"setupRegion returned null region",false);
+		memcpy(buf,payload,sz);
+		//if(sz < 1024)
+		//	cout << "size: " << sz << " payload:" << payload << endl;
+		msgr.sendMessage(r);
+		regions.push_back(r);
+		if(curt - nextT > 1000.f/framerate*5)
+			lastSent=curt; // apparently can't keep up, don't let requested time fall ridiculously behind...
+		else
+			lastSent=nextT;
+		runloopState=INTERFRAME;
+		return 0;
+	}
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.18 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:55:04 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/LoadDataThread.h ./local/LoadDataThread.h
--- ../Tekkotsu_3.0/local/LoadDataThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/LoadDataThread.h	2007-11-09 14:01:15.000000000 -0500
@@ -0,0 +1,175 @@
+//-*-c++-*-
+#ifndef INCLUDED_LoadDataThread_h_
+#define INCLUDED_LoadDataThread_h_
+
+#include "IPC/PollThread.h"
+#include "Shared/plist.h"
+#include "IPC/MessageQueue.h"
+#include "Shared/get_time.h"
+#include "local/DeviceDriver.h"
+#include "local/DataSource.h"
+#include <list>
+#include <vector>
+
+//! Provides resources for loading time-based data from disk
+/*! Runs in a separate thread, preloads data into shared memory buffers, and
+ *  then sends the buffer when the time is right.  Thread doesn't start until
+ *  you set the source or call loadFileList(). */
+class LoadDataThread : public virtual PollThread, public virtual plist::Dictionary, public virtual plist::PrimitiveListener, public virtual plist::CollectionListener, public virtual DeviceDriver::SourceListener {
+public:
+	//! member function pointer to call on DeviceDriver to get the data sources available for this thread
+	typedef void (DeviceDriver::*getDataSources_t)(std::map<std::string,DataSource*>&);
+
+	
+	//! constructor
+	/*! @param getDS a DeviceDriver member function callback, which will be used to query drivers for the data sources of they type being loaded by this thread
+	 *  @param fps frames per second, see #framerate
+	 *  @param messages the MessageQueue through which to send the data
+	 *
+	 *  For example, there are sensor sources and camera/image sources, each managed by a
+	 *  different function of DeviceDriver (DeviceDriver::getSensorSources vs. DeviceDriver::getImageSources).
+	 *  The LoadDataThread is initialized to call one of these functions to acquire data sources
+	 *  based on which driver is referenced by #source.
+	 */
+	LoadDataThread(getDataSources_t getDS, float fps, MessageQueueBase& messages)
+	: PollThread(), plist::Dictionary(),
+		source(), framerate(fps), verbose(0), heartbeat(true), frozen(false),
+		regions(), getDataSources(getDS), msgr(messages), lock(), lastSent(-1), frameSN(0), sourceSN(0), enabled(false), runloopState(INTERFRAME),
+		curDS(NULL), dsDriver(NULL)
+	{
+		setLoadSavePolicy(FIXED,SYNC);
+		addEntry("Source",source); getAvailableDataSources(); // getAvailableDataSources sets #source comment string
+		addEntry("Framerate",framerate,"The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.");
+		addEntry("Verbose",verbose,"Controls how much feedback to give on the console regarding progress\n  0 - none\n  1 - report when messages are dropped\n  2 - also report when a message is sent\n  3 - also report when heartbeat is sent/dropped, and when loop occurs\n  4 - also report when each message is preloaded");
+		addEntry("Heartbeat",heartbeat,"If enabled, an empty \"heartbeat\" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.");
+		addEntry("Frozen",frozen,"If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically");
+		source.addPrimitiveListener(this); // call setDataSource when the source changes
+		framerate.addPrimitiveListener(this); // update data source's framerate
+		verbose.addPrimitiveListener(this); // set msgr report droppings and update data source's verbosity
+		heartbeat.addPrimitiveListener(this); // start/stop thread if frozen
+		frozen.addPrimitiveListener(this); // update current source, start/stop the thread
+		DeviceDriver::getRegistry().addCollectionListener(this);
+	}
+	//! destructor
+	~LoadDataThread();
+	
+	//! Names the device driver from which the DataSource will be taken
+	/*! If you simply provide a device driver name, the first entry of the appropriate data queue will be used.
+	 *  Alternatively, use drivername.entryname to specify a specific data source entry in case the driver
+	 *  has multiple data sources for the queue type. */
+	plist::Primitive<std::string> source;
+	
+	//! frames per second to send -- this is only a suggestion to hardware devices, which generally use their 'native' framerate, but may use this to limit data flow
+	plist::Primitive<float> framerate;
+
+	//! Controls how much feedback to give on the console regarding progress
+	/*! 0 - none\n
+	 *  1 - report when message is sent\n
+	 *  2 - also report when message is dropped\n
+	 *  3 - also report when heartbeat is sent/dropped, and when loop occurs\n
+	 *  4 - also report when each message is preloaded */
+	plist::Primitive<int> verbose; 
+
+	//! if enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. no data loaded or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.
+	plist::Primitive<bool> heartbeat;
+	
+	//! if true, no frames will be sent, except via explicit (external) calls to advanceFrame(); if false, the thread will run and send messages at the requested times
+	plist::Primitive<bool> frozen;
+	
+	//! sends the next frame as soon as possible, blocking until sent
+	/*! @param forceQueue pass true to force a new data frame to be sent, otherwise will send a heartbeat if frozen
+	 * @return true if there was a frame to send; will send heartbeat if configured, but returns false for heartbeats */
+	virtual bool advanceFrame(bool forceQueue);
+
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	virtual void plistCollectionEntryAdded(Collection& /*col*/, ObjectBase& /*primitive*/) { getAvailableDataSources(); }
+	virtual void plistCollectionEntryRemoved(Collection& /*col*/, ObjectBase& /*primitive*/) { getAvailableDataSources(); }
+	virtual void plistCollectionEntriesChanged(Collection& /*col*/) { getAvailableDataSources(); }
+	virtual void start();
+	virtual void stop();
+		
+	//! recovers data from serialized IPC message, returns beginning of payload, or NULL if there's an error
+	/*! each parameter can be a pointer where to store the field, or NULL if you don't care */
+	static char* deserializeHeader(char* buf, unsigned int size, unsigned int* verbose, unsigned int* sn, std::string* filename, bool* dataInQueue, unsigned int* payloadSize);
+
+	virtual unsigned int nextTimestamp() { return (curDS!=NULL) ? curDS->nextTimestamp() : -1U; }
+	virtual const std::string& nextName() { return (curDS!=NULL) ? curDS->nextName() : emptyStr(); }
+	
+	virtual DataSource* getDataSource() { return curDS; } //!< returns #curDS
+	
+	virtual void dataSourcesUpdated() { plistValueChanged(source); }
+	
+	//! called from constructor to build list of available data source names, resets the #source help text
+	std::string getAvailableDataSources();
+	
+	virtual void loadXML(xmlNode* node) {
+		plist::Dictionary::loadXML(node);
+		getAvailableDataSources();
+	}
+	
+protected:
+	//! Makes a data source eligible for providing data
+	/*! This is protected because you shouldn't be calling it directly.  Instead, set #source to the driver instance name, which will cause this to be called via plistValueChanged */
+	virtual void setDataSource(DeviceDriver* dd, DataSource* ds);
+	
+	//! monitor #msgr, send new messages when their timestamp indicates they are due, then load upcoming messages
+	virtual unsigned int runloop();
+
+	//! removes and returns first region in #regions with only one reference, or NULL if none exists
+	virtual RCRegion* firstUnusedRegion();
+	
+	//! sets up some header info in the specified RCRegion, reallocating if the suggested region is not large enough (or is NULL), returns pointer to end of header info in the region
+	virtual char* setupRegion(RCRegion*& region, const std::string& file, unsigned int payload, bool hasMoreData);
+
+	//! removes our reference to a region created by loadFile()
+	virtual void freeRegion(RCRegion* rcr) { if(rcr!=NULL) rcr->RemoveReference(); }
+	
+	//! sends an empty heartbeat message indicating previous data should be reused
+	virtual void sendHeartbeat() { sendHeartbeat(get_time()); }
+	//! sends an empty heartbeat message indicating previous data should be reused, assuming that curt is the current time
+	virtual void sendHeartbeat(unsigned int curt);
+	
+	//! returns time of next heartbeat
+	unsigned int calcNextHeartbeat(unsigned int curt) const;
+	
+	unsigned int calcSleepTime() { unsigned int curt=get_time(); return static_cast<unsigned int>((calcNextHeartbeat(curt)-curt)/getTimeScale()); }
+	
+	typedef std::list<RCRegion* > msgbuf_t; //!< type of collection of shared data regions
+	msgbuf_t regions; //!< for efficiency, reuse old buffers -- oldest at front, most recently used at back
+	
+	//! member function pointer to be called on DeviceDriver to get its available data sources
+	getDataSources_t getDataSources;
+	
+	MessageQueueBase& msgr; //!< the MessageQueue through which to send the data
+	Thread::Lock lock; //!< allows mutual exclusion over this object's member variables
+	float lastSent; //!< timestamp of most recently sent message (or heartbeat); -1 if hasn't sent any from current source
+	unsigned int frameSN; //!< serial number of next message to send
+	unsigned int sourceSN; //!< serial number of the last data from #curDS; 0 if hasn't received any from current source
+	bool enabled; //!< set to true by start(), false by stop(), but reset if we call start or stop ourselves based on changes to freeze or heartbeat
+	volatile enum {
+		INTERFRAME, //!< runloop() is waiting between frames (usually heartbeats)
+		GET_FRAME, //!< runloop() is getting a frame, should not be interrupted
+		GOT_FRAME, //!< runloop() has gotten a frame and is waiting until its timestamp has arrived
+		ADVANCE_FRAME //!< runloop() was in GOT_FRAME, but advanceFrame() was called, frame should be sent *now*
+	} runloopState;
+	
+	DataSource * curDS; //!< pointer to the current data source
+	DeviceDriver * dsDriver; //!< pointer to the data source's driver
+	
+private:
+	LoadDataThread(const LoadDataThread&); //!< do not call
+	LoadDataThread& operator=(const LoadDataThread&); //!< do not call
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.16 $
+ * $State: Exp $
+ * $Date: 2007/11/09 19:01:15 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/LoadFileThread.cc ./local/LoadFileThread.cc
--- ../Tekkotsu_3.0/local/LoadFileThread.cc	2006-09-28 16:42:51.000000000 -0400
+++ ./local/LoadFileThread.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,643 +0,0 @@
-#include "LoadFileThread.h"
-#include "Shared/get_time.h"
-#include "Shared/debuget.h"
-#include <sys/stat.h>
-#include <regex.h>
-#include <dirent.h>
-#include <set>
-
-using namespace std;
-
-LoadFileThread::~LoadFileThread() {
-	MarkScope l(lock);
-	src.removePrimitiveListener(this);
-	verbose.removePrimitiveListener(this);
-	while(sent.size()>0) {
-		freeRegion(sent.front());
-		sent.pop_front();
-	}
-	while(loaded.size()>0) {
-		freeRegion(loaded.front());
-		loaded.pop_front();
-	}
-	timestamps.clear();
-}
-
-void LoadFileThread::loadFileList(bool clearCurrent/*=true*/, bool reportMissing/*=true*/) {
-	MarkScope l(lock);
-	struct stat sb;
-	if(clearCurrent) {
-		files.clear();
-		curfile=files.begin(); // aka files.end()
-		if(loaded.size()>0 && loaded.front()!=NULL)
-			frameSN=recoverSN(loaded.front());
-		while(loaded.size()>0) {
-			if(loaded.back()!=NULL)
-				sent.push_front(loaded.back());
-			loaded.pop_back();
-			timestamps.pop_back();
-		}
-	}
-	isIndexed=false;
-	if(stat(src.c_str(),&sb)) {
-		if(reportMissing)
-			std::cerr << "Could not access source " << src << std::endl;
-		return;
-	}
-	if(sb.st_mode&S_IFDIR) {
-		loadFileListFromDirectory();
-	} else {
-		//Test to see if the file matches the filter
-		regex_t re;
-		if(int err=regcomp(&re,filenameFilter.c_str(),REG_EXTENDED | REG_NOSUB)) {
-			char msg[128];
-			regerror(err,&re,msg,128);
-			std::cerr << "Bad filter '" << filenameFilter << "': " << msg << std::endl;
-			regfree(&re);
-			return;
-		}
-		int match=regexec(&re,src.c_str(),0,NULL,0);
-		regfree(&re);
-		if(match==0) {
-			loadSingleFile(src.c_str());
-		} else if(match==REG_NOMATCH) {
-			//if it doesn't match the image RE, assume it's an index file
-			if(!loadFileListFromIndex())
-				std::cerr << "Source '" << src << "' does not match the filename filter '" << filenameFilter << "' and is not an index list." << std::endl;
-			else
-				isIndexed=true;
-		} else {
-			char msg[128];
-			regerror(match,&re,msg,128);
-			std::cerr << "Regex error on '" << src << "': " << msg << std::endl;
-		}
-	}
-	if(clearCurrent)
-		setFrame(0);
-	else
-		curfile=files.begin(); //curfile may have been invalidated, getNextData will fast forward to current time
-	for(unsigned int i=0; i<NUM_PRELOAD && curfile!=files.end(); ++i)
-		updateLoaded(get_time());
-}
-
-void LoadFileThread::setFrame(unsigned int f) {
-	MarkScope l(lock);
-	loopRemainder=0;
-	startTimeOffset=(int)(get_time()-f*1000/framerate);
-	resetTimeOffset(startTimeOffset);
-	curfile=files.begin();
-	advance(curfile,f);
-}
-
-void LoadFileThread::loadSingleFile(const std::string& file) {
-	MarkScope l(lock);
-	files[(unsigned int)calcLoopTime()]=file;
-}
-
-void LoadFileThread::loadFileListFromDirectory() {
-	MarkScope l(lock);
-	regex_t re;
-	if(int err=regcomp(&re,filenameFilter.c_str(),REG_EXTENDED | REG_NOSUB)) {
-		char msg[128];
-		regerror(err,&re,msg,128);
-		std::cerr << "Bad filter '" << filenameFilter << "': " << msg << std::endl;
-		regfree(&re);
-		return;
-	}
-	DIR * d=opendir(src.c_str());
-	if(d==NULL) {
-		std::cerr << "Could not open directory " << src << std::endl;
-		regfree(&re);
-		return;
-	}
-	struct dirent* res;
-	
-#ifdef HAVE_READDIR_R
-	struct dirent cur;
-	if(readdir_r(d,&cur,&res)) {
-		std::cerr << "Error reading files from " << src << std::endl;
-		closedir(d);
-		regfree(&re);
-		return;
-	}
-#else
-	res=readdir(d);
-#endif
-
-	std::set<std::string> dirfiles;
-	while(res!=NULL) {
-		int match=regexec(&re,res->d_name,0,NULL,0);
-		if(match==0) {
-			dirfiles.insert(res->d_name);
-		} else if(match!=REG_NOMATCH) {
-			char msg[128];
-			regerror(match,&re,msg,128);
-			std::cerr << "Regex error on '" << res->d_name << "': " << msg << std::endl;
-		} // else std::cout << "Skipping " << res->d_name << std::endl;
-#ifdef HAVE_READDIR_R
-		if(readdir_r(d,&cur,&res)) {
-			std::cerr << "Error reading files from " << src << std::endl;
-			closedir(d);
-			regfree(&re);
-			return;
-		}
-#else
-		res=readdir(d);
-#endif
-	}
-	closedir(d);
-	regfree(&re);
-	
-	float tinc=1000.f/framerate;
-	float time=calcLoopTime();
-	for(std::set<std::string>::const_iterator it=dirfiles.begin(); it!=dirfiles.end(); ++it) {
-		//std::cout << "Enqueuing " << *it << std::endl;
-		files[static_cast<unsigned int>(time)]=(src+"/")+(*it);
-		time+=tinc;
-	}
-}
-
-bool LoadFileThread::loadFileListFromIndex() {
-	regex_t re;
-	if(int err=regcomp(&re,filenameFilter.c_str(),REG_EXTENDED | REG_NOSUB)) {
-		char msg[128];
-		regerror(err,&re,msg,128);
-		std::cerr << "Bad filter '" << filenameFilter << "': " << msg << std::endl;
-		regfree(&re);
-		return false;
-	}
-	
-	indexLoopTime=0;
-	ifstream in(src.c_str());
-	string cur;
-	getline(in,cur);
-	if(cur.find("First frame ")==0) //skip the header line from the GUI, e.g. 'First frame 42898 timestamp: 1439018'
-		getline(in,cur);
-	
-	float tinc=1000.f/framerate;
-	float time=calcLoopTime();
-	while(in) {
-		string fn = cur.substr(0,cur.find('\t'));
-		if(fn.size()!=cur.size()) {
-			const char * timep=cur.c_str()+cur.rfind('\t');
-			char * endp=NULL;
-			time=strtof(timep,&endp);
-			if(timep==endp) {
-				std::cerr << "ERROR: '" << src << "' does not seem to be a valid index file." << std::endl;
-				std::cerr << "       Use output from VisionGUI, or use format 'filename <tab> time'" << std::endl;
-				std::cerr << "       Where 'time' is the time in milliseconds at which the file should be processed, relative" << std::endl;
-				std::cerr << "       to the time at which the index file is loaded." << std::endl;
-				regfree(&re);
-				return false;
-			}
-		}
-		int match=regexec(&re,fn.c_str(),0,NULL,0);
-		if(match==0) {
-			if(fn[0]!='/') {
-				unsigned int srcdir=src.rfind('/');
-				if(srcdir!=string::npos)
-					fn=src.substr(0,srcdir+1)+fn;
-			}
-			//std::cout << "Enqueuing " << fn << " at " << time << std::endl;
-			files[static_cast<unsigned int>(time)]=fn;
-			time+=tinc;
-		} else if(match!=REG_NOMATCH) {
-			char msg[128];
-			regerror(match,&re,msg,128);
-			std::cerr << "Regex error on '" << fn << "': " << msg << std::endl;
-		} // else std::cout << "Skipping " << res->d_name << std::endl;
-		getline(in,cur);
-	}
-	regfree(&re);
-	return true;
-}
-
-bool LoadFileThread::incrementCurfile(float loopTime, int& curTime) {
-	if(++curfile == files.end()) {
-		if(!loop) {
-			if(verbose>0)
-				std::cout << "Last data from '" << src << "' loaded -- set 'loop' to true, or use 'restart' command to manually loop" << std::endl;
-			return false;
-		} else {
-			if(verbose>2)
-				std::cout << "Preparing to looping data from '" << src << "'" << std::endl;
-			unsigned int loopTimeI = (unsigned int)(loopTime);
-			loopRemainder+=loopTime-loopTimeI;
-			unsigned int loopRemainderI=(unsigned int)(loopRemainder);
-			loopRemainder-=loopRemainderI;
-			timeOffset=(startTimeOffset+=(loopTimeI+=loopRemainderI));
-			curTime-=loopTimeI;
-			curfile=files.begin();
-		}
-	}
-	return true;
-}
-
-unsigned int LoadFileThread::nextTimestamp() {
-	unsigned int curt=get_time();
-	if(frozen)
-		updateFrozenTime(curt);
-	if(!frozen && timestamps.size()>0) {
-		return timestamps.front();
-	} else if(heartbeat) {
-		return calcNextHeartbeat(curt);
-	} else
-		return -1U;
-}
-
-
-std::string LoadFileThread::getNextFrame() {
-	if(loaded.size()==0 || loaded.front()==NULL)
-		return heartbeat ? "heartbeat" : "(none)";
-	return std::string(loaded.front()->Base()+LoadSave::getSerializedSize<bool>()+2*LoadSave::getSerializedSize<int>());
-}
-
-unsigned int LoadFileThread::recoverSN(RCRegion* msg) {
-	unsigned int ans;
-	LoadSave::decode(ans,msg->Base()+LoadSave::getSerializedSize<bool>(),LoadSave::getSerializedSize(ans));
-	return ans;
-}
-
-void LoadFileThread::resetSN(RCRegion* msg, unsigned int sn) {
-	unsigned int used=LoadSave::encode(sn,msg->Base()+LoadSave::getSerializedSize<bool>(),LoadSave::getSerializedSize(sn));
-	ASSERT(used==sizeof(sn),"bad resetSN " << used)
-}
-
-bool LoadFileThread::advanceFrame(bool forceQueue) {
-	MarkScope l(lock);
-	unsigned int curt=get_time();
-	if(frozen)
-		updateFrozenTime(curt);
-	updateLoaded(curt);
-	if(loaded.size()==0 || (frozen && !forceQueue)) {
-		if(heartbeat) {
-			sendHeartbeat();
-			lastSent=curt;
-		}
-		return false;
-	}
-	lastSent=curt;
-	if(forceQueue)
-		offsetTimestamps(curt-timestamps.front());
-	timestamps.pop_front();
-	if(loaded.front()==NULL) {
-		if(heartbeat)
-			sendHeartbeat();
-		if(loaded.size()!=0)
-			loaded.pop_front();
-		return false;
-	} else { //has data
-		if(verbose>0)
-			std::cout << "Sending frame: \"" << getNextFrame() << "\" (advanced at " << curt << ')' << std::endl;
-		sent.push_back(loaded.front());
-		msgr.sendMessage(loaded.front());
-		loaded.pop_front();
-		updateLoaded(curt);
-		return true;
-	}
-}
-
-void LoadFileThread::plistValueChanged(const plist::PrimitiveBase& pl) {
-	MarkScope l(lock);
-	if(&pl==&src)
-		loadFileList();
-	else if(&pl==&verbose) {
-		msgr.setReportDroppings(verbose>1);
-		// update verbose flag of currently loaded
-		for(msgbuf_t::iterator it=loaded.begin(); it!=loaded.end(); ++it)
-			LoadSave::encode(verbose>0,(*it)->Base(),LoadSave::getSerializedSize<bool>());
-	} else if(&pl==&frozen) {
-		if(!frozen) {
-			updateFrozenTime(get_time());
-			if(!isRunning())
-				start();
-		} else if(frozen) {
-			if(!heartbeat && isRunning())
-				stop();
-			frozenTime=get_time();
-		}
-	} else if(&pl==&heartbeat) {
-		if(frozen && heartbeat && !isRunning())
-			start();
-		else if(frozen && !heartbeat && isRunning())
-			stop();
-	}
-}
-
-void LoadFileThread::setLoopTime(float t) {
-	files_t::const_iterator lastfile=files.end();
-	--lastfile;
-	unsigned int last=lastfile->first;
-	if(t<last && t!=0) {
-		stringstream ss;
-		ss << "LoadFileThread::setLoopTime error: passed loop time (" << t << ") is less than time of last frame (" << last << ")";
-		throw std::invalid_argument(ss.str());
-	}
-	indexLoopTime=t;
-}
-
-
-void LoadFileThread::getNextData(RCRegion*& data, unsigned int& t) {
-	if(files.size()==0 || curfile==files.end())
-		return;
-	if(startTimeOffset!=timeOffset)
-		resetTimeOffset(startTimeOffset);
-
-	unsigned int realt=get_time();
-	int curt=realt-timeOffset;
-	float loopTime=calcLoopTime();
-		
-	if(!frozen) {
-		//skip old data -- current time is already past these frames, no point in loading them
-		if(curt>(int)(loopTime)) {
-			if(!loop) {
-				if(verbose>2)
-					std::cout << "Way out of data from '" << src << "' -- set 'loop' to true, or use 'restart' command to manually loop" << std::endl;
-				curfile=files.end();
-				return;
-			}
-			if(verbose>2)
-				std::cout << "Mass looping data from '" << src << "'" << std::endl;
-			unsigned int loops=(unsigned int)(curt/loopTime);
-			float massLoopTime=loops*loopTime;
-			unsigned int massLoopTimeI=(unsigned int)(massLoopTime);
-			loopRemainder+=massLoopTime-massLoopTimeI;
-			unsigned int loopRemainderI=(unsigned int)(loopRemainder);
-			loopRemainder-=loopRemainderI;
-			resetTimeOffset(startTimeOffset+=(massLoopTimeI+=loopRemainderI));
-			curt=realt-timeOffset; //timeOffset set to startTimeOffset by previous line
-			curfile=files.begin();
-		}
-		while(static_cast<int>(curfile->first)<curt)
-			if(!incrementCurfile(loopTime,curt))
-				return;
-	}
-	if(timestamps.size()>0) // if there's already stuff loaded, make sure we're loading after what's already there
-		while(curfile->first+timeOffset<=timestamps.back())
-			if(!incrementCurfile(loopTime,curt))
-				return;
-	
-	if(verbose>3)
-		std::cout << "Loading frame from " << curfile->second << " dt="<<curfile->first << " scheduled:" << (curfile->first+timeOffset) << std::endl;
-	RCRegion* unused=firstUnusedRegion();
-	if(!loadFile(curfile->second, unused)) { //loadfile can accept NULL region if none was found
-		std::cerr << "Bad load on " << curfile->second << std::endl;
-		incrementCurfile(loopTime,curt);
-		if(unused!=NULL)
-			sent.push_front(unused);
-		return;
-	}
-	data=unused;
-	t=curfile->first+timeOffset;
-	incrementCurfile(loopTime,curt);
-}
-
-bool LoadFileThread::loadFile(const std::string& file, RCRegion*& data) {
-	struct stat statbuf;
-	if(stat(file.c_str(),&statbuf)!=0) {
-		perror("LoadFileThread::loadFile");
-		return false;
-	}
-	FILE * f=fopen(file.c_str(),"rb");
-	int nread;
-	try {
-		if(f==NULL) {
-			std::cerr << "LoadFileThread::loadFile(): File open failed" << std::endl;
-			return false;
-		}
-		char* buf=setupRegion(data,file,statbuf.st_size);
-		nread=fread(buf,1,statbuf.st_size,f);
-	} catch (...) {
-		fclose(f);
-		std::cerr << "Exception occurred during LoadFileThread::loadFile" << std::endl;
-		throw;
-	}
-	fclose(f);
-	f=NULL;
-	if(nread!=statbuf.st_size) {
-		std::cerr << "LoadFileThread::loadFile(): failed to load entire file, "<<nread<<" read, "<<statbuf.st_size<<" requested" << std::endl;
-		return false;
-	}
-	return true;
-}
-
-RCRegion* LoadFileThread::firstUnusedRegion() {
-	for(msgbuf_t::iterator it=sent.begin();it!=sent.end(); ++it) {
-		if((*it)->NumberOfReference()==1) {
-			RCRegion * ans=*it;
-			sent.erase(it);
-			return ans;
-		}
-	}
-	return NULL;
-}
-
-char* LoadFileThread::setupRegion(RCRegion*& region, const std::string& filename, unsigned int payload) {
-	// header fields: bool:verbose, uint:frameSN, str:filename, uint:payload
-	const unsigned int FILE_HEADER_SIZE=LoadSave::getSerializedSize<bool>() + LoadSave::getSerializedSize(frameSN) + LoadSave::getSerializedSize(filename) + LoadSave::getSerializedSize<bool>() + LoadSave::getSerializedSize(payload);
-	if(region==NULL)
-		region=new RCRegion(FILE_HEADER_SIZE+payload+sizeof(char)*filename.size()*2); //triple the allocation for filename so we don't have to resize if we get a longer name later
-	else if(region->Size()<FILE_HEADER_SIZE+payload) {
-		//too small -- free it, we'll drop it and make a bigger one
-		freeRegion(region);
-		region=new RCRegion(FILE_HEADER_SIZE+payload+sizeof(char)*filename.size()*2); //triple the allocation for filename so we don't have to resize if we get a longer name later
-	}
-	char* buf=region->Base();
-	unsigned int remain=FILE_HEADER_SIZE;
-	if(!LoadSave::encodeInc(payload>0 && verbose>0 || verbose>2,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(frameSN++,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(filename,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(loaded.size()>0,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(payload,buf,remain)) return NULL;
-	ASSERT(remain==0,"LoadFileThread::setupRegion(): Leftover bytes in header? FILE_HEADER_SIZE is wrong\n");
-	return buf;
-}
-
-char* LoadFileThread::deserializeHeader(char* buf, unsigned int size, bool* verbose, unsigned int* sn, std::string* filename, bool* dataInQueue, unsigned int* payloadSize) {
-	if(verbose!=NULL) { if(!LoadSave::decodeInc(*verbose,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*verbose);
-	if(sn!=NULL) { if(!LoadSave::decodeInc(*sn,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*sn);
-	if(filename!=NULL) { if(!LoadSave::decodeInc(*filename,buf,size)) return NULL; } else {
-		unsigned int len=0;
-		if(!LoadSave::decodeInc(len,buf,size)) return NULL;
-		buf+=len+1;
-	}
-	if(dataInQueue!=NULL) { if(!LoadSave::decodeInc(*dataInQueue,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*dataInQueue);
-#ifndef DEBUG
-	if(payloadSize!=NULL) { if(!LoadSave::decodeInc(*payloadSize,buf,size)) return NULL; } else buf+=LoadSave::getSerializedSize(*payloadSize);
-#else
-	unsigned int lPayloadSize; // want to error check payloadSize regardless of whether caller wants the info
-	if(payloadSize==NULL)
-		payloadSize=&lPayloadSize;
-	if(!LoadSave::decodeInc(*payloadSize,buf,size)) return NULL;
-	ASSERT(size>=*payloadSize,"short payload (" << size << " vs expected " << *payloadSize << ")");
-	// this is normal (regions are generated a little bigger than they need to be to allow recycling)
-	//ASSERT(size<=*payloadSize,"unhandled bytes after payload (" << size << " vs expected " << *payloadSize << ")");
-#endif
-	return buf;
-}
-
-void LoadFileThread::sendHeartbeat() {
-	msgbuf_t::const_iterator it=loaded.begin();
-	while(it!=loaded.end() && *it==NULL)
-		++it;
-	if(it!=loaded.end())
-		frameSN=recoverSN(*it);
-	RCRegion *unused=firstUnusedRegion();
-	char * buf=setupRegion(unused,"heartbeat",0);
-	if(unused==NULL || buf==NULL)
-		return;
-	if(verbose>2)
-		std::cout << "Sending heartbeat at " << get_time() << std::endl;
-	for(; it!=loaded.end(); ++it)
-		if(*it!=NULL)
-			resetSN(*it,frameSN++);
-	msgr.sendMessage(unused);
-	sent.push_back(unused);
-}
-
-unsigned int LoadFileThread::calcSleepTime() const {
-	if(getTimeScale()<0)
-		return 1000; // poll quickly when in full speed mode (100Hz)
-	const unsigned int MAX_POLL=250000U; // longest to go between polls -- 4Hz
-	if(getTimeScale()==0)
-		return MAX_POLL; // poll (somewhat) slowly when paused (4Hz)
-	//otherwise poll at framerate
-	if(timestamps.size()==0) {
-		// just to keep checking back in case of reset
-		return min(MAX_POLL,static_cast<unsigned int>(1000000/getTimeScale()/framerate));
-	} else {
-		unsigned int curt=get_time();
-		// return min of 1 second (in case of reset/user input), frame rate, or time until next frame
-		return timestamps.front()<=curt ? 0 : min(MAX_POLL,static_cast<unsigned int>(min(1000000/getTimeScale()/framerate,1000*(timestamps.front()-curt)/getTimeScale())));
-	}
-}
-
-unsigned int LoadFileThread::calcNextHeartbeat(unsigned int curt) const {
-	unsigned int skip=static_cast<unsigned int>((curt-lastSent)*framerate/1000);
-	return static_cast<unsigned int>(lastSent+(skip+1)*1000.f/framerate);
-}
-
-unsigned int LoadFileThread::runloop() {
-	MarkScope l(lock);
-	unsigned int curt=get_time();
-	if(frozen) {
-		if(heartbeat && curt>=(lastSent+1000.f/framerate)) {
-			updateFrozenTime(curt);
-			sendHeartbeat();
-			lastSent=curt;
-		}
-	} else if(timestamps.size()==0 && heartbeat && curt>=(lastSent+1000.f/framerate)) {
-		sendHeartbeat();
-		lastSent=curt;
-	} else if(timestamps.size()>0 && curt>=timestamps.front()) {
-		if(verbose>0)
-			std::cout << "Sending frame: \"" << getNextFrame() << "\" (scheduled " << timestamps.front() << ", now " << curt << ')' << std::endl;
-		lastSent=timestamps.front();
-		timestamps.pop_front();
-		if(loaded.size()==0 || loaded.front()==NULL) {
-			if(heartbeat)
-				sendHeartbeat();
-			if(loaded.size()!=0)
-				loaded.pop_front();
-		} else {
-			sent.push_back(loaded.front());
-			msgr.sendMessage(loaded.front());
-			loaded.pop_front();
-		}
-	}
-	updateLoaded(get_time());
-	if(loaded.size()<NUM_PRELOAD) //try to catch up if we're behind
-		updateLoaded(get_time()); // but only do one extra -- don't want to pause sending because we're busy loading
-	return calcSleepTime();
-}
-
-void LoadFileThread::updateLoaded(unsigned int curt) {
-	if(loaded.size()<NUM_PRELOAD) {
-		if(curfile==files.end()) //out of data -- nothing to load, return
-			return;
-		RCRegion* rcr=NULL;
-		unsigned int t=-1U;
-		getNextData(rcr,t);
-		if(t==-1U || rcr==NULL) {
-			//bad image, skip a frame and then check again in case we get reset
-			std::cerr << "Could not allocate new shared memory region or bad initial load" << std::endl;
-			if(rcr!=NULL) //if rcr was created, error during load, don't throw away the region
-				sent.push_front(rcr);
-			if(heartbeat) {
-				//send a heartbeat instead of missing frame if requested
-				rcr=firstUnusedRegion();
-				char * buf=setupRegion(rcr,"heartbeat",0);
-				if(buf!=NULL && rcr!=NULL) {
-					loaded.push_back(rcr);
-					if(timestamps.size()>0)
-						timestamps.push_back(static_cast<unsigned int>(timestamps.back()+1000.f/framerate));
-					else {
-						//skip heartbeats which have already passed
-						timestamps.push_back(calcNextHeartbeat(curt));
-					}
-				}
-			}
-		} else if(timestamps.size()==0 || t>timestamps.back()) {
-			loaded.push_back(rcr);
-			timestamps.push_back(t);
-		} else {
-			frameSN--;
-			std::cerr << "ERROR: LoadFileThread received old data from getNextData" << std::endl;
-			sent.push_front(rcr);
-		}
-	}
-}
-
-void LoadFileThread::resetTimeOffset(int t) {
-	if(loaded.size()>0 && loaded.front()!=NULL)
-		frameSN=recoverSN(loaded.front());
-	while(loaded.size()>0) {
-		if(loaded.front()!=NULL)
-			sent.push_front(loaded.front());
-		loaded.pop_front();
-	}
-	timestamps.clear();
-	if(t<timeOffset) {
-		//need to rewind curfile
-		curfile=files.begin(); //getNextData will fast forward to current time
-	}
-	timeOffset=t;
-}
-
-float LoadFileThread::calcLoopTime() const {
-	if(files.size()==0)
-		return 0;
-	float tinc=1000.f/framerate;
-	if(isIndexed) {
-		if(indexLoopTime>0)
-			return indexLoopTime;
-		files_t::const_iterator lastfile=files.end();
-		--lastfile;
-		unsigned int last=lastfile->first;
-		return last+tinc;
-	} else {
-		return files.size()*tinc;
-	}
-}
-
-void LoadFileThread::updateFrozenTime(unsigned int t) {
-	offsetTimestamps(t-frozenTime);
-	frozenTime=t;
-}
-
-void LoadFileThread::offsetTimestamps(int off) {
-	timeOffset=(startTimeOffset+=off);
-	for(std::list<unsigned int>::iterator it=timestamps.begin(); it!=timestamps.end(); ++it)
-		(*it)+=off;
-}	
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:51 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/LoadFileThread.h ./local/LoadFileThread.h
--- ../Tekkotsu_3.0/local/LoadFileThread.h	2006-09-28 16:42:51.000000000 -0400
+++ ./local/LoadFileThread.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,222 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_LoadFileThread_h_
-#define INCLUDED_LoadFileThread_h_
-
-#include "IPC/Thread.h"
-#include "Shared/plist.h"
-#include "IPC/MessageQueue.h"
-#include <list>
-
-//! Provides resources for loading time-based data from disk
-/*! Runs in a separate thread, preloads data into shared memory buffers, and
- *  then sends the buffer when the time is right.  Thread doesn't start until
- *  you set the source or call loadFileList(). */
-class LoadFileThread : public Thread, public plist::Dictionary, public plist::PrimitiveListener {
-public:
-	
-	//! constructor
-	/*! @param source the path to either a directory to load files from, or a single specific data file
-	 *  @param filter a regular expression (POSIX.2 extended format) to select which files to load from @a source, if @a is a directory
-	 *  @param fps frames per second, see #frameRate
-	 *  @param messages the MessageQueue through which to send the data
-	 *  @param doLoad if true, call loadFileList (subclasses probably want to pass false and call that themselves after their own construction)
-	 *
-	 *  The file list is not actually loaded until you call loadFileList -- this
-	 *  gives you a chance to reset the default values you supplied in the
-	 *  constructor with actual values from, for example, a preference file, and
-	 *  then load the file list after the settings are correct.
-	 */
-	LoadFileThread(std::string source, std::string filter, float fps, MessageQueueBase& messages, bool doLoad=true)
-	: Thread(), plist::Dictionary(),
-		src(source),
-		filenameFilter(filter),
-		framerate(fps),
-		verbose(0),
-		loop(true),
-		heartbeat(true), frozen(false),
-		sent(), loaded(), timestamps(), files(), curfile(files.begin()), msgr(messages),
-		startTimeOffset(0), timeOffset(0), lock(), loopRemainder(0), isIndexed(false), indexLoopTime(0), lastSent(0), frameSN(0), frozenTime(0)
-	{
-		addEntry("Source",src,"The directory from which data samples should be loaded, or a single specific file.\nA single file can be either a single data file (e.g. sensor or camera image), or an index file as output by VisionGUI, or in the format 'filename <tab> time', where 'filename' is an absolute path or relative to the directory containing the index file, and 'time' is in milliseconds, relative to the time at which the index file is loaded.\nIn the future, this could also be network addresses for teleoperation and remote processing.");
-		addEntry("FileFilter",filenameFilter,"If Source is a directory or index file, only files matching the filter will be loaded from it.");
-		addEntry("Framerate",framerate,"The rate at which images should be loaded -- only referenced when setting up files during loadFileList() -- later modifications won't reset the already loaded file list");
-		addEntry("Verbose",verbose,"Controls how much feedback to give on the console regarding progress\n  0 - none\n  1 - report when message is sent\n  2 - also report when message is dropped\n  3 - also report when heartbeat is sent/dropped, and when loop occurs\n  4 - also report when each message is preloaded");
-		addEntry("Loop",loop,"If true, restart file list at the beginning when the end is reached; otherwise just stop loading data");
-		addEntry("Heartbeat",heartbeat,"If enabled, an empty \"heartbeat\" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.");
-		addEntry("Frozen",frozen,"If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically");
-		src.addPrimitiveListener(this);
-		verbose.addPrimitiveListener(this);
-		frozen.addPrimitiveListener(this);
-		if(doLoad)
-			loadFileList(false,false);
-	}
-	//! destructor
-	~LoadFileThread();
-	
-	//! The directory from which data samples should be loaded, or a single specific file.
-	/*! A single file can be either a single data file (e.g. sensor or camera image), or an index file as output by VisionGUI, or in the format 'filename <tab> time', where 'filename' is an absolute path or relative to the directory containing the index file, and 'time' is in milliseconds, relative to the time at which the index file is loaded.\nIn the future, this could also be network addresses for teleoperation and remote processing. */
-	plist::Primitive<std::string> src;
-
-	//! a regular expression (POSIX.2 extended format) to select which files to load from #src, if #src is a directory or index file
-	plist::Primitive<std::string> filenameFilter;
-
-	//! frames per second to send -- only referenced when setting up #files during loadFileList() -- later modifications won't reset the already loaded file list
-	plist::Primitive<float> framerate;
-
-	//! Controls how much feedback to give on the console regarding progress
-	/*! 0 - none\n
-	 *  1 - report when message is sent\n
-	 *  2 - also report when message is dropped\n
-	 *  3 - also report when heartbeat is sent/dropped, and when loop occurs\n
-	 *  4 - also report when each message is preloaded */
-	plist::Primitive<int> verbose; 
-
-	//! controls whether to restart #curfile at the beginning of #files when it reaches the end
-	plist::Primitive<bool> loop;
-	
-	//! if enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. no data loaded or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.
-	plist::Primitive<bool> heartbeat;
-	
-	//! if true, no frames will be sent, except via explicit (external) calls to advanceFrame(); if false, the thread will run and send messages at the requested times
-	plist::Primitive<bool> frozen;
-	
-
-	//! call this to (re)load the list of available file names from disk
-	/*! If @a clearCurrent is set, then the current file list will be cleared;
-	 *  otherwise, the loaded files will be appended to the current queue */
-	virtual void loadFileList(bool clearCurrent=true, bool reportMissing=true);
-	//! sets the next frame to be sent (e.g. pass 0 to reset to the first frame)
-	virtual void setFrame(unsigned int f);
-	
-	//! returns the timestamp of the next message in the queue ready to be sent
-	virtual unsigned int nextTimestamp();
-	
-	//! returns the filename of the next frame scheduled to be sent
-	virtual std::string getNextFrame();
-	
-	//! returns the serial number of the message
-	static unsigned int recoverSN(RCRegion* msg);
-	
-	//! can reassign the serial number of the message
-	static void resetSN(RCRegion* msg, unsigned int sn);
-	
-	//! recovers data from serialized IPC message, returns beginning of payload, or NULL if there's an error
-	/*! each parameter can be a pointer where to store the field, or NULL if you don't care */
-	static char* deserializeHeader(char* buf, unsigned int size, bool* verbose, unsigned int* sn, std::string* filename, bool* dataInQueue, unsigned int* payloadSize);
-	
-	//! sends the next frame in #loaded, and loads the next in filelist queue
-	/*! returns true if there was a frame to send; will send heartbeat if configured, but returns false for heartbeats */
-	virtual bool advanceFrame(bool forceQueue);
-
-	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
-	
-	//! reports number of files currently pre-loaded, available for sending
-	virtual unsigned int numLoaded() { return loaded.size(); }
-	
-	virtual bool usingIndexFile() const { return isIndexed; }
-	virtual float getLoopTime() const { return calcLoopTime(); }
-	virtual void setLoopTime(float t);
-	
-protected:
-	//! removes our reference to a region created by loadFile()
-	virtual void freeRegion(RCRegion* rcr) { if(rcr!=NULL) rcr->RemoveReference(); }
-	
-	//! loads the next data element from file and provides its timestamp, skipping any files which have already expired
-	/*! @param[in] data a pre-allocated region to use, or NULL to request creation of a new one
-	 *  @param[out] data the address of the region with loaded data
-	 *  @param[out] t the timestamp at which @a data should be consumed */
-	virtual void getNextData(RCRegion*& data, unsigned int& t);
-	
-	//! does the actual work of loading and processing data from disk, subclasses should override this if they want to decompress/pre-parse the data
-	/*! This implementation merely loads the data directly into memory with no processing or parsing.
-	 *  @param[in] file full path of file to load
-	 *  @param[in] data a pre-allocated region to use, or NULL to request creation of a new one
-	 *  @param[out] data the address of the region which has been filled in
-	 *  @return true if successful, false if error */
-	virtual bool loadFile(const std::string& file, RCRegion*& data);
-	using plist::Dictionary::loadFile; // there's also the LoadSave function by the same name for loading parameters from a file
-	
-	//! increments #curfile, looping if necessary; returns false if end of list reached and not #loop
-	/*! @param[in] loopTime is the time of a single loop (the time of the last frame, plus inter-frame time)
-	 *  @param[in] curTime is the current time, relative to beginning of current loop (#timeOffset)
-	 *  @param[out] modified curTime if loop has occurred, subtracting loopTime 
-	 *  @return true if successful, false if no files are left */
-	virtual bool incrementCurfile(float loopTime, int& curTime);
-	
-	//! removes and returns first region in #sent with only one reference, or NULL if none exists
-	virtual RCRegion* firstUnusedRegion();
-	
-	//! sets up some header info in the specified RCRegion, reallocating if the suggested region is not large enough (or is NULL), returns pointer to end of header info in the region
-	virtual char* setupRegion(RCRegion*& region, const std::string& file, unsigned int payload);
-	
-	//! sends an empty heartbeat message indicating previous data should be reused
-	virtual void sendHeartbeat();
-	
-	//! load a list of files from a directory specified by #src
-	virtual void loadFileListFromDirectory();
-	//! load a single file
-	virtual void loadSingleFile(const std::string& file);
-	//! load a list of files from an index file specified by #src
-	/*! This supports either the format produced by VisionGUI, or a simplier '<code>filename [<tab> time]\n</code>' format,
-	 *  where if @c time is unspecified, the frame's time is incremented by the #framerate from the previously listed file.
-	 *  Filenames should either be either absolute paths or relative to the directory which contains the index file.*/
-	virtual bool loadFileListFromIndex();
-
-	//! returns time to sleep based front of timestamps -- limits to max sleep of 1 second or the current frame rate, if timestamp is already past, return 0
-	unsigned int calcSleepTime() const;
-	
-	//! returns time of next heartbeat
-	unsigned int calcNextHeartbeat(unsigned int curt) const;
-	
-	//! monitor #msgr, send new messages when their timestamp indicates they are due, then load upcoming messages
-	virtual unsigned int runloop();
-	
-	//! if loaded has less than NUM_PRELOAD items, loads a new frame at the end
-	virtual void updateLoaded(unsigned int curt);
-
-	//! assign a new value @a t to #timeOffset -- clears loaded data queue (to be reloaded on next call to getNextData())
-	virtual void resetTimeOffset(int t);
-	
-	//! computes the time of an entire loop through the files (including inter-frame time at the end of the loop)
-	virtual float calcLoopTime() const;
-	
-	//! calls offsetTimestamps with the difference between @a t (usually the current time) and frozenTime , then resets frozenTime to @a t
-	/*! takes a parameter instead of calling get_time itself because caller probably wants to do an "instantaneous" update, so don't want clock to tick while processing */
-	void updateFrozenTime(unsigned int t);
-	
-	//! adds off to entries in #timestamps as well as #timeOffset and #startTimeOffset
-	void offsetTimestamps(int off);
-
-	static const unsigned int NUM_PRELOAD=2; //!< number of data elements to preload
-	typedef std::list<RCRegion* > msgbuf_t; //!< type of collection of shared data regions
-	typedef std::map<unsigned int,std::string> files_t; //!< type of #files, the list of files to load
-
-	msgbuf_t sent; //!< for efficiency, reuse old buffers -- oldest at front, most recently used at back
-	msgbuf_t loaded; //!< for efficiency, reuse old buffers -- oldest at front, most recently used at back
-	std::list<unsigned int> timestamps; //!< the timestamps to send data queued in #loaded
-	files_t files; //!< the list of files to load ('second'), and their timestamps ('first')
-	files_t::const_iterator curfile; //!< an iterator referencing #files -- indicates next file to load
-	MessageQueueBase& msgr; //!< the MessageQueue through which to send the data
-	int startTimeOffset; //!< the requested time of start of run through #files -- if this is modified, it will be noticed during runloop() and #curfile will be updated appropriately
-	int timeOffset; //!< the starting time of the run through #files, see #startTimeOffset
-	Thread::Lock lock; //!< allows mutual exclusion over this object's member variables
-	float loopRemainder; //!< a bit ugly -- this is the fractional leftover accumulated from looping so we won't "drift" over time
-	bool isIndexed; //!< if we're using an index file, we have to handle the loopRemainder differently
-	float indexLoopTime; //!< if we're using an index file, this can be set to the time per loop, which can be used to keep multiple streams in sync.  Must be set externally however, as this stream doesn't know about other streams.
-	unsigned int lastSent; //!< timestamp of most recently sent message (or heartbeat)
-	unsigned int frameSN; //!< serial number of next message to load (a lower number may be enqueued but not yet sent!)
-	unsigned int frozenTime; //!< the time #frozen was set to true
-};
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:51 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/LoadImageThread.cc ./local/LoadImageThread.cc
--- ../Tekkotsu_3.0/local/LoadImageThread.cc	2006-09-28 16:42:51.000000000 -0400
+++ ./local/LoadImageThread.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,261 +0,0 @@
-#include "LoadImageThread.h"
-
-#include "Shared/debuget.h"
-
-#include <png.h>
-extern "C" {
-#include <jpeglib.h>
-
-	struct png_read_mem_status {
-		png_bytep buf;
-		size_t bufsize;
-		size_t offset;
-	};
-	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");
-		}
-	}
-	
-}
-#ifndef LOADFILE_NO_MMAP
-#  include "Shared/jpeg-6b/jpeg_mem_src.h"
-#  include <fcntl.h>
-#  include <errno.h>
-#  include <sys/types.h>
-#  include <sys/mman.h>
-#  include <sys/stat.h>
-#endif
-
-using namespace std;
-
-LoadImageThread::LoadImageThread(std::string source, std::string filter, float fps, MessageQueueBase& messages, bool doLoad/*=true*/)
-	: LoadFileThread(source,filter,fps,messages,false),
-	cinfo(new jpeg_decompress_struct), jerr(new jpeg_error_mgr), frameIndex(0), layer(0)
-{
-	cinfo->err = jpeg_std_error(jerr);
-	jpeg_create_decompress(cinfo);
-	addEntry("Layer",layer,"Controls the resolution layer at which the image should be processed.\n0 indicates \"automatic\" mode (picks layer closest to image's resolution), positive numbers indicate the resolution layer directly.\nNegative values are relative to the number of layers marked available by the vision setup, so that typically -1 would correspond to the \"double\" layer, and -2 would correspond to the \"full\" layer.");
-	if(doLoad)
-		loadFileList(false,false);
-}
-
-LoadImageThread::~LoadImageThread() {
-	jpeg_destroy_decompress(cinfo);
-	delete cinfo;
-	delete jerr;
-}
-
-bool LoadImageThread::loadFile(const std::string& file, RCRegion*& data) {
-	struct stat statbuf;
-	if(stat(file.c_str(),&statbuf)!=0) {
-		perror("LoadImageThread::loadFile");
-		return false;
-	}
-#ifdef LOADFILE_NO_MMAP
-	FILE * infile= fopen(file.c_str(), "rb");
-	if (infile==NULL) {
-		int err=errno;
-		cerr << "LoadImageThread::loadFile(): Could not open '" << file << "' (fopen:" << strerror(err) << ")" << endl;
-		return false;
-	}
-	JOCTET* inbuf=static_cast<JOCTET*>(new char[statbuf.st_size]);
-	if(!fread(inbuf,statbuf.st_size,1,infile) {
-		int err=errno;
-		cerr << "LoadImageThread::loadFile(): Could not load '" << file << "' (fread:" << strerror(err) << ")" << endl;
-		if(fclose(infile))
-			perror("Warning: LoadImageThread::loadFile(), on fclose");
-		delete [] inbuf;
-		return false;
-	}
-	if(fclose(infile))
-		 perror("Warning: LoadImageThread::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 << "LoadImageThread::loadFile(): Could not open '" << file << "' (open:" << strerror(err) << ")" << endl;
-		return false;
-	}
-	JOCTET* inbuf=static_cast<JOCTET*>(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 << "LoadImageThread::loadFile(): Could not load '" << file << "' (mmap:" << strerror(err) << ")" << endl;
-		if(close(infd)<0)
-			perror("Warning: LoadImageThread::loadFile(), on closing temporary file descriptor from open");
-		return false;
-	}
-	if(close(infd)<0)
-		perror("Warning: LoadImageThread::loadFile(), on closing temporary file descriptor from open");
-#endif
-	if(!png_sig_cmp(inbuf, 0, 8)) {
-		//is PNG
-		png_structp png_ptr = png_create_read_struct(PNG_LIBPNG_VER_STRING, (png_voidp)NULL, NULL, NULL);
-		if (!png_ptr) {
-#ifdef LOADFILE_NO_MMAP
-			delete [] inbuf;
-#else
-			if(munmap(inbuf,statbuf.st_size))
-				perror("Warning: LoadImageThread::loadFile(), on munmap");
-#endif
-			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);
-#ifdef LOADFILE_NO_MMAP
-			delete [] inbuf;
-#else
-			if(munmap(inbuf,statbuf.st_size))
-				perror("Warning: LoadImageThread::loadFile(), on munmap");
-#endif
-			return false;
-		}
-		
-		if (setjmp(png_jmpbuf(png_ptr))) {
-			png_destroy_read_struct(&png_ptr, &info_ptr, (png_infopp)NULL);
-#ifdef LOADFILE_NO_MMAP
-			delete [] inbuf;
-#else
-			if(munmap(inbuf,statbuf.st_size))
-				perror("Warning: LoadImageThread::loadFile(), on munmap");
-#endif
-			return false;
-		}
-		
-		png_read_mem_status read_status;
-		read_status.buf=(png_bytep)inbuf;
-		read_status.bufsize=statbuf.st_size;
-		read_status.offset=0;
-		png_set_read_fn(png_ptr, &read_status, user_read_png_data);
-		
-		png_read_info(png_ptr, info_ptr);
-		
-		size_t width=png_get_image_width(png_ptr, info_ptr);
-		size_t height=png_get_image_height(png_ptr, info_ptr);
-		if(width==0 || height==0) {
-			cerr << "Empty image '" << file << "'" << endl;
-			return false;
-		}
-		
-		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);
-		
-		size_t rowbytes=png_get_rowbytes(png_ptr, info_ptr);
-		/*png_bytep row_pointers[height];
-		row_pointers[0]=reinterpret_cast<png_bytep>(data->Base()+FULL_HEADER_SIZE);
-		for(unsigned int h=1; h<height; ++h)
-			row_pointers[h]=row_pointers[h-1]+rowbytes;
-		png_read_image(png_ptr, row_pointers);*/
-		png_bytep row=reinterpret_cast<png_bytep>(setupRegion(data,file,width,height,3));
-		for(unsigned int h=0; h<height; ++h) {
-			if(row+rowbytes>reinterpret_cast<png_bytep>(data->Base()+data->Size())) {
-				cerr << "Ran out of PNG buffer space" << endl;
-				break;
-			}
-			png_read_row(png_ptr, row, NULL);
-			row+=rowbytes;
-		}
-		png_read_end(png_ptr, NULL);
-		png_destroy_read_struct(&png_ptr, &info_ptr,(png_infopp)NULL);
-		
-	} else {
-		//assume JPEG
-		jpeg_mem_src(cinfo, inbuf, statbuf.st_size);
-		jpeg_read_header(cinfo, true);
-		cinfo->out_color_space=JCS_YCbCr;
-		jpeg_calc_output_dimensions(cinfo);
-		if(cinfo->output_width==0 || cinfo->output_height==0) {
-			cerr << "Empty image '" << file << "'" << endl;
-			return false;
-		}
-		unsigned int remain=cinfo->output_height;
-		unsigned int row_stride = cinfo->output_width * cinfo->output_components;
-		JSAMPROW rows[remain];
-		rows[0]=reinterpret_cast<JSAMPLE*>(setupRegion(data,file,cinfo->output_width,cinfo->output_height,cinfo->output_components));
-		if(rows[0]==NULL) {
-			jpeg_finish_decompress(cinfo);
-			return false;
-		}
-		for(unsigned int i=1; i<remain; i++)
-			rows[i]=rows[i-1]+row_stride;
-		JSAMPROW* curpos=rows;
-		//JSAMPARRAY buffer = (*cinfo.mem->alloc_sarray)((j_common_ptr) &cinfo, JPOOL_IMAGE, row_stride, 1);
-		jpeg_start_decompress(cinfo);
-		while (remain>0) {
-			unsigned int used=jpeg_read_scanlines(cinfo, curpos, remain);
-			curpos+=used;
-			remain-=used;
-		}
-		jpeg_finish_decompress(cinfo);
-	}
-#ifdef LOADFILE_NO_MMAP
-	delete [] inbuf;
-#else
-	if(munmap(inbuf,statbuf.st_size))
-		perror("Warning: LoadImageThread::loadFile(), on munmap");
-#endif
-	if(jerr->num_warnings>0) {
-		cerr << "Warning: Decompression of '" << file << "' had warnings" << endl;
-		jerr->num_warnings=0;
-	}
-	return true;
-}
-
-char* LoadImageThread::setupRegion(RCRegion*& region, const std::string& filename, unsigned int width, unsigned int height, unsigned int components) {
-	const unsigned int IMAGE_HEADER_SIZE=sizeof(unsigned int)*5;
-	const unsigned int payload=IMAGE_HEADER_SIZE+sizeof(JSAMPLE)*width*height*components;
-	char * buf=LoadFileThread::setupRegion(region,filename,payload);
-	if(buf==NULL || region==NULL)
-		return NULL;
-	unsigned int remain=IMAGE_HEADER_SIZE;
-	if(!LoadSave::encodeInc(width,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(height,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(components,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(frameIndex++,buf,remain)) return NULL;
-	if(!LoadSave::encodeInc(*layer,buf,remain)) return NULL;
-	ASSERTRETVAL(remain==0,"LoadImageThread::setupRegion(): Leftover bytes in header? IMAGE_HEADER_SIZE is wrong\n",NULL);
-	return buf;
-}
-
-
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:51 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/LoadImageThread.h ./local/LoadImageThread.h
--- ../Tekkotsu_3.0/local/LoadImageThread.h	2006-09-28 16:42:51.000000000 -0400
+++ ./local/LoadImageThread.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,41 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_LoadImageThread_h_
-#define INCLUDED_LoadImageThread_h_
-
-#include "LoadFileThread.h"
-
-class LoadImageThread : public LoadFileThread {
-public:
-	LoadImageThread(std::string source, std::string filter, float fps, MessageQueueBase& messages, bool doLoad=true);
-	~LoadImageThread();
-
-	virtual bool loadFile(const std::string& file, RCRegion*& data);
-	using LoadFileThread::loadFile; // there's also the LoadSave function by the same name for loading parameters from a file
-	
-protected:
-	virtual char* setupRegion(RCRegion*& region, const std::string& filename, unsigned int width, unsigned int height, unsigned int components);
-	using LoadFileThread::setupRegion;
-	virtual void sendHeartbeat() { frameIndex++; LoadFileThread::sendHeartbeat(); }
-
-	struct jpeg_decompress_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 frameIndex; //!< serial number, incremented for each frame loaded
-	plist::Primitive<int> layer;
-	
-private:
-	LoadImageThread(const LoadImageThread&); //!< don't call
-	LoadImageThread& operator=(const LoadImageThread&); //!< don't call
-};
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.1 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:51 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/Makefile.local ./local/Makefile.local
--- ../Tekkotsu_3.0/local/Makefile.local	2006-09-28 16:42:51.000000000 -0400
+++ ./local/Makefile.local	2007-11-01 16:27:01.000000000 -0400
@@ -4,16 +4,43 @@
 
 .PHONY: 
 
-#Each directory should represent a separate executable
-EXECS:=$(filter-out CVS,$(subst local/,,$(shell find local -mindepth 1 -maxdepth 1 -type d -prune)))
+EXECS:=$(patsubst local/%,%,$(shell find local -mindepth 1 -maxdepth 1 -type d -name '[a-z]*'))
+ifneq ($(HAVE_ICE),)
+	EXECS:=$(filter-out terk,$(EXECS))
+endif
+LSRC_SKIP:=$(foreach x,$(EXECS),\! -path local/$(x)/\*)
+LSRCS:=$(shell find local $(LSRC_SKIP) -name "*$(SRCSUFFIX)")
+SRCS:=$(SRCS) $(LSRCS)
 
-ESRCS:=$(shell find local -name "*$(SRCSUFFIX)")
-DEPENDS:=$(DEPENDS) $(addprefix $(TK_BD)/,$(ESRCS:$(SRCSUFFIX)=.d))
-SRCS:=$(SRCS) $(shell find local -maxdepth 1  -name "*$(SRCSUFFIX)")
-OBJS:=$(addprefix $(TK_BD)/,$(SRCS:$(SRCSUFFIX)=.o))
+ESRCS:=$(filter-out $(ESRCS) local/terk/%,$(shell find local -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
 
 ifeq ($(shell uname | grep -ci cygwin),0)
   PLATFORM_FLAGS:=$(PLATFORM_FLAGS) -DHAVE_READDIR_R
 endif
 
-platformBuild: $(addprefix $(TK_BD)/,$(ESRCS:$(SRCSUFFIX)=.o)) $(TK_BD)/libtekkotsu.a
+platformBuild: $(TK_BD)/$(LIBTEKKOTSU) $(PLATFORM_OBJS)
+
+$(TK_BD)/local/terk/peer/MRPLPeer.o $(TK_BD)/local/terk/TeRKPeerCommon.o $(TK_BD)/local/terk/SerialIO.o $(TK_BD)/local/terk/ObjectPingThread.o: %.o: $(if $(TEKKOTSU_PCH),$(TK_BD)/$(TEKKOTSU_PCH).gch) | $(TOOLS_BUILT_FLAG)
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(TK_BD)/%,%,$@)); \
+	echo "Compiling $$src... (reduced warnings)"; \
+	$(CXX) $(filter-out -Weffc++ -Wshadow,$(CXXFLAGS)) $(INCLUDE_PCH) -o $@ -c $$src > $*.log 2>&1; \
+	retval=$$?; \
+	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
+	test $$retval -eq 0;
+
+$(TK_BD)/local/DeviceDrivers/Dynamixel.o $(TK_BD)/local/DeviceDrivers/TeRKDriver.o $(TK_BD)/local/terk/QwerkBot.o: %.o: $(if $(TEKKOTSU_PCH),$(TK_BD)/$(TEKKOTSU_PCH).gch) | $(TOOLS_BUILT_FLAG)
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(TK_BD)/%,%,$@)); \
+	echo "Compiling $$src... (reduced warnings)"; \
+	$(CXX) $(filter-out -Weffc++,$(CXXFLAGS)) $(INCLUDE_PCH) -o $@ -c $$src > $*.log 2>&1; \
+	retval=$$?; \
+	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
+	test $$retval -eq 0;
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/MotionHook.h ./local/MotionHook.h
--- ../Tekkotsu_3.0/local/MotionHook.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/MotionHook.h	2007-08-27 18:14:16.000000000 -0400
@@ -0,0 +1,110 @@
+//-*-c++-*-
+#ifndef INCLUDED_MotionHook_h_
+#define INCLUDED_MotionHook_h_
+
+#include "Shared/RobotInfo.h"
+#include <vector>
+
+//! Interface for connections to remote hosts and hardware devices which should be polled with output values
+/*! - Override motionCheck() if your hardware needs to have a value specified for every output
+ *    on every update, regardless of whether it changes.
+ *  - Override motionUpdated() if you only need to process the outputs which have changed.
+ *
+ *  You can expect to be called every FrameTime*NumFrame milliseconds in terms of simulator time.
+ *  However, keep in mind this is relative to SharedGlobals::timeScale (Config.Speed) in terms of
+ *  wall-clock time, and is also subject to the simulator being paused, set to full-speed mode, or hitting 
+ *  a breakpoint in the debugger.  See enteringRealtime() and leavingRealtime() if you want updates 
+ *  when the user switches simulation modes, although there's still no way to get notification if a
+ *  debugger breakpoint is hit */
+class MotionHook {
+public:
+	//! constructor
+	MotionHook() : verbose(0), isFirstCheck(true) {}
+	
+	//! no-op destructor
+	virtual ~MotionHook() {}
+	
+	//! Called when motion process is starting
+	virtual void motionStarting() {}
+	
+	//! Called each time the motion process has polled active motion commands
+	/*! When in realtime mode, this should be called every FrameTime*NumFrames (defined in the RobotInfo)
+	 *  milliseconds if running at full speed.  See enteringRealtime() and leavingRealtime().
+	 *
+	 *  This default implementation checks to see which outputs have changed value since the last call and
+	 *  passes the summary on to motionUpdated().  #lastOutputs will be updated with the new values @e after
+	 *  the call to motionUpdated().
+	 *
+	 *  If you need to process all the outputs on every frame, you only need to override this function.
+	 *  Your subclass doesn't need to call the MotionHook implementation unless you want to have
+	 *  lastOutputs updated for you.
+	 *
+	 *  If you only need to process the @e changed outputs for each frame, override motionUpdated() instead.
+	 *  motionUpdated() is always called for each update, even if there aren't any changes, so you can still
+	 *  use that if there are some outputs which need to be updated every cycle.  */
+	virtual void motionCheck(const float outputs[][NumOutputs]) {
+		std::vector<size_t> changedIndices;
+		changedIndices.reserve(NumOutputs);
+		for(size_t i=0; i<NumOutputs; ++i) {
+			if(isFirstCheck) {
+				changedIndices.push_back(i);
+			} else {
+				for(size_t j=0; j<NumFrames; ++j) { // if *any* of the frames have changed, update the output
+					if(outputs[j][i]!=lastOutputs[i]) { // (not just checking last frame for each output)
+						changedIndices.push_back(i);
+						break;
+					}
+				}
+			}
+		}
+		motionUpdated(changedIndices,outputs);
+		for(size_t i=0; i<NumOutputs; ++i)
+			lastOutputs[i] = outputs[NumFrames-1][i];
+		isFirstCheck=false;
+	}
+	
+	//! Called by motionCheck(), after comparing the new output values to #lastOutputs, and before lastOutputs is updated
+	/*! Override this if you only need to send commands to the hardware for values that have changed. 
+	 *  This function is always called for each update, even though changedIndices might be empty. */
+	virtual void motionUpdated(const std::vector<size_t>& /*changedIndices*/, const float /*outputs*/[][NumOutputs]) {}
+	
+	//! Called when motion process is stopping
+	virtual void motionStopping() { isFirstCheck=true; }
+	
+	//! Called when the controller is going to be running in realtime mode, which is probably the normal mode you'd expect.
+	/*! No guarantees though!  You might be in realtime mode, but a debugger breakpoint will still pause things. */
+	virtual void enteringRealtime() {}
+	
+	//! Called when leaving realtime mode, which means you have no idea when motionCheck is going to be called in terms of wall-clock time.
+	/*! Argument set to true if entering full speed mode, which @e may mean motionCheck will be
+	 *  called at a high(er) frequency, or slower the computation is overwhelming the host hardware.
+	 *  However, if false, almost certainly indicates updates will be sparse.
+	 *
+	 *  A non-realtime mode might be triggered if the user wants to pause the simulator/controller to debug something...
+	 *  No guarantees though!  The debugger might catch a breakpoint and stop things, and this won't be called! */
+	virtual void leavingRealtime(bool /*isFullSpeed*/) {}
+	
+	//! Called by simulator thread to indicate level of verbosity for diagnostics and reporting errors
+	virtual void setMotionHookVerbose(int v) { verbose=v; }
+
+protected:
+	//! stores current verbosity
+	int verbose;
+	//! set to false following the first motionCheck, reset to true by motionStopping
+	bool isFirstCheck;
+	//! stores the last frame of the outputs, updated by motionCheck()
+	float lastOutputs[NumOutputs];
+};
+
+/*! @file
+ * @brief Describes MotionHook, an interface for connections to remote hosts and hardware devices which should be polled with output values
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.3 $
+ * $State: Exp $
+ * $Date: 2007/08/27 22:14:16 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/MotionHooks/IPCMotionHook.cc ./local/MotionHooks/IPCMotionHook.cc
--- ../Tekkotsu_3.0/local/MotionHooks/IPCMotionHook.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/MotionHooks/IPCMotionHook.cc	2007-06-03 13:03:26.000000000 -0400
@@ -0,0 +1,46 @@
+#include "IPCMotionHook.h"
+#include "IPC/MessageQueue.h"
+#include <sstream>
+
+using namespace std;
+
+IPCMotionHook::~IPCMotionHook() {
+	for(msgbuf_t::iterator it=regions.begin();it!=regions.end(); ++it)
+		(*it)->RemoveReference();
+}
+
+void IPCMotionHook::motionCheck(const float outputs[][NumOutputs]) {
+	RCRegion * r = getRegion();
+	memcpy(r->Base(),outputs,r->Size());
+	mq.sendMessage(r);
+	regions.push_back(r);
+}
+
+RCRegion* IPCMotionHook::getRegion() {
+	for(msgbuf_t::iterator it=regions.begin();it!=regions.end(); ++it) {
+		if((*it)->NumberOfReference()==1) {
+			RCRegion * ans=*it;
+			regions.erase(it);
+			return ans;
+		}
+	}
+	// no unused regions found, make a new one
+	static int count=0; // how many have we made (unique names for easier debugging)
+	stringstream ss;
+	ss << "MotionUpdate." << count++;
+	cout << "Created " << ss.str() << endl;
+	return new RCRegion(ss.str(),sizeof(float)*NumOutputs*NumFrames);
+}
+
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:26 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/MotionHooks/IPCMotionHook.h ./local/MotionHooks/IPCMotionHook.h
--- ../Tekkotsu_3.0/local/MotionHooks/IPCMotionHook.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/MotionHooks/IPCMotionHook.h	2007-06-03 13:03:26.000000000 -0400
@@ -0,0 +1,38 @@
+//-*-c++-*-
+#ifndef INCLUDED_IPCMotionHook_h_
+#define INCLUDED_IPCMotionHook_h_
+
+#include "local/MotionHook.h"
+#include <list>
+
+class MessageQueueBase;
+class RCRegion;
+
+//! description of IPCMotionHook
+class IPCMotionHook : public MotionHook {
+public:
+	IPCMotionHook(MessageQueueBase& q) : MotionHook(), mq(q), regions() {}
+	virtual ~IPCMotionHook();
+	
+	virtual void motionCheck(const float outputs[][NumOutputs]);
+	
+protected:
+	MessageQueueBase& mq;
+
+	RCRegion* getRegion();
+	typedef std::list<RCRegion* > msgbuf_t; //!< type of collection of shared data regions
+	msgbuf_t regions; //!< for efficiency, reuse old buffers -- oldest at front, most recently used at back
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/03 17:03:26 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/SoundPlayThread.cc ./local/SoundPlayThread.cc
--- ../Tekkotsu_3.0/local/SoundPlayThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/SoundPlayThread.cc	2007-10-12 12:55:04.000000000 -0400
@@ -0,0 +1,47 @@
+#include "SoundPlayThread.h"
+#include "Shared/Config.h"
+#include "Sound/SoundManager.h"
+
+//better to put this here instead of the header
+using namespace std; 
+
+void SoundPlayThread::reset() {
+	if(sndman->getNumPlaying()<=0 && isStarted())
+		stop();
+	else if(sndman->getNumPlaying()>0 && !isStarted())
+		start();
+}
+
+bool SoundPlayThread::launched() {
+	buffersInFlight=0;
+	//cout << "SoundPlayThread launched " << buffersInFlight << ' ' << sndman->getNumPlaying() << endl;
+	return sndman->getNumPlaying()>0;
+}
+
+bool SoundPlayThread::poll() {
+	if(buffersInFlight>0)
+		buffersInFlight--; // poll has timed out, remove a buffer from in-flight
+	size_t tgtsize = BUFFER_TIME*(config->sound.sample_bits/8)*config->sound.sample_rate/1000;
+	if(bufsize!=tgtsize) {
+		delete buf;
+		buf = new char[bufsize=tgtsize];
+	}
+	while(buffersInFlight<NUM_BUFFERS) {
+		sndman->CopyTo(buf,bufsize);
+		// interface with host hardware to play the sound...?
+		buffersInFlight++;
+	}
+	//cout << "SoundPlayThread polled " << buffersInFlight << ' ' << sndman->getNumPlaying() << endl;
+	return sndman->getNumPlaying()>0;
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:55:04 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/SoundPlayThread.h ./local/SoundPlayThread.h
--- ../Tekkotsu_3.0/local/SoundPlayThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/SoundPlayThread.h	2007-02-16 15:18:23.000000000 -0500
@@ -0,0 +1,40 @@
+//-*-c++-*-
+#ifndef INCLUDED_SoundPlayThread_h_
+#define INCLUDED_SoundPlayThread_h_
+
+#include "IPC/PollThread.h"
+
+class SoundPlayThread : public PollThread {
+public:
+	static const long BUFFER_TIME=32;
+	static const unsigned int NUM_BUFFERS=2;
+	SoundPlayThread() : PollThread(0L,BUFFER_TIME,true,false), buf(NULL), bufsize(0), buffersInFlight(0) {}
+	virtual ~SoundPlayThread() { delete buf; buf=NULL; }
+	
+	void reset();
+	
+protected:
+	virtual bool launched();
+	virtual bool poll();
+	
+	char * buf;
+	size_t bufsize;
+	unsigned int buffersInFlight;
+	
+private:
+	SoundPlayThread(const SoundPlayThread& l); //!< don't call
+	SoundPlayThread& operator=(const SoundPlayThread& l); //!< don't call
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/02/16 20:18:23 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/minisim.h ./local/minisim.h
--- ../Tekkotsu_3.0/local/minisim.h	2006-07-13 13:25:50.000000000 -0400
+++ ./local/minisim.h	2007-11-15 12:25:10.000000000 -0500
@@ -40,7 +40,7 @@
 		WirelessThread() : Thread() {}
 		//! destructor -- stop thread
 		virtual ~WirelessThread() {
-			if(isRunning()) {
+			if(isStarted()) {
 				stop();
 				join();
 			}
@@ -62,8 +62,23 @@
 	void initialize() {
 #ifdef TK_ENABLE_CONFIG
 		if(config==NULL) {
-			string configfile=TK_cstr(TK_ENABLE_CONFIG);
-			config=new Config(configfile.size()==0 ? "tekkotsu.cfg" : configfile);
+			::config = new Config();
+			::config->setFileSystemRoot("ms");
+			std::string configfile=TK_cstr(TK_ENABLE_CONFIG);
+			if(configfile.size()!=0) {
+				if(::config->loadFile(configfile.c_str())==0)
+					std::cerr << std::endl << " *** ERROR: Could not load configuration file config/tekkotsu.xml *** " << std::endl << std::endl;
+			} else {
+				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;
+				}
+				if(::config->loadFile("config/sim_ovrd.xml")==0)
+					if(::config->loadFile("config/sim_ovrd.cfg")!=0)
+						std::cerr << "Successfully imported settings from old-format simulator.cfg" << std::endl;
+			}
 		}
 #endif
 		
@@ -79,15 +94,15 @@
 #endif
 #ifdef TK_ENABLE_SOUTSERR
 #  ifdef TK_ENABLE_WIRELESS
-		sout=wireless->socket(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);
 #  else
 		sout=new Socket(0);
 		serr=new Socket(1);
 #  endif
-		serr->setFlushType(SocketNS::FLUSH_BLOCKING);
+		serr->setFlushType(Socket::FLUSH_BLOCKING);
 		sout->setTextForward();
 		serr->setForward(sout);
 #  ifdef TK_ENABLE_WIRELESS
@@ -103,7 +118,7 @@
 #  ifdef TK_ENABLE_WIRELESS //but if wireless is enabled, might as well define them
 		sout=new Socket(-1);
 		serr=new Socket(-1);
-		serr->setFlushType(SocketNS::FLUSH_BLOCKING);
+		serr->setFlushType(Socket::FLUSH_BLOCKING);
 		sout->setTextForward();
 		serr->setForward(sout);
 #  endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Main.cc ./local/sim/Main.cc
--- ../Tekkotsu_3.0/local/sim/Main.cc	2006-09-26 17:44:30.000000000 -0400
+++ ./local/sim/Main.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,418 +0,0 @@
-#include "Main.h"
-#include "SoundPlay.h"
-#include "Motion.h"
-#include "Simulator.h"
-#include "TimerExecThread.h"
-
-#include "IPC/RegionRegistry.h"
-#include "IPC/MessageReceiver.h"
-#include "IPC/PollThread.h"
-#include "Motion/Kinematics.h"
-#include "Motion/PostureEngine.h"
-#include "Wireless/Wireless.h"
-#include "Shared/ProjectInterface.h"
-#include "Behaviors/BehaviorBase.h"
-#include "Events/DataEvent.h"
-#include "Events/EventRouter.h"
-#include "Shared/Config.h"
-#include "Shared/MarkScope.h"
-
-#include "Events/EventBase.h"
-#include "Events/LocomotionEvent.h"
-#include "Events/TextMsgEvent.h"
-#include "Events/VisionObjectEvent.h"
-
-Main::Main()
-	: Process(getID(),getClassName()),
-	sounds(ipc_setup->registerRegion(SoundPlay::getSoundPlayID(),sizeof(sim::SoundPlayQueue_t))),
-	motions(ipc_setup->registerRegion(Motion::getMotionCommandID(),sizeof(sim::MotionCommandQueue_t))),
-	events(ipc_setup->registerRegion(getEventsID(),sizeof(sim::EventQueue_t))),
-	cameraFrames(ipc_setup->registerRegion(Simulator::getCameraQueueID(),sizeof(sim::CameraQueue_t))),
-	sensorFrames(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
-	timerWakeup(ipc_setup->registerRegion(Simulator::getTimerWakeupID(),sizeof(sim::TimerWakeup_t))),
-	statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
-	motionmanager(ipc_setup->registerRegion(Motion::getMotionManagerID(),sizeof(MotionManager))),
-	soundmanager(ipc_setup->registerRegion(SoundPlay::getSoundManagerID(),sizeof(SoundManager))),
-	worldstatepool(ipc_setup->registerRegion(getWorldStatePoolID(),sizeof(WorldStatePool))),
-	motionProf(ipc_setup->registerRegion(Motion::getMotionProfilerID(),sizeof(motionProfiler_t))),
-	soundProf(ipc_setup->registerRegion(SoundPlay::getSoundProfilerID(),sizeof(soundProfiler_t))),
-	visrecv(NULL), sensrecv(NULL), evtrecv(NULL), timerrecv(NULL), statusrecv(NULL), timerExec(NULL),
-	visionRead(true), wireless_thread(), worldStateCache(), behaviorLock(*worldstatepool),
-	curimgregion(NULL), img(), lastVisionSN(-1U), lastSensorSN(-1U), lastSensorUpdateTime(0)
-{
-	new (&(*events)) sim::EventQueue_t;
-	new (&(*worldstatepool)) WorldStatePool;
-	state=NULL;
-	motman=&(*motionmanager);
-	sndman=&(*soundmanager);
-	::mainProfiler=new mainProfiler_t;
-	::motionProfiler=&(*motionProf);
-	::soundProfiler=&(*soundProf);
-
-	//Setup wireless
-	wireless = new Wireless();
-	wireless->setCallbackLock(behaviorLock);
-	sout=wireless->socket(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);
-	wireless->setDaemon(sout);
-	wireless->setDaemon(serr);
-	serr->setFlushType(SocketNS::FLUSH_BLOCKING);
-	sout->setTextForward();
-	serr->setForward(sout);
-
-	//Setup Kinematics
-	kine=new Kinematics();
-	
-	//need to register any events which we might be sending or receiving
-	EventTranslator::registerPrototype<EventBase>();
-	EventTranslator::registerPrototype<LocomotionEvent>();
-	EventTranslator::registerPrototype<TextMsgEvent>();
-	EventTranslator::registerPrototype<VisionObjectEvent>();
-
-	//EventRouter and Config are set up for all processes by main() before fork
-}
-
-Main::~Main() {
-}
-
-
-void Main::DoStart() {
-try {
-	Process::DoStart();
-	//These are constructed by other processes, so need to wait
-	//until the construction runlevel is complete
-	sndman->InitAccess(*sounds);
-	motman->InitAccess(*motions,behaviorLock);
-
-	wireless->listen(sout, config->main.console_port);
-	wireless->listen(serr, config->main.stderr_port);
-	wireless_thread.start();
-	statusrecv=new MessageReceiver(*statusRequest,statusReport);
-
-	evtrecv=new MessageReceiver(*events,gotEvent,false);
-	visrecv=new MessageReceiver(*cameraFrames,gotCamera,false);
-	sensrecv=new MessageReceiver(*sensorFrames,gotSensors,false);
-	timerrecv=new MessageReceiver(*timerWakeup,gotTimer,false);
-	timerExec=new TimerExecThread(behaviorLock,false);
-	
-} catch(const std::exception& ex) {
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStart",&ex))
-		throw;
-} catch(...) {
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStart",NULL))
-		throw;
-}
-}
-
-void Main::run() {
-try {
-	{
-		MarkScope bl(behaviorLock);
-		ProjectInterface::startupBehavior().DoStart();
-		globals->setNextTimer(erouter->getNextTimer());
-	}
-	evtrecv->start();
-	visrecv->start();
-	sensrecv->start();
-	timerrecv->start();
-	timerExec->reset();
-	
-	Process::run();
-
-	sensrecv->finish();
-	visrecv->finish();
-	evtrecv->finish();
-	timerrecv->finish();
-	
-	{
-		MarkScope bl(behaviorLock);
-		ProjectInterface::startupBehavior().DoStop();
-		globals->setNextTimer(erouter->getNextTimer());
-	}
-	timerExec->reset();
-
-} catch(const std::exception& ex) {
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main 'run' runlevel (startupBehavior initialization and startup)",&ex))
-		throw;
-} catch(...) {
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main 'run' runlevel (startupBehavior initialization and startup)",NULL))
-		throw;
-}
-}
-
-void Main::DoStop() {
-try {
-
-	delete sensrecv;
-	sensrecv=NULL;
-	delete visrecv;
-	visrecv=NULL;
-	delete evtrecv;
-	evtrecv=NULL;
-	delete timerrecv;
-	timerrecv=NULL;
-	delete statusrecv;
-	statusrecv=NULL;
-	
-	motman->RemoveAccess();
-	
-	if(curimgregion!=NULL)
-		curimgregion->RemoveReference();
-
-	wireless_thread.stop();
-	wireless_thread.join();
-	wireless->setDaemon(sout,false);
-	wireless->close(sout);
-	sout=NULL;
-	wireless->setDaemon(serr,false);
-	wireless->close(serr);
-	serr=NULL;
-	
-	Process::DoStop();
-
-} catch(const std::exception& ex) {
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStop",&ex))
-		throw;
-} catch(...) {
-	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStop",NULL))
-		throw;
-}
-}
-
-bool Main::gotCamera(RCRegion* msg) {
-	if(msg==NULL)
-		return true;
-	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	ASSERTRETVAL(main!=NULL,"gotCamera, but not within Main process!",true);
-	MarkScope bl(main->behaviorLock);
-	PROFSECTION("GotImage()",*mainProfiler);
-
-	try {
-		BufferedImageGenerator::ImageSource& img=main->img;
-		
-		bool verbose;
-		unsigned int sn;
-		string file;
-		unsigned int payload;
-		char* buf=LoadFileThread::deserializeHeader(msg->Base(),msg->Size(),&verbose,&sn,&file,NULL,&payload);
-		unsigned int remain=msg->Size()-(buf-msg->Base());
-		if(verbose && sn-main->lastVisionSN!=1)
-			cout << "Main dropped " << (sn-main->lastVisionSN-1) << " camera frame(s)" << endl;
-		if(verbose) {
-			if(payload==0)
-				cout << "Main received image heartbeat at " << get_time() << endl;
-			else
-				cout << "Main received image data \"" << file << "\" at " << get_time() << endl;
-		}
-		
-		if(payload==0) {
-			if(img.width==0 || img.height==0 || img.img==NULL)
-				return true; // can't do the heartbeat, don't have an initial image to replicate
-			img.frameIndex++;
-		} else {
-			LoadSave::decodeIncT(img.width,buf,remain);
-			LoadSave::decodeIncT(img.height,buf,remain);
-			LoadSave::decodeIncT(img.channels,buf,remain);
-			LoadSave::decodeIncT(img.frameIndex,buf,remain);
-			int l;
-			LoadSave::decodeInc(l,buf,remain);
-			if(l!=0) {
-				img.layer = (l<0)?ProjectInterface::defRawCameraGenerator->getNumLayers()+l:l-1;
-			} else {
-				// using "automatic" mode, pick the layer closest to resolution of provided image
-				// assumes each layer doubles in size, with smallest layer at 0
-				float fullRes=sqrt(CameraResolutionX*CameraResolutionY); // from RobotInfo
-				float givenRes=sqrt(img.width*img.height);
-				if(givenRes==0) {
-					cerr << "Received empty image!" << endl;
-					img.layer=0;
-				} else {
-					float ratio=log2f(givenRes/fullRes);
-					int layerOff=static_cast<int>(rintf(ratio));
-					int tgtLayer=static_cast<int>(ProjectInterface::fullLayer)+layerOff;
-					if(tgtLayer<0)
-						img.layer=0;
-					else if(static_cast<unsigned int>(tgtLayer)>=ProjectInterface::defRawCameraGenerator->getNumLayers())
-						img.layer=ProjectInterface::defRawCameraGenerator->getNumLayers()-1;
-					else
-						img.layer=tgtLayer;
-					if(static_cast<unsigned int>(tgtLayer)!=img.layer)
-						cerr << "Image dimensions of " << img.width << "x" << img.height << " are well beyond the available resolution layers (full is " << CameraResolutionX << "x" << CameraResolutionY << ")" << endl;
-				}
-			}
-			img.img=reinterpret_cast<unsigned char*>(buf);
-			msg->AddReference();
-			if(main->curimgregion!=NULL)
-				main->curimgregion->RemoveReference();
-			main->curimgregion=msg;
-		}
-		DataEvent<BufferedImageGenerator::ImageSource> dev(img,EventBase::visOFbkEGID,0,EventBase::activateETID);
-		erouter->postEvent(dev);
-		dev.setTypeID(EventBase::statusETID);
-		erouter->postEvent(dev);
-		dev.setTypeID(EventBase::deactivateETID);
-		erouter->postEvent(dev);
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during camera frame processing",&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during camera frame processing",NULL))
-			throw;
-	}
-	try {
-		erouter->processTimers();
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
-			throw;
-	}
-	if(globals->setNextTimer(erouter->getNextTimer()))
-		main->timerExec->reset();
-	return true;
-}
-
-bool Main::gotSensors(RCRegion* msg) {
-	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	ASSERTRETVAL(main!=NULL,"gotSensors, but not within Main process!",true);
-
-	PROFSECTION("GotSensorFrame()",*mainProfiler);
-	MarkScope l(main->behaviorLock);
-
-	string exceptionPhase="sensor";
-	try {
-		unsigned int orgSN=main->lastSensorSN;
-		WorldStatePool::UpdateInfo * info=main->worldstatepool->isUnread(*msg,globals->motion.frameNumber,main->lastSensorSN,false,globals->motion.override);
-		int dif=0;
-		if(info!=NULL) {
-			bool generateFeedback=((info->payloadSize==0 && !info->dataInQueue) || globals->motion.override) && globals->motion.feedbackDelay>=0;
-			EntryPoint::WorldStateWrite wsw(info->frameNumber);
-			MarkScope lw(main->behaviorLock, wsw);
-			if(state!=NULL && wsw.frame==globals->motion.frameNumber) {
-				// ^-- make sure a newer one didn't come in while we were waiting for the lock
-				// (if one did, we'll report the accumulated drops next time we get one we don't drop)
-				if(main->worldstatepool->read(*info,wsw,generateFeedback,globals->motion.zeroPIDFeedback,NULL)) {
-					if(wsw.frame-main->lastSensorSN!=1 && info->verbose)
-						cout << ProcessID::getIDStr() << " dropped " << (wsw.frame-main->lastSensorSN-1) << " sensor frame(s)" << endl;
-					main->lastSensorSN=wsw.frame;
-				}
-				if(wsw.getComplete()) {
-					dif=state->lastSensorUpdateTime - main->lastSensorUpdateTime;
-					ASSERT(dif>=0,"sensor update time is negative? " << dif);
-					main->lastSensorUpdateTime=state->lastSensorUpdateTime;
-					erouter->postEvent(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,dif,"SensorSourceID::UpdatedSID",1);
-					exceptionPhase="timer";
-					erouter->processTimers();
-				}
-			}
-		} else if(orgSN!=main->lastSensorSN) {
-			// received update after sensor frame was already parsed by other process
-			l.reset(); //update state
-			dif=state->lastSensorUpdateTime - main->lastSensorUpdateTime;
-			ASSERT(dif>=0,"sensor update time is negative? " << dif);
-			main->lastSensorUpdateTime=state->lastSensorUpdateTime;
-			erouter->postEvent(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,dif,"SensorSourceID::UpdatedSID",1);
-			exceptionPhase="timer";
-			erouter->processTimers();
-		}
-		if(dif==0) {
-			exceptionPhase="timer";
-			erouter->processTimers();
-		}
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,("Occurred during "+exceptionPhase+" processing").c_str(),&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,("Occurred during "+exceptionPhase+" processing").c_str(),NULL))
-			throw;
-	}
-	if(globals->setNextTimer(erouter->getNextTimer()))
-		main->timerExec->reset();
-	return true;
-}
-
-bool Main::gotEvent(RCRegion* msg) {
-	if(msg==NULL)
-		return true;
-	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	ASSERTRETVAL(main!=NULL,"gotEvent, but not within Main process!",true);
-	MarkScope l(main->behaviorLock);
-	EventBase* evt=NULL;
-	try {
-		evt=EventTranslator::decodeEvent(msg->Base(),msg->Size());
-		if(evt==NULL) {
-			cerr << "ERROR: Main::gotEvent() failed to decode message" << endl;
-			return true;
-		}
-		if(evt->getGeneratorID()==EventBase::sensorEGID)
-			main->lastSensorUpdateTime=evt->getTimeStamp();
-		erouter->postEvent(*evt);
-	} catch(const std::exception& ex) {
-		std::string emsg("Occurred during inter-process event processing");
-		if(evt!=NULL)
-			emsg+=": "+evt->getName();
-		delete evt;
-		evt=NULL;
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,emsg.c_str(),&ex))
-			throw;
-	} catch(...) {
-		std::string emsg("Occurred during inter-process event processing");
-		if(evt!=NULL)
-			emsg+=": "+evt->getName();
-		delete evt;
-		evt=NULL;
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,emsg.c_str(),NULL))
-			throw;
-	}
-	delete evt;
-	evt=NULL;
-	try {
-		erouter->processTimers();
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
-			throw;
-	}
-	if(globals->setNextTimer(erouter->getNextTimer()))
-		main->timerExec->reset();
-	return true;
-}
-
-bool Main::gotTimer(RCRegion* /*msg*/) {
-	Main * main=dynamic_cast<Main*>(Process::getCurrent());
-	ASSERTRETVAL(main!=NULL,"gotTimer, but not within Main process!",true);
-
-	ASSERTRETVAL(main->timerExec!=NULL,"timerExec thread is NULL when timer wakeup received",true);
-	main->timerExec->reset();
-	
-	if(globals->timeScale<=0) {
-		MarkScope bl(main->behaviorLock);
-		try {
-			erouter->processTimers();
-		} catch(const std::exception& ex) {
-			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
-				throw;
-		} catch(...) {
-			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
-				throw;
-		}
-		globals->setNextTimer(erouter->getNextTimer());
-		// don't need to reset timerExec (again) because we're only here if speed<=0, in which case timerExec isn't running	main->timerExec->reset();
-	}
-	return true;
-}
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.46 $
- * $State: Exp $
- * $Date: 2006/09/26 21:44:30 $
- */
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Main.h ./local/sim/Main.h
--- ../Tekkotsu_3.0/local/sim/Main.h	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/Main.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,84 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_Main_h_
-#define INCLUDED_Main_h_
-
-#include "Process.h"
-#include "sim.h"
-#include "IPC/SharedObject.h"
-#include "SharedGlobals.h"
-#include "Motion/MotionManager.h"
-#include "Sound/SoundManager.h"
-#include "Shared/WorldStatePool.h"
-#include "local/EntryPoint.h"
-#include "Vision/BufferedImageGenerator.h"
-#include "Shared/Profiler.h"
-
-class Main : public Process {
-public:
-	//! constructor
-	Main();
-	//! destructor
-	~Main();
-
-	virtual void DoStart();
-	virtual void DoStop();
-	virtual void run();
-
-	static const char* getClassName() { return "Main"; }
-	static ProcessID::ProcessID_t getID() { return ProcessID::MainProcess; }
-	
-	static const char * getEventsID() { return "MainEvents"; }
-	static const char * getWorldStatePoolID() { return "WorldStatePool"; }
-	
-protected:
-	SharedObject<sim::SoundPlayQueue_t> sounds;
-	SharedObject<sim::MotionCommandQueue_t> motions;
-	SharedObject<sim::EventQueue_t> events;
-	SharedObject<sim::CameraQueue_t> cameraFrames;
-	SharedObject<sim::SensorQueue_t> sensorFrames;
-	SharedObject<sim::TimerWakeup_t> timerWakeup;
-	SharedObject<sim::StatusRequest_t> statusRequest;
-	SharedObject<MotionManager> motionmanager;
-	SharedObject<SoundManager> soundmanager;
-	SharedObject<WorldStatePool> worldstatepool;
-	SharedObject<motionProfiler_t> motionProf;
-	SharedObject<soundProfiler_t> soundProf;
-	
-	class MessageReceiver * visrecv;
-	class MessageReceiver * sensrecv;
-	class MessageReceiver * evtrecv;
-	class MessageReceiver * timerrecv;
-	class MessageReceiver * statusrecv;
-	class TimerExecThread * timerExec;
-	bool visionRead;
-	WirelessThread wireless_thread;
-	WorldState worldStateCache; //!< used for temporary storage when parsing sensor frames, allocation here avoids rather costly constructor call on every sensor frame
-	EntryPoint behaviorLock;
-
-	static bool gotCamera(RCRegion* msg);
-	static bool gotSensors(RCRegion* msg);
-	static bool gotEvent(RCRegion* msg);
-	static bool gotTimer(RCRegion* msg);
-	RCRegion * curimgregion;
-	BufferedImageGenerator::ImageSource img; //!< root data source for vision stream, references data in #curimg
-	unsigned int lastVisionSN; //!< serial number of last camera frame, just so we can give warning message when we drop (if verbose is set)
-	unsigned int lastSensorSN; //!< serial number of last sensor frame, just so we can give warning message when we drop (if verbose is set)
-	unsigned int lastSensorUpdateTime; //!< time that last sensor update was posted
-	
-private:
-	Main(const Main&); //!< don't call (copy constructor)
-	Main& operator=(const Main&); //!< don't call (assignment operator)
-};
-
-/*! @file
- * @brief Defines Main, which DESCRIPTION
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.17 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Motion.cc ./local/sim/Motion.cc
--- ../Tekkotsu_3.0/local/sim/Motion.cc	2006-08-31 15:01:46.000000000 -0400
+++ ./local/sim/Motion.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,198 +0,0 @@
-#include "Motion.h"
-#include "Main.h"
-#include "SoundPlay.h"
-#include "Simulator.h"
-#include "MotionExecThread.h"
-#include "IPC/RegionRegistry.h"
-#include "IPC/MessageReceiver.h"
-#include "Motion/Kinematics.h"
-#include "Wireless/Wireless.h"
-#include "Events/EventRouter.h"
-#include "Shared/MarkScope.h"
-
-#include "Events/EventBase.h"
-#include "Events/LocomotionEvent.h"
-#include "Events/TextMsgEvent.h"
-#include "Events/VisionObjectEvent.h"
-
-Motion::Motion()
-	: Process(getID(),getClassName()),
-	sounds(ipc_setup->registerRegion(SoundPlay::getSoundPlayID(),sizeof(sim::SoundPlayQueue_t))),
-	motions(ipc_setup->registerRegion(getMotionCommandID(),sizeof(sim::MotionCommandQueue_t))),
-	events(ipc_setup->registerRegion(Main::getEventsID(),sizeof(sim::EventQueue_t))),
-	sensorFrames(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
-	statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
-	motionmanager(ipc_setup->registerRegion(getMotionManagerID(),sizeof(MotionManager))),
-	soundmanager(ipc_setup->registerRegion(SoundPlay::getSoundManagerID(),sizeof(SoundManager))),
-	worldstatepool(ipc_setup->registerRegion(Main::getWorldStatePoolID(),sizeof(WorldStatePool))),
-	motionWakeup(ipc_setup->registerRegion(Simulator::getMotionWakeupID(),sizeof(sim::MotionWakeup_t))),
-	motionProf(ipc_setup->registerRegion(getMotionProfilerID(),sizeof(motionProfiler_t))),
-	etrans(NULL), sensrecv(NULL), statusrecv(NULL), wakeuprecv(NULL), motionExec(NULL),
-	wireless_thread(), motionLock(*worldstatepool), lastSensorSN(-1U)
-{
-	new (&(*motions)) sim::MotionCommandQueue_t;
-	new (&(*motionmanager)) MotionManager;
-	new (&(*motionProf)) motionProfiler_t;
-	motman=&(*motionmanager);
-	motman->InitAccess(*motions,motionLock);
-	sndman=&(*soundmanager);
-	state=NULL;
-	::motionProfiler=&(*motionProf);
-	
-	//Setup wireless
-	wireless = new Wireless();
-	sout=wireless->socket(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);
-	wireless->setDaemon(sout);
-	wireless->setDaemon(serr);
-	serr->setFlushType(SocketNS::FLUSH_BLOCKING);
-	sout->setTextForward();
-	serr->setForward(sout);
-
-	//Setup Kinematics
-	kine=new Kinematics();
-	
-	//need to register any events which we might be sending or receiving
-	EventTranslator::registerPrototype<EventBase>();
-	EventTranslator::registerPrototype<LocomotionEvent>();
-	EventTranslator::registerPrototype<TextMsgEvent>();
-	EventTranslator::registerPrototype<VisionObjectEvent>();
-
-	//EventRouter and Config are set up for all processes by main() before fork
-}
-
-Motion::~Motion() {
-	delete etrans;
-	etrans=NULL;
-	MotionManager::setTranslator(NULL);
-}
-
-void Motion::DoStart() {
-	Process::DoStart();
-	//These are constructed by other processes, so need to wait
-	//until the construction runlevel is complete before we access them
-	sndman->InitAccess(*sounds);
-	etrans=new IPCEventTranslator(*events);
-	MotionManager::setTranslator(etrans);
-	
-	// Set up Event Translator to trap and send events to main process
-	//send everything over except erouter events
-	for(unsigned int i=0; i<EventBase::numEGIDs; i++)
-		if(i!=EventBase::erouterEGID)
-			erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
-	
-	wireless_thread.start();
-	sensrecv=new MessageReceiver(*sensorFrames,gotSensors);
-	statusrecv=new MessageReceiver(*statusRequest,statusReport);
-	wakeuprecv=new MessageReceiver(*motionWakeup,gotWakeup,false);
-
-	motionExec=new MotionExecThread(motionLock);
-}
-
-
-void Motion::run() {
-	motionExec->reset(); //starts the thread if appropriate
-	wakeuprecv->start();
-	Process::run();
-	wakeuprecv->stop();
-}
-
-void Motion::DoStop() {
-	wakeuprecv->finish();
-	statusrecv->finish();
-	sensrecv->finish();
-
-	delete motionExec;
-	motionExec=NULL;
-	delete wakeuprecv;
-	wakeuprecv=NULL;
-	delete statusrecv;
-	statusrecv=NULL;
-	delete sensrecv;
-	sensrecv=NULL;
-	
-	erouter->removeTrapper(etrans);
-	motman->RemoveAccess();
-
-	wireless_thread.stop();
-	wireless_thread.join();
-	
-	Process::DoStop();
-}
-
-bool Motion::gotWakeup(RCRegion* /*msg*/) {
-	Motion * motion=dynamic_cast<Motion*>(Process::getCurrent());
-	ASSERTRETVAL(motion!=NULL,"gotWakeup, but not within motion process!",true);
-	ASSERTRETVAL(motion->motionExec!=NULL,"motionExec thread is NULL when motion wakeup received",true);
-	
-	MarkScope l(motion->motionLock);
-	if(globals->timeScale<=0 && get_time()>=globals->getNextMotion())
-		motion->motionExec->poll();
-	motion->motionExec->reset(); //reset will set globals->getNextMotion(), so have to do this after the poll itself
-	return true;
-}
-
-bool Motion::gotSensors(RCRegion* msg) {
-	Motion * motion=dynamic_cast<Motion*>(Process::getCurrent());
-	ASSERTRETVAL(motion!=NULL,"gotSensors, but not within Motion process!",true);
-	
-	PROFSECTION("GotSensorFrame()",*motionProfiler);
-	MarkScope l(motion->motionLock);
-	
-	EntryPoint::WorldStateWrite wsw(-1U);
-	try {
-		WorldStatePool::UpdateInfo * info=motion->worldstatepool->isUnread(*msg,globals->motion.frameNumber,motion->lastSensorSN,globals->motion.feedbackDelay>=0,globals->motion.override);
-		int dif=0;
-		if(info!=NULL) {
-			bool generateFeedback=((info->payloadSize==0 && !info->dataInQueue) || globals->motion.override) && globals->motion.feedbackDelay>=0;
-			const PostureEngine* pose = generateFeedback ? &motion->motionExec->getPostureFeedback() : NULL;
-			wsw.frame=info->frameNumber;
-			MarkScope lw(motion->motionLock, wsw);
-			if(state==NULL || wsw.frame<globals->motion.frameNumber) {
-				//a newer one came in while we were waiting for the lock (we'll report the accumulated drops next time we get one we don't drop)
-				return true;
-			}
-			ASSERT((wsw.getStatus()&WorldStatePool::FEEDBACK_APPLIED)==0,"motion feedback already applied?");
-			bool completedPartial=!wsw.getComplete() && (wsw.getStatus()&WorldStatePool::SENSORS_APPLIED)!=0;
-			if(generateFeedback && info->verbose)
-				cout << "Motion filling in sensor feedback" << endl;
-			ASSERT(!completedPartial || generateFeedback,"partially complete, yet no feedback?");
-			if(motion->worldstatepool->read(*info,wsw,generateFeedback,globals->motion.zeroPIDFeedback,pose)) {
-				if(wsw.frame-motion->lastSensorSN!=1 && info->verbose)
-					cout << ProcessID::getIDStr() << " dropped " << (wsw.frame-motion->lastSensorSN-1) << " sensor frame(s)" << endl;
-				motion->lastSensorSN=wsw.frame;
-			}
-			if(completedPartial && wsw.getComplete()) { // was partial before, now completed as well
-				dif=state->lastSensorUpdateTime - wsw.src->lastSensorUpdateTime;
-				ASSERT(dif>=0,"sensor update time is negative? " << dif << ' ' << state << ' ' << wsw.src);
-			}
-		}
-		if(dif>0) {
-			// need to notify main that the sensor update it started is now complete
-			// do it outside the write lock so if main gets this instantly it can use the new data
-			// some sleight of hand here -- we've previously registered an IPCEventTranslator as an event trapper.  By posting here, the event will be sent to the Main process
-			erouter->postEvent(EventBase::sensorEGID,SensorSourceID::UpdatedSID,EventBase::statusETID,dif,"SensorSourceID::UpdatedSID",1);
-		}
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during sensor processing",&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during sensor processing",NULL))
-			throw;
-	}
-	
-	return true;
-}
-	
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.21 $
- * $State: Exp $
- * $Date: 2006/08/31 19:01:46 $
- */
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Motion.h ./local/sim/Motion.h
--- ../Tekkotsu_3.0/local/sim/Motion.h	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/Motion.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,76 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_Motion_h_
-#define INCLUDED_Motion_h_
-
-#include "Process.h"
-#include "sim.h"
-#include "IPC/ProcessID.h"
-#include "IPC/SharedObject.h"
-#include "SharedGlobals.h"
-#include "Motion/MotionManager.h"
-#include "Sound/SoundManager.h"
-#include "Shared/WorldStatePool.h"
-#include "Shared/Profiler.h"
-#include "local/EntryPoint.h"
-#include <list>
-
-class Motion : public Process {
-public:
-	//! constructor
-	Motion();
-	//! destructor
-	~Motion();
-
-	virtual void DoStart();
-	virtual void run();
-	virtual void DoStop();
-
-	static const char * getClassName() { return "Motion"; }
-	static ProcessID::ProcessID_t getID() { return ProcessID::MotionProcess; }
-	
-	static const char * getMotionCommandID() { return "MotionCommands"; }
-	static const char * getMotionManagerID() { return "MotionManager"; }
-	static const char * getMotionProfilerID() { return "MotionProfiler"; }
-
-protected:
-	SharedObject<sim::SoundPlayQueue_t> sounds;
-	SharedObject<sim::MotionCommandQueue_t> motions;
-	SharedObject<sim::EventQueue_t> events;
-	SharedObject<sim::SensorQueue_t> sensorFrames;
-	SharedObject<sim::StatusRequest_t> statusRequest;
-	SharedObject<MotionManager> motionmanager;
-	SharedObject<SoundManager> soundmanager;
-	SharedObject<WorldStatePool> worldstatepool;
-	SharedObject<sim::MotionWakeup_t> motionWakeup;
-	SharedObject<motionProfiler_t> motionProf;
-	
-	IPCEventTranslator * etrans;
-	class MessageReceiver * sensrecv;
-	class MessageReceiver * statusrecv;
-	class MessageReceiver * wakeuprecv;
-	class MotionExecThread * motionExec;
-	WirelessThread wireless_thread;
-
-	EntryPoint motionLock;
-	
-	static bool gotSensors(RCRegion* msg);
-	static bool gotWakeup(RCRegion* msg);
-	unsigned int lastSensorSN;
-	
-private:
-	Motion(const Motion&); //!< don't call (copy constructor)
-	Motion& operator=(const Motion&); //!< don't call (assignment operator)
-};
-
-/*! @file
- * @brief Defines Motion, which DESCRIPTION
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.11 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/MotionExecThread.cc ./local/sim/MotionExecThread.cc
--- ../Tekkotsu_3.0/local/sim/MotionExecThread.cc	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/MotionExecThread.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,184 +0,0 @@
-#include "MotionExecThread.h"
-#include "SharedGlobals.h"
-#include "Shared/ProjectInterface.h"
-#include "Shared/WorldState.h"
-#include "Shared/MarkScope.h"
-#include "Motion/MotionManager.h"
-#include "IPC/MessageQueue.h"
-#include "Shared/debuget.h"
-#include "Shared/Profiler.h"
-#include "local/EntryPoint.h"
-
-using namespace std; 
-
-void MotionExecThread::reset() {
-	globals->setNextMotion(getNextMotion());
-	if(globals->timeScale<=0 && isRunning())
-		stop();
-	else if(globals->timeScale>0 && !isRunning())
-		start();
-	else if(isRunning()) {
-		interrupt();
-	}
-}
-
-/*void MotionExecThread::start() {
-	lastPoll=-1U;
-	launching=initialPoll=true;
-	Thread::start(); //skipping PollThread::start() because we don't want to reset startTime
-}*/
-
-bool MotionExecThread::poll() {
-	MarkScope l(motionLock);
-	PROFSECTION("ReadySendJoints()",*motionProfiler);
-	//this is OK: (can happen if the thread gets behind and the last one finished late, still want to do the current one, which appears to come early)
-	//ASSERTRETVAL(get_time()>=globals->getNextMotion()-1,"MotionExecThread::poll() early (time="<<get_time()<< " vs. nextMotion=" <<globals->getNextMotion()<<")",true);
-	if(get_time()<globals->getNextMotion())
-		return true;
-	try {
-		if(globals->motion.verbose)
-			cout << "Motion processing at " << get_time() << endl;
-		const unsigned int bufTime=NumFrames*FrameTime;
-		unsigned int tgtSize=(globals->motion.feedbackDelay>0 ? (globals->motion.feedbackDelay)/bufTime+1 : 1);
-		if(motionBuffers.size()<tgtSize) {
-			motionBuffers.insert(motionBufferPos,new float[NumFrames][NumOutputs]);
-			motionBufferPos--;
-		} else {
-			while(motionBuffers.size()>tgtSize) {
-				std::list<float(*)[NumOutputs]>::iterator tmp=motionBufferPos++;
-				delete [] *tmp;
-				motionBuffers.erase(tmp);
-				if(motionBufferPos==motionBuffers.end())
-					motionBufferPos=motionBuffers.begin();
-			}
-		}
-		if(lastPoll!=-1U && motionBuffers.size()>1) {
-			std::list<float(*)[NumOutputs]>::iterator prev=motionBufferPos;
-			if(prev==motionBuffers.begin())
-				prev=motionBuffers.end();
-			prev--;
-			unsigned int cnt=motionBuffers.size()-1;
-			while(get_time()>=lastPoll+bufTime*2) {
-				lastPoll+=bufTime;
-				if(globals->motion.verbose)
-					cout << "Dropped motion frame in poll() (late call)" << endl;
-				if(cnt==0)
-					continue; //we've overwritten all of the buffer, no need wrap through it again
-				memcpy(*motionBufferPos,*prev,sizeof(float[NumFrames][NumOutputs]));
-				prev=motionBufferPos;
-				if(++motionBufferPos==motionBuffers.end())
-					motionBufferPos=motionBuffers.begin();
-				cnt--;
-			}
-		}
-		motman->getOutputs(*motionBufferPos);
-		if(++motionBufferPos==motionBuffers.end())
-			motionBufferPos=motionBuffers.begin();
-		{
-			EntryPoint::WorldStateWrite wsw(globals->motion.frameNumber==-1U?0:globals->motion.frameNumber);
-			MarkScope lw(motionLock,wsw);
-			if(state==NULL) {
-				// This should not be possible -- we requested the most recent frame, it should be available
-				cerr << "WARNING: Motion received NULL state for PID update on frame " << wsw.frame << " (now " << globals->motion.frameNumber << ")" << endl;
-				//just in case, try again one time
-				lw.getResource().releaseResource(wsw);
-				wsw.frame=globals->motion.frameNumber;
-				lw.getResource().useResource(wsw);
-			}
-			if(state==NULL) {
-				cerr << "WARNING: Motion PID update retry failed, falling back to previous WorldState (tried " << wsw.frame << ", now " << globals->motion.frameNumber << ")" << endl;
-				state=wsw.src;
-			}	
-			if(state==NULL)
-				cerr << "ERROR: Fallback failed, Motion unable to update PID values for frame " << wsw.frame << endl;
-			else {
-				if(!wsw.getComplete())
-					state=wsw.src;
-				motman->updatePIDs();
-				//motman->updateWorldState();
-			}
-		}
-		globals->setNextMotion(getNextMotion());
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionManager processing",&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionManager processing",NULL))
-			throw;
-	}
-	lastPoll=get_time();
-	return true;
-}
-
-bool MotionExecThread::launched() {
-	if(globals->timeScale<=0)
-		return false;
-	startTime.Set();
-	globals->setNextMotion(getNextMotion());
-	//reset startTime to last motion time
-	startTime-=(get_time()-(getNextMotion()-FrameTime*NumFrames))/globals->timeScale/1000;
-	interrupted();
-	//delay=(getNextMotion()>get_time()) ? (getNextMotion()-get_time())/globals->timeScale/1000 : 0;
-	return PollThread::launched();
-}
-
-void MotionExecThread::interrupted() {
-	period=FrameTime*NumFrames/globals->timeScale/1000;
-	delay=(globals->getNextMotion()-get_time())/globals->timeScale/1000+startTime.Age();
-	//cout << "interrupt " << get_time() << ' ' << globals->getNextMotion() << ' ' << startTime.Age() << ' ' << delay << ' ' << period << ' ' << isRunning() << ' ' << globals->timeScale << endl;
-}
-
-const PostureEngine& MotionExecThread::getPostureFeedback() {
-	if(globals->motion.feedbackDelay<0)
-		return curPose;
-	
-	const unsigned int bufTime=NumFrames*FrameTime;
-	MarkScope l(motionLock);
-	if(lastPoll!=-1U && motionBuffers.size()>1) {
-		std::list<float(*)[NumOutputs]>::iterator prev=motionBufferPos;
-		if(prev==motionBuffers.begin())
-			prev=motionBuffers.end();
-		prev--;
-		unsigned int cnt=motionBuffers.size()-1;
-		while(get_time()>=lastPoll+bufTime*2) {
-			lastPoll+=bufTime;
-			cout << "Dropped motion frame in getPostureFeedback()" << endl;
-			if(cnt==0)
-				continue; //we've overwritten all of the buffer, no need wrap through it again
-			memcpy(*motionBufferPos,*prev,sizeof(float[NumFrames][NumOutputs]));
-			prev=motionBufferPos;
-			if(++motionBufferPos==motionBuffers.end())
-				motionBufferPos=motionBuffers.begin();
-			cnt--;
-		}
-	}
-	unsigned int bufDelay=globals->motion.feedbackDelay/bufTime;
-	unsigned int frameDelay=(globals->motion.feedbackDelay-bufDelay*bufTime)/FrameTime;
-	int bufAdvance=motionBuffers.size()-1-bufDelay;
-	std::list<float(*)[NumOutputs]>::iterator tgt=motionBufferPos;
-	if(bufAdvance<0) {
-		//cout << "negative bufAdvance " << bufAdvance << ' ' << globals->motion.feedbackDelay << ' ' << motionBuffers.size() << endl;
-		frameDelay=0;
-	} else if(bufAdvance>0) {
-		//cout << "positive bufAdvance " << bufAdvance << ' ' << globals->motion.feedbackDelay << ' ' << motionBuffers.size() << endl;
-		while(bufAdvance-- > 0) {
-			if(++tgt==motionBuffers.end())
-				tgt=motionBuffers.begin();
-		}
-	}
-	float * outputs = (*tgt)[NumFrames-1-frameDelay];
-	for(unsigned int i=0; i<NumOutputs; ++i)
-		curPose(i).value=outputs[i];
-	return curPose;
-}
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.16 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/MotionExecThread.h ./local/sim/MotionExecThread.h
--- ../Tekkotsu_3.0/local/sim/MotionExecThread.h	2006-08-07 17:51:28.000000000 -0400
+++ ./local/sim/MotionExecThread.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,76 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_MotionExecThread_h_
-#define INCLUDED_MotionExecThread_h_
-
-#include "IPC/PollThread.h"
-#include "Shared/RobotInfo.h"
-#include "IPC/MessageQueue.h"
-#include "Shared/get_time.h"
-#include "Motion/PostureEngine.h"
-#include "SharedGlobals.h"
-#include <list>
-
-class RCRegion;
-class EntryPoint;
-
-//! description of MotionExecThread
-class MotionExecThread : public PollThread {
-public:
-	//! constructor, enables trackPollTime, but not auto-start (call reset() when you're ready to start it)
-	/*! @arg bl a process lock to ensure mutual exclusion between MotionExecThread::poll() and other threads in the process */
-	MotionExecThread(EntryPoint& bl)
-		: PollThread(0L, FrameTime*NumFrames/globals->timeScale/1000, true,false), motionLock(bl),
-		motionBuffers(), motionBufferPos(), curPose(), lastPoll(-1U)
-	{
-		motionBuffers.push_front(new float[NumFrames][NumOutputs]);
-		for(unsigned int f=0; f<NumFrames; ++f)
-			for(unsigned int o=0; o<NumOutputs; ++o)
-				motionBuffers.front()[f][o]=0;
-		motionBufferPos=motionBuffers.begin();
-		curPose.setWeights(1);
-	}
-	virtual ~MotionExecThread() {
-		while(motionBuffers.size()>0) {
-			delete [] motionBuffers.front();
-			motionBuffers.pop_front();
-		}
-	}
-	virtual void reset(); //!< starts and stops thread as needed, or interrupts thread to reset sleep time if already running
-	
-	//virtual void start();
-	virtual bool poll();
-
-	//! returns time (in milliseconds) of next motion frame -- multiples of FrameTime*NumFrames
-	static unsigned int getNextMotion() {
-		unsigned int pd=FrameTime*NumFrames;
-		return (get_time()/pd+1)*pd;
-	}
-	
-	const PostureEngine& getPostureFeedback();
-
-protected:
-	virtual bool launched();
-	//! resets PollThread::delay and PollThread::period to appropriate values for current SharedGlobals::timeScale value
-	virtual void interrupted();
-	
-	EntryPoint& motionLock; //!< a lock on the motions which should be obtained before updating
-
-	std::list<float(*)[NumOutputs]> motionBuffers;
-	std::list<float(*)[NumOutputs]>::iterator motionBufferPos;
-	PostureEngine curPose;
-	
-	unsigned int lastPoll;
-};
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.8 $
- * $State: Exp $
- * $Date: 2006/08/07 21:51:28 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Process.cc ./local/sim/Process.cc
--- ../Tekkotsu_3.0/local/sim/Process.cc	2006-06-16 21:15:38.000000000 -0400
+++ ./local/sim/Process.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,66 +0,0 @@
-#include "Process.h"
-#include "SharedGlobals.h"
-#include "Sound/SoundManager.h"
-#include "IPC/SharedObject.h"
-#include "Shared/MarkScope.h"
-#include "Shared/debuget.h"
-#include <unistd.h>
-
-using namespace std;
-
-std::string Process::name;
-Process * Process::current;
-
-Process::Process(ProcessID::ProcessID_t pid, const std::string& pname) {
-	ProcessID::setID(pid);
-	name=pname;
-	current=this;
-	globals->pids[ProcessID::getID()]=getpid();
-	strncpy(globals->processNames[ProcessID::getID()],name.c_str(),SharedGlobals::MAX_PROCESS_NAME_LEN);
-}
-
-Process::~Process() {
-	current=NULL;
-}
-
-void Process::run() {
-	globals->waitShutdown();
-}
-
-void Process::statusReport(std::ostream& os) {
-	os << getName() << " (" << ProcessID::getID() << ") Attached Regions -----------" << endl;
-	RCRegion::attachedRegions_t::const_iterator it=RCRegion::attachedBegin(true);
-	for(; it!=RCRegion::attachedEnd(); RCRegion::attachedAdvance(it)) {
-		//subtract one from the reference counts to discount iterator's own reference (using thread-safe iterator access, uses a reference)
-		unsigned int lref=(it->second->NumberOfLocalReference()-1);
-		unsigned int ref=(it->second->NumberOfReference()-1);
-		os << '\t' << setw(16) << left << it->first << setw(8) << right << it->second->Size() << " bytes" << setw(8) << lref<<'/'<<ref << " references" << endl;
-	}
-	os << '\t' << setw(16) << left << "Next RCRegion ID: " << setw(8) << right << RCRegion::getNextKey() << endl;
-	os << '\t' << setw(16) << left << "Next ShdObj ID: " << setw(8) << right << SharedObjectBase::getNextKey() << endl;
-	if(sndman!=NULL)
-		os << '\t' << setw(16) << left << "Next SndRgn ID: " << setw(8) << right << sndman->getNextKey() << endl;
-}
-
-bool Process::statusReport(RCRegion* msg) {
-	Process* cur=Process::getCurrent();
-	ASSERTRETVAL(cur!=NULL,"statusReport, but NULL process!",true);
-	if(strcasecmp(msg->Base(),getName().c_str())==0 || strcasecmp(msg->Base(),"all")==0) {
-		MarkScope l(msg->getLock()); //prevent jumbling reports
-		cur->statusReport(cout);
-		cout << endl;
-	}
-	return true;
-}
-
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.6 $
- * $State: Exp $
- * $Date: 2006/06/17 01:15:38 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Process.h ./local/sim/Process.h
--- ../Tekkotsu_3.0/local/sim/Process.h	2006-06-16 21:15:38.000000000 -0400
+++ ./local/sim/Process.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,45 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_Process_h_
-#define INCLUDED_Process_h_
-
-#include "IPC/ProcessID.h"
-#include <string>
-
-class RCRegion;
-
-//! Represents a common interface for each process being run
-class Process {
-public:
-	Process(ProcessID::ProcessID_t pid, const std::string& pname);
-	virtual ~Process();
-	virtual void DoStart() {}
-	virtual void DoStop() {}
-	virtual void run();
-
-	static const std::string& getName() { return name; }
-	static Process * getCurrent() { return current; }
-	
-	virtual void statusReport(std::ostream& os);
-	static bool statusReport(RCRegion* msg);
-
-protected:
-	static std::string name;
-	static Process * current;
-	
-private:
-	Process(const Process&);            //!< don't call
-	Process& operator=(const Process&); //!< don't call
-};
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.5 $
- * $State: Exp $
- * $Date: 2006/06/17 01:15:38 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/SharedGlobals.cc ./local/sim/SharedGlobals.cc
--- ../Tekkotsu_3.0/local/sim/SharedGlobals.cc	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/SharedGlobals.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,66 +0,0 @@
-#include "SharedGlobals.h"
-#include "Simulator.h"
-
-const char * const SharedGlobals::runlevel_names[SharedGlobals::NUM_RUNLEVELS] = {
-	"CREATED",
-	"CONSTRUCTING",
-	"STARTING",
-	"RUNNING",
-	"STOPPING",
-	"DESTRUCTING",
-	"DESTRUCTED"
-};
-
-ipc_setup_t * ipc_setup=NULL;
-SharedGlobals * globals=NULL;
-
-unsigned int SharedGlobals::get_time() {
-	float lastLastTimeScale=lastTimeScale; // used to avoid repeated "pause" commands if we're past autoPauseTime
-	if(timeScale<=0) {
-		//just need to update lastTimeScale in case it had been realtime mode
-		//adding an 'if' to test before the assignment is slower than just always doing the assignment
-		lastTimeScale=timeScale;
-	} else {
-		if(lastTimeScale<=0) {
-			//switching from non-realtime to realtime mode -- reset time offset
-			timeOffset=bootTime.Age().Value()*timeScale*1000-simulatorTime;
-			lastTimeScale=timeScale;
-			//we reset timeOffset such that simulatorTime hasn't changed
-		} else if(lastTimeScale!=timeScale) {
-			//switching speeds -- reset time offset
-			simulatorTime=get_real_time(lastTimeScale);
-			timeOffset=bootTime.Age().Value()*timeScale*1000-simulatorTime;
-			lastTimeScale=timeScale;
-		} else {
-			simulatorTime=get_real_time(timeScale);
-		}
-		//cout << timeOffset << ' ' << lastTimeScale << ' ' << timeScale << endl;
-	}
-	if(simulatorTime>autoPauseTime) {
-		simulatorTime=autoPauseTime;
-		if(ProcessID::getID()==ProcessID::SimulatorProcess) {
-			if(timeScale!=0) // don't reset it if it's already set -- triggers infinite recursion if/when the hook calls get_time
-				timeScale=0;
-		} else {
-			// can't set timeScale directly because Simulator process has hooks registered and we aren't in the Simulator process
-			if(lastLastTimeScale!=0) {
-				lastTimeScale=0;
-				Simulator::sendCommand("pause quiet"); // so do this instead
-			}
-		}
-	}
-	return simulatorTime;
-}
-
-float SharedGlobals::getTimeScale() const { return timeScale; }
-
-/*! @file
- * @brief A class to hold various simulator parameters which need to be accessed from multiple processes
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.8 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/SharedGlobals.h ./local/sim/SharedGlobals.h
--- ../Tekkotsu_3.0/local/sim/SharedGlobals.h	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/SharedGlobals.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,219 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_CLASSNAME_h_
-#define INCLUDED_CLASSNAME_h_
-
-#include "IPC/MutexLock.h"
-#include "IPC/SemaphoreManager.h"
-#include "IPC/ProcessID.h"
-#include "Shared/plist.h"
-#include "Shared/TimeET.h"
-
-//! A class to hold various simulator parameters which need to be accessed from multiple processes
-class SharedGlobals {
-public:
-	//! constructor
-	SharedGlobals()
-		: simulatorTime(0), timeScale(1), motion(), lock(), 
-		nextTimer(-1U), nextMotion(-1U), nextSensorUpdate(-1U), bootTime(), timeOffset(0), lastTimeScale(0), autoPauseTime(-1U),
-			semgr(1), running(semgr.getSemaphore())
-	{
-		for(unsigned int i=0; i<NUM_RUNLEVELS; i++)
-			level_count[i]=0;
-		semgr.raise(running,1);
-	}
-	//! destructor
-	~SharedGlobals() {
-		semgr.releaseSemaphore(running);
-	}
-
-	//       ****************
-	//!@name Shutdown Control
-	//       ****************
-
-	//! call this to cause "system shutdown" -- clean halt of the simulator (not actually the host system)
-	void signalShutdown() {
-		semgr.setValue(running,0);
-	}
-	//! test to see if the shutdown flag has been set (non-blocking)
-	bool isShutdown() const {
-		return semgr.testZero(running,false);
-	}
-	//! blocks until shutdown flag has been set
-	bool waitShutdown() {
-		return semgr.testZero(running,true);
-	}
-	
-	//! access to #semgr, returns SemaphoreManager::hadFault()
-	bool hadFault() const { return semgr.hadFault(); }
-	
-	//! access to #semgr's SemaphoreManager::faultShutdown() -- call this *after* a fault has occured from the signal handler; doesn't signal the fault itself
-	void faultShutdown() { semgr.faultShutdown(); }
-	
-	//@}
-
-
-	//       ************
-	//!@name Time Control
-	//       ************
-
-	//! returns the current simulator time, in milliseconds since startup
-	/*! the simulator should set project_get_time::get_time_callback to call this,
-	 *  so calls to ::get_time() will be forwarded here.  That wall all processes
-	 *  will share the same time */
-	unsigned int get_time();
-	
-	//! returns the current simulator #timeScale (speed factor), as a ratio of real time (e.g. '2' means simulation is running two times wall clock)
-	/*! the simulator should set project_get_time::get_timeScale_callback to call this,
-	 *  so calls to ::getTimeScale() will be forwarded here. */
-	float getTimeScale() const;
-	
-	//! the current time within the simulation, only applicable when #isRealTime is false
-	unsigned int simulatorTime;
-	
-	//! The speed at which time from get_time() will move when #isRealTime is true
-	/*! You can use this to pretend your hardware is faster or slower
-	 *  than it actually is.  For instance, a value of .5 means time
-	 *  will move at half speed (pretending your hardware is twice as
-	 *  fast)  This can be useful for "slow motion" analysis, or you
-	 *  can speed up time to simulate a more processor-restrictive platform.
-	 *
-	 *  Negative values indicate full-speed processing -- time will be
-	 *  incremented only as quickly as it can be without dropping any
-	 *  video or sensor frames. (may be faster or slower than realtime)
-	 *
-	 *  A value of zero halts time. */
-	plist::Primitive<double> timeScale;
-
-	//! sets #autoPauseTime
-	void setAutoPauseTime(unsigned int t) { autoPauseTime=t; }
-	//! returns #autoPauseTime
-	unsigned int getAutoPauseTime() const { return autoPauseTime; }
-	
-	//@}
-
-
-	//       **********************
-	//!@name Runlevel Communication
-	//       **********************
-
-	//! defines the runlevels that each process passes through; runlevels should monotonically increase (can't go backwards)
-	enum runlevel_t {
-		CREATED=0,    //!< corresponding element of #level_count is incremented prior to each fork -- not strictly a runlevel per se
-		CONSTRUCTING, //!< currently initializing
-		STARTING,     //!< setting up shared memory regions with other processes
-		RUNNING,      //!< full activity, stay here until the #running semaphore is set to 0
-		STOPPING,     //!< dereferencing shared regions, waiting for threads to finish
-		DESTRUCTING,  //!< destructors are in progress
-		DESTRUCTED,   //!< destruction has completed, corresponding element of #level_count is incremented immediately prior to process completion
-	};
-	static const unsigned int NUM_RUNLEVELS=DESTRUCTED+1; //!< symbolic access to the total number of runlevel stages
-
-	//! string versions of runlevel_t for runtime user-feedback
-	static const char * const runlevel_names[NUM_RUNLEVELS];
-
-	//! a count of the number of processes which have passed through each runlevel
-	unsigned int level_count[NUM_RUNLEVELS];
-
-	//@}
-
-
-	//       **********************
-	//!@name Configuration Parameters
-	//       **********************
-
-	//! holds configuration parameters for the motion process
-	class MotionSimConfig : public plist::Dictionary {
-	public:
-		MotionSimConfig() : Dictionary(), verbose(false), feedbackDelay(0), zeroPIDFeedback(false), /*speedLimit(0),*/ override(false), frameNumber(-1U) {
-			addEntry("Verbose",verbose,"Report whenever motion commands are being processed or joints are updated");
-			addEntry("FeedbackDelay",feedbackDelay,"Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)");
-			addEntry("ZeroPIDFeedback",zeroPIDFeedback,"When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative");
-			//addEntry("EnforceSpeedLimit",speedLimit,"The simulated motion of joints is limited to this factor of model's recommended speed limits.  0 (or negative) disables speed limit altogether.");
-			addEntry("OverrideSensors",override,"Allows motion feedback to override position values from sensor data loaded from disk.\nIf false, feedback is only provided when no other sensor data is being provided");
-		}
-		plist::Primitive<bool> verbose; //!< Report whenever motion commands are being processed or joints are updated
-		plist::Primitive<int> feedbackDelay; //!< Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)
-		plist::Primitive<bool> zeroPIDFeedback; //!< When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative
-		//plist::Primitive<float> speedLimit; //!< The simulated motion of joints is limited to this factor of model's recommended speed limits.  0 (or negative) disables speed limit altogether.
-		plist::Primitive<bool> override; //!< Allows motion feedback to override position values from sensor data loaded from disk; if false, feedback is only provided when no other sensor data is being provided
-		unsigned int frameNumber; //!< a monotonically increasing count of the number of sensor frames which have been "completed".  Needed to allow coordination between sensor loading from disk and feedback from motion.  Count is increased by the simulator process, which will send a heartbeat message over Simulator::sensorQueue when it does so.
-	} motion;
-	
-	//@}
-	
-	//! allows mutually exclusive access to the fields of SharedObject
-	MutexLock<ProcessID::NumProcesses> lock;
-
-	//! holds the host system's process ID for each simulator process
-	pid_t pids[ProcessID::NumProcesses];
-
-	//! maximum storage size of strings in #processNames
-	static const unsigned int MAX_PROCESS_NAME_LEN=32;
-
-	//! each process should set a string version of its name for user feedback
-	char processNames[ProcessID::NumProcesses][MAX_PROCESS_NAME_LEN];
-	
-	bool setNextTimer(unsigned int t) { if(nextTimer==t) return false; nextTimer=t; return true; } //!< sets #nextTimer, returns true if the new value differs from previous value
-	unsigned int getNextTimer() { return nextTimer; } //!< gets #nextTimer
-	
-	void setNextMotion(unsigned int t) { nextMotion=t; } //!< sets #nextMotion
-	unsigned int getNextMotion() { return nextMotion; } //!< gets #nextMotion
-	
-	void setNextSensorUpdate(unsigned int t) { nextSensorUpdate=t; } //!< sets #nextSensorUpdate
-	unsigned int getNextSensorUpdate() { return nextSensorUpdate; } //!< gets #nextSensorUpdate
-	
-protected:
-	//! this returns time since boot (#bootTime), scaled by @a scale, relative to #timeOffset
-	unsigned int get_real_time(double scale) const {
-		return static_cast<unsigned int>(bootTime.Age().Value()*scale*1000-timeOffset);
-	}
-
-	//! set by setNextTimer, called with the current value of EventRouter::getNextTimer() after each user code section, indicates time of next timer event
-	unsigned int nextTimer;
-	
-	//! updated by Motion process after each motion update
-	unsigned int nextMotion;
-	
-	//! updated by Main process after each sensor update
-	unsigned int nextSensorUpdate;
-	
-	//! real time since simulator startup (or, at least, since SharedGlobals was constructed... close enough)
-	TimeET bootTime; 
-
-	//! the scaled value of #bootTime at which isRealTime was last activated, allows you to start and stop realtime fluidly
-	double timeOffset; 
-	
-	//! updated by each call to get_time(), if timeScale differs, allows timeOffset to be updated fluidly
-	double lastTimeScale;
-	
-	//! if simulatorTime is about to move past this value, timeScale is set to 0 instead, and simulatorTime is set to this
-	unsigned int autoPauseTime;
-	
-	SemaphoreManager semgr; //!< a semaphore set, only used for #running
-	SemaphoreManager::semid_t running; //!< the semaphore within #semgr to communicate shutdown status between processes -- when the semaphore is set to 0, shutdown is requested
-};
-
-const unsigned int MAX_SUBJECTS=50; //!< maximum number of message queues the simulator can maintain
-const unsigned int MAX_SUBJECT_NAME=50; //!< maximum storage capacity of subject names
-
-// just a forward definition of RegionRegistry
-template<unsigned int MAX_SUBJECTS, unsigned int MAX_SUBJECT_NAME> class RegionRegistry;
-//! the type to use for the inter-process communication registry
-typedef RegionRegistry<MAX_SUBJECTS,MAX_SUBJECT_NAME> ipc_setup_t;
-
-extern ipc_setup_t * ipc_setup; //!< a global pointer to the inter-process message queue registry (a RegionRegistry)
-extern SharedGlobals * globals; //!< a global pointer to the SharedGlobals instance
-extern float getTimeScale(); //!< a prototype for accessing current time scale without referencing ::globals directly
-
-/*! @file
- * @brief A class to hold various simulator parameters which need to be accessed from multiple processes
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.25 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/SimConfig.h ./local/sim/SimConfig.h
--- ../Tekkotsu_3.0/local/sim/SimConfig.h	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/SimConfig.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,56 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_SimConfig_h_
-#define INCLUDED_SimConfig_h_
-
-#include "Shared/plist.h"
-#include "SharedGlobals.h"
-
-//! Provides the root dictionary of the simulator configuration, items from SharedGlobals and LoadFileThreads are added as entries in this dictionary
-class SimConfig : public plist::Dictionary {
-public:
-	SimConfig() : 
-		cmdPrompt("sim >"),
-		initSimTime(0),
-		tgtRunlevel(SharedGlobals::RUNNING, SharedGlobals::runlevel_names, SharedGlobals::NUM_RUNLEVELS),
-		lastfile()
-	{
-		setUnusedWarning(false);
-		addEntry("InitialTime",initSimTime,"The value to initialize the simulator's clock (in milliseconds)");
-		addEntry("InitialRunlevel",tgtRunlevel,"Specifies how far startup should proceed before pausing for user interaction.\nThis value only affects startup, and setting this value from the simulator command prompt will have no effect.  (Use the 'runlevel' command instead.)");
-	}
-	
-	std::string cmdPrompt; //!< not persistently stored -- [re]set by main(...) on each run
-	plist::Primitive<unsigned int> initSimTime;
-	plist::NamedEnumeration<SharedGlobals::runlevel_t> tgtRunlevel;
-
-	void setLastFile(const std::string& str) const {
-		lastfile=str;
-	}
-	const std::string& getLastFile() const {
-		return lastfile;
-	}
-	virtual	unsigned int loadFile(const char* filename) {
-		lastfile=filename;
-		return Dictionary::loadFile(filename);
-	}
-	virtual unsigned int saveFile(const char* filename) const {
-		lastfile=filename;
-		return Dictionary::saveFile(filename);
-	}
-	
-protected:
-	mutable std::string lastfile;
-};
-
-/*! @file
- * @brief Provides the root dictionary of the simulator configuration, items from SharedGlobals and LoadFileThreads are added as entries in this dictionary
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.6 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Simulator.cc ./local/sim/Simulator.cc
--- ../Tekkotsu_3.0/local/sim/Simulator.cc	2006-09-26 17:42:50.000000000 -0400
+++ ./local/sim/Simulator.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,885 +0,0 @@
-#include "Simulator.h"
-#include "Main.h"
-#include "IPC/RegionRegistry.h"
-#include "Shared/string_util.h"
-#include "Shared/RobotInfo.h"
-#include <iostream>
-#include "SimConfig.h"
-#include "Shared/debuget.h"
-#include "Shared/MarkScope.h"
-#include "IPC/MessageReceiver.h"
-
-#ifndef DISABLE_READLINE
-#  include <readline/readline.h>
-#  include <readline/history.h>
-#endif
-
-using namespace std;
-
-const float Simulator::avgSpeedupGamma=.99;
-
-Simulator::Simulator()
-: Process(getID(),getClassName()), frameCounter(),
-cameraQueue(ipc_setup->registerRegion(Simulator::getCameraQueueID(),sizeof(sim::CameraQueue_t))),
-sensorQueue(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
-timerWakeup(ipc_setup->registerRegion(Simulator::getTimerWakeupID(),sizeof(sim::TimerWakeup_t))),
-motionWakeup(ipc_setup->registerRegion(Simulator::getMotionWakeupID(),sizeof(sim::MotionWakeup_t))),
-statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
-events(ipc_setup->registerRegion(Main::getEventsID(),sizeof(sim::EventQueue_t))),
-commandQueue(ipc_setup->registerRegion(Simulator::getCommandQueueID(),sizeof(CommandQueue_t))),
-cameraStatus(*cameraQueue), sensorStatus(*sensorQueue), timerStatus(*timerWakeup), motionStatus(*motionWakeup), eventsStatus(), commandrecv(NULL),
-vision("images", ".*\\.(jpg|jpeg|png)$", 30, *cameraQueue,false),
-sensors("sensors", ".*\\.pos$", 1000.f/NumFrames/FrameTime, *sensorQueue,false),
-frameTimes(), runSpeed(1), step(STEP_NONE), waitingSteps(0), curLevel(SharedGlobals::CONSTRUCTING), 
-fullspeedWallStart(), fullspeedSimStart(), lastFrameWallStart(), avgWallTime(), avgSimTime(),
-simLock()
-{
-	new (&(*cameraQueue)) sim::CameraQueue_t;
-	new (&(*sensorQueue)) sim::SensorQueue_t;
-	new (&(*timerWakeup)) sim::TimerWakeup_t;
-	new (&(*motionWakeup)) sim::MotionWakeup_t;
-	new (&(*statusRequest)) sim::StatusRequest_t;
-	new (&(*commandQueue)) CommandQueue_t;
-	statusRequest->setOverflowPolicy(MessageQueueBase::WAIT);
-	commandQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-	
-	sim::config.writeParseTree();
-	sim::config.addEntry("Sensors",sensors,"Settings for the loading of sensor values");
-	sim::config.addEntry("Vision",vision,"Settings for the loading of camera frames");
-	sim::config.readParseTree();
-	
-	motionWakeup->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-	timerWakeup->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-	cameraQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-	sensorQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-	sensorQueue->addMessageFilter(frameCounter);
-	
-	globals->timeScale.addPrimitiveListener(this);
-	sensors.src.addPrimitiveListener(this);
-	vision.src.addPrimitiveListener(this);
-	
-	vector<vector<string> > delayed;
-	bool visSet=false, senSet=false;
-	for(unsigned int i=0; i<sim::assignments.size(); i++) {
-		vector<string> setarg;
-		setarg.push_back("set");
-		setarg.push_back(sim::assignments[i]);
-		if(sim::assignments[i].find(".Source=")==string::npos) {
-			if(!cmdSet(setarg))
-				cerr << "Occurred while processing " << sim::assignments[i] << endl;
-		} else {
-			delayed.push_back(setarg); // delay setting of source until after options like Frozen or Speed have been set
-			if(sim::assignments[i].find("Vision.")==0)
-				visSet=true;
-			if(sim::assignments[i].find("Sensors.")==0)
-				senSet=true;
-		}
-	}
-	for(unsigned int i=0; i<delayed.size(); i++) {
-		//this avoids dropping initial frame(s)
-		if(!cmdSet(delayed[i]))
-			cerr << "Occurred while processing " << delayed[i][1] << endl;
-	}
-	if(!visSet)
-		vision.loadFileList();
-	if(!senSet)
-		sensors.loadFileList();
-	commandrecv=new MessageReceiver(*commandQueue,gotCommand);
-	processRunlevel(SharedGlobals::CONSTRUCTING);
-}
-
-Simulator::~Simulator() {
-	globals->timeScale.removePrimitiveListener(this);
-	globals->motion.feedbackDelay.removePrimitiveListener(this);
-	processRunlevel(SharedGlobals::DESTRUCTING);
-}
-
-void Simulator::DoStart() {
-	Process::DoStart();
-	eventsStatus.setMessageQueue(*events);
-	processRunlevel(SharedGlobals::STARTING);
-}
-
-void Simulator::run() {
-	for(unsigned int i=0; i<ProcessID::NumProcesses; ++i)
-		cout << globals->processNames[i] << " pid=" << globals->pids[i] << ";  ";
-	cout << endl;
-	if(globals->timeScale!=0)
-		runSpeed=globals->timeScale;
-
-	resetSpeedMode();
-	if(globals->timeScale<0)
-		incrementTime();
-
-	CommandThread cmdThread;
-	cmdThread.start();
-	if(sim::config.tgtRunlevel==SharedGlobals::RUNNING)
-		Process::run();
-	if(cmdThread.isRunning()) {
-		cout << "\n\nShutdown requested, press 'enter' to continue...\n\n" << endl;
-		cmdThread.stop();
-	}
-
-	if(sensors.isRunning())
-		sensors.stop();
-	if(vision.isRunning())
-		vision.stop();
-	
-	if(globals->timeScale<0) {
-		motionStatus.removeStatusListener(this);
-		timerStatus.removeStatusListener(this);
-		sensorStatus.removeStatusListener(this);
-		cameraStatus.removeStatusListener(this);
-	}
-	globals->signalShutdown();
-}
-
-void Simulator::plistValueChanged(const plist::PrimitiveBase& pl) {
-	if(&pl==&globals->timeScale) {
-		get_time(); // force SharedGlobals to notice the change and update its state
-		resetSpeedMode();
-		if(globals->timeScale<0)
-			incrementTime();
-		timerWakeup->sendMessage(NULL);
-		motionWakeup->sendMessage(NULL);
-	} else if(&pl==&sensors.src || &pl==&vision.src) {
-		// if both stream are using the same index file, keep them in sync across loops, regardless of (or in case of) their framerate differing
-		if(sensors.src==vision.src && sensors.usingIndexFile()) {
-			float looptime=max(sensors.getLoopTime(),vision.getLoopTime());
-			sensors.setLoopTime(looptime);
-			vision.setLoopTime(looptime);
-		}
-	} else {
-		cerr << "WARNING: Simulator got a plistValueChanged for an unknown plist primitive";
-	}
-}
-
-void Simulator::messagesRead(MessageQueueBase& mq, unsigned int /*n*/) {
-	MarkScope l(simLock);
-	if(globals->timeScale<0) {
-		//clear corresponding bit in waitingSteps
-		 if(&mq==&(*cameraQueue)) {
-			//cout << "Camera read, ";
-			waitingSteps&=~(1<<STEP_CAMERA);
-		} else if(&mq==&(*sensorQueue)) {
-			//cout << "Sensor read, ";
-			waitingSteps&=~(1<<STEP_SENSOR);
-		} else if(&mq==&(*timerWakeup)) {
-			//cout << "Timer read, ";
-			waitingSteps&=~(1<<STEP_TIMER);
-		} else if(&mq==&(*motionWakeup)) {
-			//cout << "Motion read, ";
-			waitingSteps&=~(1<<STEP_MOTION);
-		} else if(&mq==&(*events)) {
-			//cout << "Main read event queue (" << events->getMessagesUnread() << "remain), ";
-			// nothing to do, just waiting for main to catch up before incrementing
-		} else {
-			cout << "Unknown message base read (either you meant to add some code to Simulator::messagesRead, or why did you bother to register a listener?)" << endl;
-		}
-		//cout << " waiting " << waitingSteps << " events " << events->getMessagesUnread << endl;
-		
-		if(waitingSteps==0 && events->getMessagesUnread()==0) //if that was the last one we were waiting for -- go for the next!
-			incrementTime();
-	}
-}
-
-void Simulator::sendCommand(const std::string& cmd) {
-	static unsigned int cmdSN=0;
-	char msgname[30];
-	snprintf(msgname,30,"SimCommand.%d.%d",ProcessID::getID(),cmdSN++);
-	RCRegion * msg = new RCRegion(msgname,cmd.size());
-	strcpy(msg->Base(),cmd.c_str());
-	SharedObject<CommandQueue_t> commandQ(ipc_setup->registerRegion(Simulator::getCommandQueueID(),sizeof(CommandQueue_t)));
-	commandQ->sendMessage(msg,true);
-}
-
-void Simulator::DoStop() {
-	if(sensors.isRunning())
-		sensors.join();
-	if(vision.isRunning())
-		vision.join();
-	processRunlevel(SharedGlobals::STOPPING);
-	Process::DoStop();
-}
-
-
-void* Simulator::CommandThread::run() {
-	Simulator * simp=dynamic_cast<Simulator*>(Process::getCurrent());
-	ASSERTRETVAL(simp!=NULL,"CommandThread not in Simulator!",NULL);
-	simp->processRunlevel(SharedGlobals::RUNNING);
-	return NULL;
-}
-
-
-void Simulator::resetSpeedMode() {
-	if(globals->timeScale<=0) {
-		if(vision.isRunning()) {
-			vision.stop();
-			//vision.join(); // can't join because runfor/runto pause might be triggered within LoadFileThread's get_time() call
-		}
-		if(sensors.isRunning()) {
-			sensors.stop();
-			//sensors.join(); // can't join because runfor/runto pause might be triggered within LoadFileThread's get_time() call
-		}
-	} else {
-		if(sim::config.tgtRunlevel==SharedGlobals::RUNNING) { 
-			if(!vision.isRunning() && (!vision.frozen || vision.heartbeat))
-				vision.start();
-			if(!sensors.isRunning() && (!sensors.frozen || sensors.heartbeat))
-				sensors.start();
-		}
-	}
-	if(globals->timeScale<0) {
-		cameraQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-		sensorQueue->setOverflowPolicy(MessageQueueBase::WAIT);
-		cameraStatus.addStatusListener(this);
-		sensorStatus.addStatusListener(this);
-		timerStatus.addStatusListener(this);
-		motionStatus.addStatusListener(this);
-		eventsStatus.addStatusListener(this);
-		fullspeedWallStart.Set();
-		fullspeedSimStart=globals->simulatorTime;
-		lastFrameWallStart.Set();
-		avgWallTime=avgSimTime=0;
-	} else {
-		cameraQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-		sensorQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
-		eventsStatus.removeStatusListener(this);
-		motionStatus.removeStatusListener(this);
-		timerStatus.removeStatusListener(this);
-		sensorStatus.removeStatusListener(this);
-		cameraStatus.removeStatusListener(this);
-	}
-	if(globals->timeScale==0)
-		globals->setAutoPauseTime(-1U);
-}
-
-void Simulator::incrementTime() {
-	MarkScope l(simLock);
-	waitingSteps=getNextFrame();
-	if(waitingSteps==0)
-		return;
-	unsigned int next=*frameTimes.begin();
-	if(next>globals->simulatorTime) {
-		unsigned int adv=next-globals->simulatorTime;
-		avgWallTime=avgWallTime*avgSpeedupGamma + lastFrameWallStart.Age().Value()*(1-avgSpeedupGamma);
-		avgSimTime=avgSimTime*avgSpeedupGamma + adv*(1-avgSpeedupGamma);
-		lastFrameWallStart.Set();
-		//cout << "inc " << (avgSimTime/avgWallTime/1000) << " " << waitingSteps << endl;
-		globals->simulatorTime=next;
-	}
-	if(waitingSteps & (1<<STEP_CAMERA))
-		vision.advanceFrame(false);
-	if(waitingSteps & (1<<STEP_SENSOR))
-		sensors.advanceFrame(false);
-	if(waitingSteps & (1<<STEP_TIMER))
-		timerWakeup->sendMessage(NULL);
-	if(waitingSteps & (1<<STEP_MOTION))
-		motionWakeup->sendMessage(NULL);
-	if(globals->getAutoPauseTime()<=globals->simulatorTime || (1<<step) & waitingSteps) {
-		//that was the step we were waiting for, pause sim
-		globals->timeScale=0;
-		step=STEP_NONE;
-		globals->setAutoPauseTime(-1U);
-	}
-}
-
-unsigned int Simulator::getNextFrame() {
-	frameTimes.clear();
-	/*set<unsigned int>::iterator past=frameTimes.begin();
-	while(past!=frameTimes.end() && *past<=globals->simulatorTime)
-	past++;
-	frameTimes.erase(frameTimes.begin(),past);*/
-	unsigned int vis = vision.frozen && !vision.heartbeat ? -1U : vision.nextTimestamp();
-	frameTimes.insert(vis);
-	unsigned int sen = sensors.frozen && !sensors.heartbeat ? -1U : sensors.nextTimestamp();
-	frameTimes.insert(sen);
-	unsigned int tim=globals->getNextTimer();
-	frameTimes.insert(tim);
-	unsigned int mot=globals->getNextMotion();
-	frameTimes.insert(mot);
-	unsigned int next=*frameTimes.begin();
-	//cout << "Testing: " << globals->simulatorTime << " => next camera: "<< vis << " next sensor: " << sen << " next timer: " << tim << " next motion: " << mot << " => " << next << endl;
-	unsigned int steps=0;
-	if(next!=-1U) {
-		if(next==vis) {
-			steps |= 1<<STEP_CAMERA;
-		}
-		if(next==sen) {
-			steps |= 1<<STEP_SENSOR;
-		}
-		if(next==tim) {
-			steps |= 1<<STEP_TIMER;
-		}
-		if(next==mot) {
-			steps |= 1<<STEP_MOTION;
-		}
-	}
-	return steps;
-}
-
-void Simulator::processRunlevel(SharedGlobals::runlevel_t curRunLevel) {
-	curLevel=curRunLevel;
-	while(sim::config.tgtRunlevel==curLevel && (!globals->isShutdown() || curLevel>SharedGlobals::RUNNING)) {
-		string line;
-#ifndef DISABLE_READLINE
-		char* readin=readline(sim::config.cmdPrompt.c_str());
-		if(readin==NULL) {
-			cmdQuit(vector<string>());
-			continue;
-		}
-		line=readin;
-		free(readin);
-#else
-		cout << sim::config.cmdPrompt << flush;
-		getline(cin,line);
-		if(!cin) {
-			cmdQuit(vector<string>());
-			continue;
-		}
-#endif
-		processCommand(line,true);
-	}
-}
-
-void Simulator::processCommand(const std::string& line, bool addToHistory) {
-	vector<string> args;
-	vector<unsigned int> offs;
-	if(!string_util::parseArgs(line,args,offs)) {
-		cerr << "Mismatched quotes" << endl;
-		return;
-	}
-	if(args.size()==0)
-		return;
-#ifndef DISABLE_READLINE
-	/*		if(current_history()==NULL)
-		cout << "current_history()==NULL" << endl;
-	else if(current_history()->line==NULL)
-		cout << "line == NULL" << endl;
-	else if(line!=current_history()->line)
-		cout << "line is different" << endl;
-	else {
-		cout << "not added" << endl;
-		cout << "new line: " << line << endl;
-		cout << "old line: " << current_history()->line << endl;
-	}
-	if(history_get(-1)==NULL)
-		cout << "history_get(0)==NULL" << endl;
-	else if(history_get(-1)->line==NULL)
-		cout << "line 0 == NULL" << endl;
-	else {
-		cout << "line 0: " << history_get(-1)->line << endl;
-		if(line!=history_get(-1)->line)
-			cout << "line 0 is different" << endl;
-		else
-			cout << "0 not added" << endl;
-	}
-	*/	
-	if(addToHistory && (current_history()==NULL || current_history()->line==NULL || line!=current_history()->line))
-		add_history(line.c_str());
-#endif
-	if(args[0]=="shutdown" || args[0]=="quit" || args[0]=="exit") {
-		cmdQuit(args);
-	} else if(args[0]=="load") {
-		cmdLoad(args);
-	} else if(args[0]=="save") {
-		cmdSave(args);
-	} else if(args[0]=="runlevel") {
-		cmdRunlevel(args);
-	} else if(args[0]=="get_time") {
-		cout << "Current time is " << get_time() << endl;
-	} else if(args[0]=="set") {
-		cmdSet(args);
-	} else if(args[0]=="runto") {
-		cmdRun(args,false);
-	} else if(args[0]=="runfor") {
-		cmdRun(args,true);
-	} else if(args[0]=="run" || args[0]=="r") {
-		cmdRun(args);
-	} else if(args[0]=="pause" || args[0]=="p") {
-		cmdPause(args);
-	} else if(args[0]=="help") {
-		cmdHelp(args);
-	} else if(args[0]=="step") {
-		cmdStep(args);
-	} else if(args[0]=="status") {
-		cmdStatus(args);
-	} else if(args[0]=="advance") {
-		cmdAdvance(args);
-	} else if(args[0]=="freeze") {
-		cmdFreeze(true,args);
-	} else if(args[0]=="unfreeze") {
-		cmdFreeze(false,args);
-	} else if(args[0]=="reset") {
-		cmdReset(args);
-	} else {
-		cout << "Unknown command '" << args[0] << "'" << endl;
-	}
-}
-
-bool Simulator::gotCommand(RCRegion* msg) {
-	Simulator * simp=dynamic_cast<Simulator*>(Process::getCurrent());
-	ASSERTRETVAL(simp!=NULL,"gotCommand, but not within Simulator process!",true);
-	simp->processCommand(msg->Base(),false);
-	return true;
-}	
-
-void Simulator::cmdQuit(const std::vector<std::string>& /*args*/) {
-	sim::config.tgtRunlevel=SharedGlobals::DESTRUCTED;
-	globals->signalShutdown();
-}
-void Simulator::cmdLoad(const std::vector<std::string>& args) {
-	if(args.size()>1)
-		for(unsigned int i=1; i<args.size(); i++)
-			sim::config.loadFile(args[i].c_str());
-	else
-		sim::config.loadFile(sim::config.getLastFile().c_str());
-}
-void Simulator::cmdSave(const std::vector<std::string>& args) {
-	if(args.size()>1)
-		for(unsigned int i=1; i<args.size(); i++)
-			sim::config.saveFile(args[i].c_str());
-	else
-		sim::config.saveFile(sim::config.getLastFile().c_str());
-}
-void Simulator::cmdRunlevel(const std::vector<std::string>& args) {
-	if(args.size()<=1) {
-		sim::config.tgtRunlevel=static_cast<SharedGlobals::runlevel_t>(sim::config.tgtRunlevel+1);
-		cout << "Moving to next runlevel: " << SharedGlobals::runlevel_names[sim::config.tgtRunlevel] << endl;
-	} else {
-		try {
-			sim::config.tgtRunlevel=string_util::makeUpper(args[1]);
-		} catch(...) {
-			cout << "Invalid runlevel specification.  Try one of:\n\t";
-			for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++)
-				cout << i << ' ' << SharedGlobals::runlevel_names[i] << ", ";
-			cout << "\nCurrently at " << SharedGlobals::runlevel_names[curLevel] << endl;
-			return;
-		}
-		if(sim::config.tgtRunlevel<curLevel) {
-			sim::config.tgtRunlevel=curLevel;
-			cout << "Cannot reduce runlevel, currently at " << curLevel << ' ' << SharedGlobals::runlevel_names[curLevel] << "\n\t";
-			for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++)
-				cout << i << ' ' << SharedGlobals::runlevel_names[i] << ", ";
-			cout << endl;
-			return;
-		} else if(sim::config.tgtRunlevel==curLevel) {
-			cout << "Already at " << curLevel << ' ' << SharedGlobals::runlevel_names[curLevel] << "\n\t";
-			for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++)
-				cout << i << ' ' << SharedGlobals::runlevel_names[i] << ", ";
-			cout << endl;
-			return;
-		}
-	}
-	if(sim::config.tgtRunlevel>SharedGlobals::RUNNING && curLevel<=SharedGlobals::RUNNING)
-		globals->signalShutdown();
-}
-bool Simulator::cmdSet(const std::vector<std::string>& args) {
-	if(args.size()<=1) {
-		cout << sim::config << endl;
-		return false;
-	}
-	string arg;
-	for(unsigned int i=1; i<args.size(); i++) {
-		arg+=args[i];
-		if(i!=args.size()-1)
-			arg+=" ";
-	}
-	if(arg.rfind("=")==string::npos) {
-		plist::ObjectBase* ob=sim::config.getEntry(arg);
-		if(ob==NULL) {
-			cout << "'" << arg << "' is unknown" << endl;
-			return false;
-		}
-		cout << *ob << endl;
-	} else {
-		string value=string_util::trim(arg.substr(arg.find("=")+1));
-		string key=string_util::trim(arg.substr(0,arg.find("=")));
-		plist::ObjectBase* ob=sim::config.getEntry(key);
-		if(ob==NULL) {
-			cout << "'" << key << "' is unknown" << endl;
-			return false;
-		}
-		if(plist::PrimitiveBase* pbp=dynamic_cast<plist::PrimitiveBase*>(ob)) {
-			try {
-				pbp->set(value);
-				return true;
-			} catch(const XMLLoadSave::bad_format& bf) {
-				cout << "'" << value << "' is a bad value for '" << key << "'" << endl;
-				cout << bf.what() << endl;
-			} catch(const std::exception& e) {
-				cout << "An exception occured: " << e.what() << endl;
-			}
-		} else {
-			cout << "Cannot assign to a dictionary" << endl;
-			return false;
-		}
-	}
-	return false; //exception occurred
-}
-void Simulator::cmdRun(const std::vector<std::string>& args, bool isRelative) {
-	if(args.size()<=1) {
-		cout << "runfor/runto requires an argument" << endl;
-		return;
-	}
-	if(isRelative)
-		globals->setAutoPauseTime(get_time()+atoi(args[1].c_str()));
-	else
-		globals->setAutoPauseTime(atoi(args[1].c_str()));
-	if(globals->timeScale==0)
-		globals->timeScale=runSpeed;
-}
-void Simulator::cmdRun(const std::vector<std::string>& args) {
-	if(args.size()<=1) {
-		if(globals->timeScale!=0) {
-			cout << "Already running" << endl;
-			return;
-		}
-		globals->timeScale=runSpeed;
-	} else {
-		float speed=atof(args[1].c_str());
-		if(speed!=0)
-			runSpeed=speed;
-		globals->timeScale=speed;
-	}
-}
-void Simulator::cmdPause(const std::vector<std::string>& args) {
-	if(globals->timeScale==0) {
-		if(find(args.begin(),args.end(),"quiet")==args.end())
-			cout << "Already paused" << endl;
-		return;
-	}
-	runSpeed=globals->timeScale;
-	globals->timeScale=0;
-}
-void Simulator::cmdHelp(const std::vector<std::string>& args) {
-	map<string,string> syntax;
-	syntax["load"]="[file]";
-	syntax["save"]="[file]";
-	syntax["runlevel"]="[";
-	for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++) {
-		stringstream ss;
-		ss << i << "|" << SharedGlobals::runlevel_names[i];
-		if(i!=SharedGlobals::NUM_RUNLEVELS-1)
-			ss << " | ";
-		syntax["runlevel"]+=ss.str();
-	}
-	syntax["runlevel"]+="]";
-	syntax["get_time"]="";
-	syntax["set"]="[var=value]";
-	syntax["runto"]="time";
-	syntax["runfor"]="time";
-	syntax["run"]="[speed]";
-	syntax["pause"]="";
-	syntax["step"]="[camera|sensor|timer|motion]";
-	syntax["status"]="[Main|Motion|SoundPlay|Simulator|all]*";
-	syntax["advance"]=syntax["freeze"]=syntax["unfreeze"]="[camera|sensors|all]*";
-	syntax["reset"]="[camera|sensors|all]";
-	
-	map<string,string> help;
-	
-	help["load"]="Load simulator configuration from file; if file unspecified, defaults to 'simulator.plist'.\n"
-		"Note that these files are human-readable XML (with comments!), and you can remove values to specify only a subset of settings.";
-	
-	help["save"]="Save simulator configuration to file; if file unspecified, defaults to 'simulator.plist'.\n"
-		"Note that these files are human-readable XML (with comments!), and you can remove values to specify only a subset of settings.";
-	
-	help["runlevel"]="You can specify a runlevel to move to, or if unspecified, the next one.\n"
-		"You can only move forward runlevels, not backward.  Usually you'll only need RUNNING, "
-		"unless you are debugging startup/shutdown code or the simulator itself.";
-	
-	help["get_time"]="Displays the simulator time.";
-	
-	help["set"]="Sets simulator configuration variables.  Without any arguments, displays all available variables and their current values.\n"
-		"Type 'help set <variable>' to get more information about a particular variable.";
-	
-	help["runto"]="Triggers 'run' until the simulator time reaches the specified value and then pauses.";
-	
-	help["runfor"]="Triggers 'run' until the simulator time has moved by the specified number of milliseconds, then pauses.";
-	
-	help["run"]="Resets simulator speed to last non-zero value (i.e. value prior to last 'pause'), can override by passing a new value as argument.  Can be abbreviated 'r'.";
-	
-	help["pause"]="Equivalent to 'set Speed=0'.  Can be abbreviated 'p'.  Stops the flow of time within the simulator.";
-	
-	help["step"]="Runs at \"full\" speed until the next indicated time frame, or the next available frame if no type is specified.\n"
-		"See 'status' for available frames.";
-	
-	help["status"]="Displays a status report regarding current time, upcoming keyframes, and semaphore usage.  Specify one or more processes to get more in-depth, per-process status reports.";
-	
-	help["advance"]="Sends the next frame for the specified queue(s) in their listed order (can be listed more than once).\n"
-		"Disregards timestamp information, and doesn't advance time, unlike 'step' command.  No arguments and \"all\" is the same as \"sensors camera\".";
-	
-	help["freeze"]="Equivalent to 'set queue.Frozen=true'.\n"
-		"Stops sending frames from the specified queue(s), but still allows time to move (unlike 'pause').  No arguments is the same as \"all\".  See 'advance' and 'unfreeze'.";
-	
-	help["unfreeze"]="Equivalent to 'set queue.Frozen=false'.\n"
-		"Begin sending frames from the specified queue(s) again.  Timestamps for the file listing are offset by the time spent frozen minus frames advanced so the queue(s) will continue from their current position.  No arguments is the same as \"all\".";
-	
-	help["reset"]="Moves the specified data queue(s) back to the first entry in their list.";
-	
-	if(args.size()==1) {
-		cout << "Available commands: " << endl;
-		for(map<string,string>::const_iterator it=help.begin(); it!=help.end(); ++it) {
-			cout << '\t' << it->first << " " << syntax[it->first] << endl;
-		}
-		cout << "type 'help <command>' for more information" << endl;
-	} else {
-		if(help.find(args[1])==help.end()) {
-			cout << "The command '"<< args[1] << "' was not found" << endl;
-			return;
-		}
-		if(args.size()==2) {
-			cout << args[1] << " " << syntax[args[1]] << endl;
-			cout << help[args[1]] << endl;
-		} else {
-			if(args[1]=="set") {
-				plist::ObjectBase* ob=sim::config.getEntry(args[2]);
-				if(ob==NULL) {
-					cout << "'" << args[2] << "' is unknown" << endl;
-					return;
-				}
-				size_t n=args[2].rfind('.');
-				if(n==string::npos)
-					cout << sim::config.getComment(args[2]) << endl;
-				else {
-					ob=sim::config.getEntry(args[2].substr(0,n));
-					if(const plist::Dictionary * dict=dynamic_cast<const plist::Dictionary*>(ob))
-						cout << dict->getComment(args[2].substr(n+1)) << endl;
-					else
-						cout << "'" << args[2].substr(0,n) << "' is not a dictionary" << endl;
-				}
-			} else {
-				cout << args[1] << " " << syntax[args[1]] << endl;
-				cout << help[args[1]] << endl;
-			}
-		}
-	}
-}
-void Simulator::cmdStep(const std::vector<std::string>& args) {
-	if(args.size()<=1) {
-		if(globals->timeScale!=0)
-			globals->timeScale=0;
-		step=STEP_NONE;
-		incrementTime();
-		return;
-	}
-	if(args.size()>2) {
-		cout << args[0] << " takes 0 or 1 arguments; " << args.size()-1 << " supplied" << endl;
-		return;
-	}
-	if(args[1]=="camera")
-		step=STEP_CAMERA;
-	else if(args[1]=="sensor" || args[1]=="sensors")
-		step=STEP_SENSOR;
-	else if(args[1]=="timer")
-		step=STEP_TIMER;
-	else if(args[1]=="motion")
-		step=STEP_MOTION;
-	else {
-		cout << args[1] << " is not a valid argument for 'step'.  Type 'help step'." << endl;
-		return;
-	}
-	if(step==STEP_CAMERA && vision.frozen && !vision.heartbeat) {
-		cout << "Camera queue is frozen and has no heartbeat, cannot step (use 'advance' instead)" << endl;
-		step=STEP_NONE;
-	} else if(step==STEP_SENSOR && sensors.frozen && !sensors.heartbeat) {
-		cout << "Sensor queue is frozen and has no heartbeat, cannot step (use 'advance' instead)" << endl;
-		step=STEP_NONE;
-	} else {
-		unsigned int steps=getNextFrame();
-		if((1<<step) & steps) { // the desired step is the next step -- just increment
-			if(globals->timeScale!=0)
-				globals->timeScale=0;
-			step=STEP_NONE;
-			incrementTime();
-		} else if(globals->timeScale!=-1)
-			globals->timeScale=-1;
-	}
-}
-void Simulator::cmdStatus(const std::vector<std::string>& args) {
-	cout << "Speed is " << static_cast<float>(globals->timeScale);
-	if(globals->timeScale<0)
-		cout << " (full speed mode: avg speed=" << ((globals->simulatorTime-fullspeedSimStart)/fullspeedWallStart.Age().Value()/1000) << "x, "
-			<< " current speed=" << (avgSimTime/avgWallTime/1000) << "x)";
-	cout << endl;
-	cout << "Current time is " << get_time() << endl;
-	unsigned int vis=vision.nextTimestamp();
-	unsigned int sen=sensors.nextTimestamp();
-	unsigned int tim=globals->getNextTimer();
-	unsigned int mot=globals->getNextMotion();
-	cout << "Next camera: ";
-	if(vision.numLoaded()==0) cout << "(none)"; else {
-		if(vision.frozen)
-			cout << "Frozen@";
-		cout << vision.getNextFrame();
-		if(!vision.frozen || vision.heartbeat) {
-			if(vision.frozen && vision.heartbeat && vision.getNextFrame()!="heartbeat")
-				cout << " heartbeat";
-			cout << " scheduled at " << vis;
-		}
-	}
-	cout << endl;
-	cout << "Next sensor: ";
-	if(sensors.numLoaded()==0) cout << "(none)"; else {
-		if(sensors.frozen)
-			cout << "Frozen@";
-		cout << sensors.getNextFrame();
-		if(!sensors.frozen || sensors.heartbeat) {
-			if(sensors.frozen && sensors.heartbeat && sensors.getNextFrame()!="heartbeat")
-				cout << " heartbeat";
-			cout << " scheduled at " << sen;
-		}
-	}
-	cout << endl;
-	cout << "Next timer: ";
-	if(tim==-1U) cout << "(none)"; else cout << tim;
-	cout << endl;
-	cout << "Next motion: ";
-	if(mot==-1U) cout << "(none)"; else cout << mot;
-	cout << endl;
-	unsigned int semUsed=MutexLockBase::getSemaphoreManager()->used();
-	unsigned int semMax=semUsed+MutexLockBase::getSemaphoreManager()->available();
-	cout << "Semaphores used: " << semUsed << "/" << semMax << " (" << ((semUsed*10000+5)/semMax/10)/10.f << "%)" << endl;
-	cout << endl;
-	if(args.size()>1) {
-		SemaphoreManager::semid_t sem=statusRequest->addReadStatusListener();
-		for(unsigned int i=1; i<args.size(); ++i) {
-			RCRegion * region=new RCRegion(args[i].size()+1);
-			strncpy(region->Base(),args[i].c_str(),args[i].size()+1);
-			statusRequest->sendMessage(region);
-			region->RemoveReference();
-		}
-		//wait until they're done to put the prompt back up
-		if(sem!=statusRequest->getSemaphoreManager()->invalid()) {
-			statusRequest->getSemaphoreManager()->lower(sem,args.size()-1);
-			statusRequest->removeReadStatusListener(sem);
-		}
-		//check to see if we're included:
-		//haha, now I remember why I don't use functional programming
-		/*if(find_if(args.begin()+1,args.end(),not1(__gnu_cxx::compose1(bind2nd(ptr_fun(strcasecmp),getName().c_str()),mem_fun_ref(&string::c_str))))!=args.end())
-			statusReport(cout);*/
-		for(unsigned int i=1; i<args.size(); ++i) {
-			if(strcasecmp(args[i].c_str(),getName().c_str())==0 || strcasecmp(args[i].c_str(),"all")==0) {
-				statusReport(cout);
-				cout << endl;
-			}
-		}
-	}
-}
-void Simulator::cmdAdvance(const std::vector<std::string>& args) {
-	if(curLevel!=SharedGlobals::RUNNING) {
-		cout << args[0] << " can only be used in the RUNNING runlevel" << endl;
-		return;
-	}
-	std::string senstr="sensors";
-	std::string camstr="camera";
-	std::vector<std::string> queuenames;
-	bool isAll=false;
-	if(args.size()<=1) { // no arguments supplied, advance all
-		queuenames.push_back(senstr);
-		queuenames.push_back(camstr);
-		isAll=true;
-	}
-	for(unsigned int i=1; i<args.size(); ++i) {
-		if(args[i]==camstr)
-			queuenames.push_back(camstr);
-		else if(args[i]==senstr)
-			queuenames.push_back(senstr);
-		else if(args[i]=="all") {
-			queuenames.push_back(senstr);
-			queuenames.push_back(camstr);
-			isAll=true;
-		} else {
-			cout << "invalid argument for advance command: " << args[i] << endl;
-			return;
-		}
-	}
-	for(std::vector<std::string>::iterator it=queuenames.begin(); it!=queuenames.end(); ++it) {
-		LoadFileThread * lft=NULL;
-		MessageQueueBase* q=NULL;
-		if(*it==camstr) {
-			lft=&vision;
-			q=&(*cameraQueue);
-		} else if(*it==senstr) {
-			lft=&sensors;
-			q=&(*sensorQueue);
-		} else {
-			cout << "Simulator: internal error, invalid queue " << *it << endl;
-			return;
-		}
-		SemaphoreManager::semid_t sem=q->addReadStatusListener(); //register read status listener before sending!
-		bool sent=lft->advanceFrame(true); // send frame
-		if(!sent) { // no data in queue
-			sent=lft->heartbeat; // but there may have been a heartbeat?
-			if(!isAll) {
-				// only report empty queue if the queue was explicitly specified
-				cout << "No data in " << *it << " queue";
-				if(lft->heartbeat)
-					cout << ", sent heartbeat";
-				cout << endl;
-			}
-		}
-		if(sent)
-			q->getSemaphoreManager()->lower(sem,true); //block until we know message was read
-		q->removeReadStatusListener(sem);
-	}
-}
-void Simulator::cmdFreeze(bool v, const std::vector<std::string>& args) {
-	std::string senstr="sensors";
-	std::string camstr="camera";
-	std::set<std::string> queuenames;
-	if(args.size()<=1) {
-		queuenames.insert(camstr);
-		queuenames.insert(senstr);
-	}
-	for(unsigned int i=1; i<args.size(); ++i) {
-		if(args[i]==camstr)
-			queuenames.insert(camstr);
-		else if(args[i]==senstr)
-			queuenames.insert(senstr);
-		else if(args[i]=="all") {
-			queuenames.insert(camstr);
-			queuenames.insert(senstr);
-		} else {
-			cout << "invalid argument for freeze/unfreeze command: " << args[i] << endl;
-			return;
-		}
-	}
-	for(std::set<std::string>::iterator it=queuenames.begin(); it!=queuenames.end(); ++it) {
-		if(*it==camstr)
-			vision.frozen=v;
-		else if(*it==senstr)
-			sensors.frozen=v;
-		else {
-			cout << "Simulator: internal error, invalid queue " << *it << endl;
-			return;
-		}
-	}
-}
-void Simulator::cmdReset(const std::vector<std::string>& args) {
-	std::string senstr="sensors";
-	std::string camstr="camera";
-	for(unsigned int i=1; i<args.size(); ++i) {
-		if(args[i]==camstr)
-			vision.setFrame(0);
-		else if(args[i]==senstr)
-			sensors.setFrame(0);
-		else if(args[i]=="all") {
-			vision.setFrame(0);
-			sensors.setFrame(0);
-		} else
-			cout << "invalid argument for reset command: " << args[i] << endl;
-	}
-}
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.62 $
- * $State: Exp $
- * $Date: 2006/09/26 21:42:50 $
- */
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/Simulator.h ./local/sim/Simulator.h
--- ../Tekkotsu_3.0/local/sim/Simulator.h	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/Simulator.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,138 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_Simulator_h_
-#define INCLUDED_Simulator_h_
-
-#include "Process.h"
-#include "sim.h"
-#include "IPC/SharedObject.h"
-#include "IPC/MessageQueueStatusThread.h"
-#include "SharedGlobals.h"
-#include "Shared/plist.h"
-#include "Shared/debuget.h"
-#include "local/LoadImageThread.h"
-#include <set>
-
-class Simulator : public Process,  public plist::PrimitiveListener, public MessageQueueStatusThread::StatusListener {
-public:
-	//! constructor
-	Simulator();
-	
-	~Simulator();
-
-	virtual void DoStart();
-	virtual void DoStop();
-	virtual void run();
-	
-	static const char * getClassName() { return "Simulator"; }
-	static ProcessID::ProcessID_t getID() { return ProcessID::SimulatorProcess; }
-	
-	static const char * getCameraQueueID() { return "CameraData"; }
-	static const char * getSensorQueueID() { return "SensorData"; }
-	static const char * getTimerWakeupID() { return "TimerWakeup"; }
-	static const char * getMotionWakeupID() { return "MotionWakeup"; }
-	static const char * getStatusRequestID() { return "StatusRequest"; }
-	static const char * getCommandQueueID() { return "CommandQueue"; }
-	
-	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
-
-	virtual void messagesRead(MessageQueueBase& mq, unsigned int n);
-	
-	static void sendCommand(const std::string& cmd);
-
-protected:
-	class : public MessageQueueBase::MessageFilter {
-	public:
-		virtual bool filterSendRequest(RCRegion* rcr) {
-			globals->motion.frameNumber++;
-			ASSERT(globals->motion.frameNumber==LoadFileThread::recoverSN(rcr),"globals->motion.frameNumber does not match frame number sent! (" << globals->motion.frameNumber << " vs " << LoadFileThread::recoverSN(rcr));
-			return true;
-		}
-	} frameCounter;
-	
-	class CommandThread : public Thread {
-	public:
-		virtual void * run();
-	};
-	enum step_t {
-		STEP_NONE,
-		STEP_CAMERA,
-		STEP_SENSOR,
-		STEP_TIMER,
-		STEP_MOTION
-	};
-	
-	void incrementTime();
-	void sendTimerWakeup();
-	unsigned int getNextFrame();
-	void resetSpeedMode();
-	
-	void processRunlevel(SharedGlobals::runlevel_t curRunLevel);
-	void processCommand(const std::string& line, bool addToHistory); //!< process an individual command
-	static bool gotCommand(RCRegion* msg); //!< for commands coming from other processes via #commandQueue and #commandrecv
-	
-	void cmdQuit(const std::vector<std::string>& args);
-	void cmdLoad(const std::vector<std::string>& args);
-	void cmdSave(const std::vector<std::string>& args);
-	void cmdRunlevel(const std::vector<std::string>& args);
-	bool cmdSet(const std::vector<std::string>& args);
-	void cmdRun(const std::vector<std::string>& args, bool isRelative);
-	void cmdRun(const std::vector<std::string>& args);
-	void cmdPause(const std::vector<std::string>& args);
-	void cmdHelp(const std::vector<std::string>& args);
-	void cmdStep(const std::vector<std::string>& args);
-	void cmdStatus(const std::vector<std::string>& args);
-	void cmdAdvance(const std::vector<std::string>& args);
-	void cmdFreeze(bool v, const std::vector<std::string>& args);
-	void cmdReset(const std::vector<std::string>& args);
-	
-	SharedObject<sim::CameraQueue_t> cameraQueue;
-	SharedObject<sim::SensorQueue_t> sensorQueue;
-	SharedObject<sim::TimerWakeup_t> timerWakeup;
-	SharedObject<sim::MotionWakeup_t> motionWakeup;
-	SharedObject<sim::StatusRequest_t> statusRequest;
-	SharedObject<sim::EventQueue_t> events;
-	typedef MessageQueue<10> CommandQueue_t;
-	SharedObject<CommandQueue_t> commandQueue;
-	
-	MessageQueueStatusThread cameraStatus;
-	MessageQueueStatusThread sensorStatus;
-	MessageQueueStatusThread timerStatus;
-	MessageQueueStatusThread motionStatus;
-	MessageQueueStatusThread eventsStatus;
-
-	class MessageReceiver * commandrecv;
-	
-	LoadImageThread vision;
-	LoadFileThread sensors;
-	std::set<unsigned int> frameTimes;
-	float runSpeed;
-	step_t step;
-	unsigned int waitingSteps;
-	SharedGlobals::runlevel_t curLevel;
-	
-	TimeET fullspeedWallStart; //!< "real" wall-clock time that full-speed mode was entered
-	unsigned int fullspeedSimStart; //!< simulator time at which full-speed mode was entered
-	TimeET lastFrameWallStart; //!< "real" wall-clock time that processing started on last frame (only valid in full-speed mode)
-	float avgWallTime; //!< running average of frame processing time
-	float avgSimTime; //!< running average of frame increments
-	static const float avgSpeedupGamma; //!< gamma parameter for calculating running average in #avgFrameTime
-	
-	ThreadNS::Lock simLock;
-
-private:
-	Simulator(const Simulator&); //!< don't call (copy constructor)
-	Simulator& operator=(const Simulator&); //!< don't call (assignment operator)
-};
-
-/*! @file
- * @brief Defines Simulator, which DESCRIPTION
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.28 $
- * $State: Exp $
- * $Date: 2006/09/28 20:42:52 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/SoundPlay.cc ./local/sim/SoundPlay.cc
--- ../Tekkotsu_3.0/local/sim/SoundPlay.cc	2006-09-18 14:07:58.000000000 -0400
+++ ./local/sim/SoundPlay.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,76 +0,0 @@
-#include "SoundPlay.h"
-#include "Simulator.h"
-#include "SharedGlobals.h"
-#include "Main.h"
-#include "IPC/RegionRegistry.h"
-#include "IPC/MessageReceiver.h"
-#include "Events/EventRouter.h"
-
-SoundPlay::SoundPlay()
-	: Process(getID(),getClassName()),
-		requests(ipc_setup->registerRegion(getSoundPlayID(),sizeof(sim::SoundPlayQueue_t))),
-		events(ipc_setup->registerRegion(Main::getEventsID(),sizeof(sim::EventQueue_t))),
-		statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
-		soundmanager(ipc_setup->registerRegion(getSoundManagerID(),sizeof(SoundManager))),
-		soundProf(ipc_setup->registerRegion(getSoundProfilerID(),sizeof(soundProfiler_t))),
-		etrans(NULL), sndrecv(NULL), statusrecv(NULL)
-{
-	new (&(*requests)) sim::SoundPlayQueue_t;
-	new (&(*soundmanager)) SoundManager;
-	new (&(*soundProfiler)) soundProfiler_t;
-	sndman=&(*soundmanager);
-	::soundProfiler=&(*soundProf);
-
-	//need to register any events which we might be sending
-	EventTranslator::registerPrototype<EventBase>(); //Sound only sends the basic event type
-}
-
-SoundPlay::~SoundPlay() {
-	delete etrans;
-	etrans=NULL;
-	MotionManager::setTranslator(NULL);
-}
-
-void SoundPlay::DoStart() {
-	Process::DoStart();
-	//These are constructed by other processes, so need to wait
-	//until the construction runlevel is complete before we access them
-	etrans=new IPCEventTranslator(*events);
-	MotionManager::setTranslator(etrans); //although SoundPlay shouldn't use any motions...
-
-	// Set up Event Translator to trap and send events to main process
-	//send everything over except erouter events
-	for(unsigned int i=0; i<EventBase::numEGIDs; i++)
-		if(i!=EventBase::erouterEGID)
-			erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
-	
-	sndrecv=new MessageReceiver(*requests,gotSnd);
-	statusrecv=new MessageReceiver(*statusRequest,statusReport);
-}
-
-void SoundPlay::DoStop() {
-	sndrecv->finish();
-	statusrecv->finish();
-
-	delete sndrecv;
-	sndrecv=NULL;
-	delete statusrecv;
-	statusrecv=NULL;
-	
-	sndman->stopPlay();
-	erouter->removeTrapper(etrans);
-	Process::DoStop();
-}
-
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.7 $
- * $State: Exp $
- * $Date: 2006/09/18 18:07:58 $
- */
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/SoundPlay.h ./local/sim/SoundPlay.h
--- ../Tekkotsu_3.0/local/sim/SoundPlay.h	2006-07-13 13:25:51.000000000 -0400
+++ ./local/sim/SoundPlay.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,58 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_SoundPlay_h_
-#define INCLUDED_SoundPlay_h_
-
-#include "Process.h"
-#include "sim.h"
-#include "IPC/ProcessID.h"
-#include "IPC/SharedObject.h"
-#include "SharedGlobals.h"
-#include "Sound/SoundManager.h"
-#include "Shared/Profiler.h"
-
-class SoundPlay : public Process {
-public:
-	//! constructor
-	SoundPlay();
-	//! destructor
-	~SoundPlay();
-
-	virtual void DoStart();
-	virtual void DoStop();
-
-	static const char * getClassName() { return "SoundPlay"; }
-	static ProcessID::ProcessID_t getID() { return ProcessID::SoundProcess; }
-	
-	static const char * getSoundPlayID() { return "Sounds"; }
-	static const char * getSoundManagerID() { return "SoundManager"; }
-	static const char * getSoundProfilerID() { return "SoundProfiler"; }
-
-protected:
-	SharedObject<sim::SoundPlayQueue_t> requests;
-	SharedObject<sim::EventQueue_t> events;
-	SharedObject<sim::StatusRequest_t> statusRequest;
-	SharedObject<SoundManager> soundmanager;
-	SharedObject<soundProfiler_t> soundProf;
-	
-	IPCEventTranslator * etrans;
-	class MessageReceiver * sndrecv;
-	class MessageReceiver * statusrecv;
-	static bool gotSnd(RCRegion* msg) { sndman->ProcessMsg(msg); return true; }
-	
-private:
-	SoundPlay(const SoundPlay&); //!< don't call (copy constructor)
-	SoundPlay& operator=(const SoundPlay&); //!< don't call (assignment operator)
-};
-
-/*! @file
- * @brief Defines SoundPlay, which DESCRIPTION
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.6 $
- * $State: Exp $
- * $Date: 2006/07/13 17:25:51 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/TimerExecThread.cc ./local/sim/TimerExecThread.cc
--- ../Tekkotsu_3.0/local/sim/TimerExecThread.cc	2006-07-11 18:40:25.000000000 -0400
+++ ./local/sim/TimerExecThread.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,69 +0,0 @@
-#include "TimerExecThread.h"
-#include "SharedGlobals.h"
-#include "Shared/ProjectInterface.h"
-#include "Shared/MarkScope.h"
-#include "Shared/get_time.h"
-#include "Events/EventRouter.h"
-
-//better to put this here instead of the header
-using namespace std; 
-
-
-void TimerExecThread::reset() {
-	if((globals->getNextTimer()==-1U || globals->timeScale<=0) && isRunning())
-		stop();
-	else if(globals->timeScale>0 && !isRunning())
-		start();
-	else if(isRunning()) {
-		interrupt();
-	}
-}
-
-long TimerExecThread::calcSleepTime() {
-	startTime.Set();
-	return static_cast<long>((globals->getNextTimer()-get_time())/globals->timeScale);
-}
-
-bool TimerExecThread::launched() {
-	if(globals->timeScale<=0)
-		return false;
-	delay=calcSleepTime();
-	return PollThread::launched();
-}
-
-bool TimerExecThread::poll() {
-	MarkScope bl(behaviorLock);
-	//cout << "Poll at " << get_time() << " next timer " << globals->getNextTimer() << " (vs. " << erouter->getNextTimer() << ")" << endl;
-	//this happens normally:
-	//ASSERT(get_time()>=globals->getNextTimer(),"TimerExecThread::poll() early (time="<<get_time()<< " vs. nextTimer=" <<globals->getNextTimer()<<")");
-	try {
-		erouter->processTimers();
-	} catch(const std::exception& ex) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
-			throw;
-	} catch(...) {
-		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
-			throw;
-	}
-	globals->setNextTimer(erouter->getNextTimer());
-	if(globals->getNextTimer()==-1U)
-		return false;
-	period=calcSleepTime();
-	return true;
-}
-
-void TimerExecThread::interrupted() {
-	delay=calcSleepTime();
-}
-
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.5 $
- * $State: Exp $
- * $Date: 2006/07/11 22:40:25 $
- */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/TimerExecThread.h ./local/sim/TimerExecThread.h
--- ../Tekkotsu_3.0/local/sim/TimerExecThread.h	2006-08-23 15:02:32.000000000 -0400
+++ ./local/sim/TimerExecThread.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,34 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_TimerExecThread_h_
-#define INCLUDED_TimerExecThread_h_
-
-#include "IPC/PollThread.h"
-#include "Shared/Resource.h"
-
-//! executes EventRouter::processTimers() as necessary (allows timers to work without any other vision or sensor processing)
-class TimerExecThread : public PollThread {
-public:
-	explicit TimerExecThread(Resource& bl, bool autoStart=true) : PollThread(), behaviorLock(bl) { if(autoStart) reset(); }
-	virtual void reset(); //!< starts and stops thread as needed, or interrupts thread to reset sleep time if already running
-	
-protected:
-	virtual long calcSleepTime(); //!< returns the time in milliseconds to sleep until the next timer; resets PollThread::startTime
-	virtual bool launched();
-	virtual bool poll();
-	virtual void interrupted();
-
-	Resource& behaviorLock; //!< a lock on behaviors which should be obtained before processing timer events
-};
-
-/*! @file
- * @brief 
- * @author Ethan Tira-Thompson (ejt) (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.4 $
- * $State: Exp $
- * $Date: 2006/08/23 19:02:32 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/sim.cc ./local/sim/sim.cc
--- ../Tekkotsu_3.0/local/sim/sim.cc	2006-09-28 16:42:52.000000000 -0400
+++ ./local/sim/sim.cc	1969-12-31 19:00:00.000000000 -0500
@@ -1,442 +0,0 @@
-#include "sim.h"
-#include "local/sim/SharedGlobals.h"
-#include "local/sim/Main.h"
-#include "local/sim/Motion.h"
-#include "local/sim/SoundPlay.h"
-#include "local/sim/SimConfig.h"
-#include "IPC/RegionRegistry.h"
-#include "local/sim/Simulator.h"
-#include "IPC/SharedObject.h"
-#include "Shared/Config.h"
-#include "Shared/string_util.h"
-#include "Shared/StackTrace.h"
-#include "IPC/SemaphoreManager.h"
-#include "Events/EventRouter.h"
-#include <iostream>
-#include <sstream>
-#include <iomanip>
-#include <sys/ipc.h>
-#include <signal.h>
-#include <unistd.h>
-#include <sys/wait.h>
-#include <sys/stat.h>
-#include <errno.h>
-#include <pwd.h>
-	
-using namespace std;
-	
-const char * const sim::usage=
-"[-h|--help] [-c|--config config-file] [var=val ...]";
-	
-//only true for the first process -- children should set this to false when they fork
-bool sim::original=true;
-	
-SimConfig sim::config;
-vector<string> sim::assignments;
-	
-/* Although I generally dislike the "can't have main function without a class declaration" style of java,
- * sometimes it does come in handy.  See the class notes for sim for more information. */
-int main(int argc, const char* argv[]) {
-	
-	//This should match the ID of the process sent to manage_process by sim::run()
-	// *must* be done before we create any shared regions to provide proper reference counting
-	ProcessID::setID(ProcessID::SimulatorProcess);
-			
-	//initialize some threading globals
-	Thread::initMainThread();
-	
-#ifndef USE_UNBACKED_SHM
-	//append username to shared memory root avoid permission denied
-	struct passwd * pw=getpwuid(getuid());
-	if(pw!=NULL) {
-		if(RCRegion::shmRoot[RCRegion::shmRoot.size()-1]=='/') {
-			RCRegion::shmRoot[RCRegion::shmRoot.size()-1]='-';
-			RCRegion::shmRoot+=pw->pw_name;
-			RCRegion::shmRoot+='/';
-		} else {
-			RCRegion::shmRoot+=pw->pw_name;
-		}
-	}
-#endif
-
-	{
-		sim s;
-		if(!s.processCommandLine(argc,argv))
-			return 2;
-		//now the real meat begins
-		if(!s.run()) //when this eventually returns, we're done (and all our children forks as well)
-			return 1;
-		return 0;
-	}
-}
-	
-sim::sim() :
-	mutexSemMgr(),
-	glob(),
-	subj(),
-	child(static_cast<pid_t>(-1))
-{
-	//what's the granularity of usleep on this platform?
-	MutexLockBase::usleep_granularity=measure_usleep_cost();
-	//use our own custom get_time routine
-	project_get_time::get_time_callback=&sim_get_time;
-	project_get_time::get_timeScale_callback=&sim_getTimeScale;
-	
-	//setup signal handlers
-	signal(SIGHUP, handle_signal);
-	signal(SIGINT, handle_signal);
-	signal(SIGQUIT, handle_signal);
-	signal(SIGILL, handle_signal);
-	signal(SIGABRT, handle_signal);
-	signal(SIGFPE, handle_signal);
-	signal(SIGBUS, handle_signal);
-	signal(SIGSEGV, handle_signal);
-	signal(SIGSYS, handle_signal);
-	signal(SIGPIPE, handle_signal);
-	signal(SIGTERM, handle_signal);
-	atexit(handle_exit);
-		
-#ifndef USE_UNBACKED_SHM
-	//add config item for file backed memory
-	sim::config.addEntry("TempStorageRoot",RCRegion::shmRoot,"The directory to use for temporary storage of file-backed shared memory regions");
-#endif
-	
-	//Set up mutex's semaphore manager
-	MutexLockBase::setSemaphoreManager(&(*mutexSemMgr));
-	//Set up MessageQueue's semaphore manager
-	MessageQueueBase::setSemaphoreManager(&(*mutexSemMgr));
-	
-	//Set up shared global parameters -- e.g. clock and runlevel info
-	globals = &(*glob);
-	sim::config.addEntry("Speed",globals->timeScale,"The speed at which to run the simulation, as a multiple of \"real-time\".\nFor example, '1' is normal, '0.5' is half-speed, '0' is paused.\nAny negative value requests non-realtime mode, where the clock is moved as fast as processing (or manual control) allows.");
-	globals->simulatorTime=sim::config.initSimTime;
-	sim::config.addEntry("Motion",globals->motion,"Parameters for motion simulation");
-		
-	//Set up the subject registration area
-	ipc_setup = &(*subj);
-		
-	//everyone uses config and erouter, might as well set it up here
-	::config = new Config();
-	::config->setFileSystemRoot("ms");
-	::config->readConfig("config/tekkotsu.cfg");
-	::config->readConfig("config/sim_ovrd.cfg");
-	::erouter = new EventRouter;
-	
-	//we won't have sensor values yet, but the system clock is good enough
-	if(::config->main.seed_rng) {
-		double t=TimeET().Value(); //current time with nanosecond resolution
-		unsigned int * tm=reinterpret_cast<unsigned int*>(&t);
-		unsigned int seed=tm[0]+tm[1];
-		cout << "RNG seed=" << seed << endl;;
-		srand(seed);
-	}
-}
-	
-bool sim::processCommandLine(int argc, const char* argv[]) {
-	int i=0;
-	
-	//try to load the default configuration file
-	const char * const defaultconfigfile="simulator.plist";
-	struct stat sb;
-	if(stat(defaultconfigfile,&sb)==0) {
-		if(!sim::config.loadFile(defaultconfigfile)) {
-			cerr << "Error loading default configuration file, may be malformed." << endl;
-			return false;
-		}
-	} else
-		sim::config.setLastFile(defaultconfigfile);
-	
-	//set the prompt from the binary name
-	config.cmdPrompt=argv[i];
-	if(config.cmdPrompt.rfind('/')!=string::npos)
-		config.cmdPrompt=config.cmdPrompt.substr(config.cmdPrompt.rfind('/')+1);
-	config.cmdPrompt+="> ";
-	
-	//now run through the rest of the arguments
-	for(i++; i<argc; i++) {
-		if(!strcmp(argv[i],"-h") || !strcmp(argv[i],"--help")) {
-			cerr << argv[0] << ": " << usage << endl;
-			return false;
-		} else if(!strcmp(argv[i],"-c") || !strcmp(argv[i],"--config")) {
-			if(!sim::config.loadFile(argv[++i]))
-				return false;
-		} else if(strchr(argv[i],'=')!=NULL) {
-			string value=string_util::trim(strchr(argv[i],'=')+1);
-			string key=string_util::trim(string(argv[i],strchr(argv[i],'=')-argv[i]));
-			plist::ObjectBase* ob=sim::config.getEntry(key);
-			if(ob==NULL)
-				assignments.push_back(argv[i]); //might be a key which is added by Simulator, we'll come back to it once Simulator has been launched
-			else if(plist::PrimitiveBase* pbp=dynamic_cast<plist::PrimitiveBase*>(ob)) {
-				try {
-					pbp->set(value);
-				} catch(const XMLLoadSave::bad_format& bf) {
-					cout << "'" << value << "' is a bad value for '" << key << "'" << endl;
-					cout << bf.what() << endl;
-					return false;
-				} catch(const std::exception& e) {
-					cout << "An exception occured: " << e.what() << endl;
-					return false;
-				}
-			} else {
-				cout << "Cannot assign to a dictionary ("<<key<<")" << endl;
-				return false;
-			}
-		} else {
-			cerr << "Unknown argument '" << argv[i] << "': assignments must be of the form 'var=value'" << endl;
-			return false;
-		}
-	}
-		
-	return true;
-}
-	
-bool sim::run() {
-	//this will force all of the processes to wait at the end of construction
-	//until we're done spawning all of them
-	globals->level_count[SharedGlobals::CREATED]++;
-		
-	cout << "Spawning processes..." << endl;
-	cout.setf(ios::left);
-	cout << "  Initializing runlevel " << setw(12) << SharedGlobals::runlevel_names[SharedGlobals::CONSTRUCTING] << endl;
-	cout.unsetf(ios::left);
-	if(fork_process<Main>()) ;
-	else if(fork_process<Motion>()) ;
-	else if(fork_process<SoundPlay>()) ;
-	else manage_process<Simulator>();
-		
-	//every process is going to pass through here on their way out
-	globals->level_count[SharedGlobals::DESTRUCTED]++;
-		
-	return true;
-}
-	
-sim::~sim() {
-	MutexLockBase::setSemaphoreManager(NULL);
-	MessageQueueBase::setSemaphoreManager(NULL);
-	globals=NULL;
-	ipc_setup=NULL;
-	
-	if(child==static_cast<pid_t>(-1)) // never got to the fork (or had an error at the fork)
-		return;
-	
-	if(original)
-		cout << ProcessID::getIDStr() << ": Waiting for children to exit..." << endl;
-	if(child!=0) {
-		int status;
-		int res=waitpid(child,&status,0);
-		if(res<0 && errno!=ECHILD)
-			perror("wait");
-		if(!WIFEXITED(status))
-			cout << ProcessID::getIDStr() << ": waiting for " << child << "..." << endl;
-		while(!WIFEXITED(status)) {
-			sleep(1);
-			res=waitpid(child,&status,0);
-			if(res<0 && errno!=ECHILD)
-				perror("wait");
-		}
-	}
-}
-	
-void sim::wait_runlevel(SharedGlobals::runlevel_t level) {
-	globals->lock.lock(ProcessID::getID());
-	globals->level_count[level]++;
-	if(globals->level_count[level]==1) {
-		cout.setf(ios::left);
-		cout << "Collecting for runlevel " << setw(12) << SharedGlobals::runlevel_names[level] << "  |=" << flush;
-		cout.unsetf(ios::left);
-	}
-	cout << Process::getName() << '=' << flush;
-	if(globals->level_count[level]==globals->level_count[SharedGlobals::CREATED])
-		cout << "|  done" << endl;
-	globals->lock.unlock();
-	while(globals->level_count[level]!=globals->level_count[SharedGlobals::CREATED])
-		usleep(150*1000);
-	globals->lock.lock(ProcessID::getID());
-	globals->lock.unlock();
-}
-	
-template<class T>
-void sim::manage_process() {
-	//initialize the first runlevel
-	globals->lock.lock(T::getID());
-	globals->level_count[SharedGlobals::CONSTRUCTING]++;
-	cout << setw(35) << T::getClassName() << ":  ProcessID::getID()=" << T::getID() << "   pid=" << getpid() << endl;
-	T t;
-	ASSERT(T::getID()==ProcessID::getID(),"Process ID set incorrectly!");
-	globals->lock.unlock();
-	while(globals->level_count[SharedGlobals::CONSTRUCTING]!=globals->level_count[SharedGlobals::CREATED])
-		usleep(150*1000);
-	globals->lock.lock(ProcessID::getID());
-	globals->lock.unlock();
-	
-	//now just walk through each of the other steps
-	wait_runlevel(SharedGlobals::STARTING);
-	t.DoStart();
-	wait_runlevel(SharedGlobals::RUNNING);
-	t.run(); //should return if/when SharedGlobals::shutdown flag is set
-	wait_runlevel(SharedGlobals::STOPPING);
-	t.DoStop();
-	wait_runlevel(SharedGlobals::DESTRUCTING);
-}
-	
-template<class T>
-bool sim::fork_process() {
-	RCRegion::aboutToFork(T::getID());
-	MutexLockBase::aboutToFork();
-	//increment this *before* the fork to guarantee everyone knows to wait for the new process
-	globals->level_count[SharedGlobals::CREATED]++;
-	child=fork();
-	if(child==static_cast<pid_t>(-1)) {
-		cerr << "Unable to spawn simulator process!" << endl;
-		exit(1);
-	}
-	if(child!=0) {
-		manage_process<T>();
-		return true;
-	}
-	original=false;
-	return false;
-}
-	
-void sim::handle_signal(int sig) {
-	//	sigset_t mask_set;  /* used to set a signal masking set. */
-	//	sigset_t old_set;   /* used to store the old mask set.   */
-		
-	/* reset the signal handler for next time */
-	//	signal(sig, handle_signal);
-	/* mask any further signals while we're inside the handler. */
-	//	sigfillset(&mask_set);
-	//	sigprocmask(SIG_SETMASK, &mask_set, &old_set);
-		
-	char * name=NULL;
-	char defBuf[30];
-	switch(sig) {
-	case SIGINT: name="SIGINT"; break;
-	case SIGQUIT: name="SIGQUIT"; break;
-	case SIGBUS: name="SIGBUS"; break;
-	case SIGSEGV: name="SIGSEGV"; break;
-	case SIGTERM: name="SIGTERM"; break;
-	case SIGABRT: name="SIGABRT"; break;
-	case SIGFPE: name="SIGFPE"; break;
-	case SIGPIPE: name="SIGPIPE"; break;
-	case SIGHUP: name="SIGHUP"; break;
-	default:
-		name=defBuf;
-		snprintf(name,30,"signal %d",sig);
-		break;
-	}
-	cout << "*** ERROR " << Process::getName() << ": Received " << name << endl;
-	
-	static bool firstCall=true;
-	if(!firstCall) {
-		cerr << "Signal handler was recursively called, may be leaked IPC resources :(" << endl;
-		cerr << "The 'ipcs' tool can be used to manually free these, if it becomes a problem. " << endl;
-		cerr << "However, simply re-running will generally reclaim the previous buffers for you." << endl;
-		exit(EXIT_FAILURE);
-		return;
-	}
-	firstCall=false;
-	
-	stacktrace::displayCurrentStackTrace(15);
-	
-	cout << "*** ERROR " << Process::getName() << ": Engaging fault shutdown..." << endl;
-	if(globals!=NULL && !globals->hadFault()) {
-		if(!MutexLockBase::getSemaphoreManager()->hadFault())
-			globals->lock.lock(ProcessID::getID());
-		if(globals->level_count[SharedGlobals::CREATED]>0)
-			globals->level_count[SharedGlobals::CREATED]--;
-		else
-			cout << "*** ERROR " << Process::getName() << ": level_count[CREATED] underflow" << endl;
-		globals->signalShutdown();
-		if(!MutexLockBase::getSemaphoreManager()->hadFault())
-			globals->lock.unlock();
-		globals->faultShutdown();
-	}
-	if(MutexLockBase::getSemaphoreManager()!=NULL && !MutexLockBase::getSemaphoreManager()->hadFault()) {
-		cout << "*** ERROR " << Process::getName() << ": Dereferencing mutex SemaphoreManager" << endl;
-		MutexLockBase::setSemaphoreManager(NULL); //reset to preallocated instance
-		MutexLockBase::getSemaphoreManager()->faultShutdown();
-	}
-	cout << "*** ERROR " << Process::getName() << ": Dereferencing shared memory regions" << endl;
-	RCRegion::faultShutdown();
-	cout << "*** ERROR " << Process::getName() << ": Exiting..." << endl;
-	exit(EXIT_FAILURE);
-}
-	
-void sim::handle_exit() {
-	static bool firstCall=true;
-	if(!firstCall) {
-		cerr << "handle_exit was recursively called" << endl;
-		return;
-	}
-	firstCall=false;
-	if(Process::getName().size()>0)
-		cout << Process::getName() << ": Exiting..." << endl;
-	if(RCRegion::NumberOfAttach()==0) {
-		if(original)
-			cout << "Clean shutdown complete.  Have a nice day." << endl;
-		return;
-	}
-	cout << "*** ERROR " << Process::getName() << ": Exit with attached memory regions, engaging fault shutdown..." << endl;
-	if(globals!=NULL && !globals->hadFault()) {
-		if(!MutexLockBase::getSemaphoreManager()->hadFault())
-			globals->lock.lock(ProcessID::getID());
-		if(globals->level_count[SharedGlobals::CREATED]>0)
-			globals->level_count[SharedGlobals::CREATED]--;
-		else
-			cout << "*** ERROR " << Process::getName() << ": level_count[CREATED] underflow" << endl;
-		globals->signalShutdown();
-		if(!MutexLockBase::getSemaphoreManager()->hadFault())
-			globals->lock.unlock();
-		globals->faultShutdown();
-	} else {
-		cerr << "*** ERROR " << Process::getName() << ": exit with previous global fault" << endl;
-	}
-	if(MutexLockBase::getSemaphoreManager()!=NULL && !MutexLockBase::getSemaphoreManager()->hadFault()) {
-		cout << "*** ERROR " << Process::getName() << ": Dereferencing mutex SemaphoreManager" << endl;
-		MutexLockBase::setSemaphoreManager(NULL); //reset to preallocated instance
-		MutexLockBase::getSemaphoreManager()->faultShutdown();
-	} else {
-		cerr << "*** ERROR " << Process::getName() << ": exit with previous mutex fault" << endl;
-	}
-	cout << "*** ERROR " << Process::getName() << ": Dereferencing shared memory regions" << endl;
-	RCRegion::faultShutdown();
-	cout << "*** ERROR " << Process::getName() << ": Exiting..." << endl;
-}
-	
-unsigned int sim::measure_usleep_cost() {
-	usleep(50000); //to hopefully clear out the scheduler for the duration of our test
-	const unsigned int TRIALS=50;
-	TimeET mintime(1.0); //should definitely be less than a second
-	for(unsigned int i=0; i<TRIALS; i++) {
-		//measure usleep (plus overhead)
-		TimeET cur;
-		usleep(1); // at least 1 to avoid being a no-op
-		TimeET elapsed(cur.Age());
-		if(elapsed<mintime)
-			mintime=elapsed;
-	}
-	usleep(50000); //to hopefully clear out the scheduler for the duration of our test
-	TimeET minover(1.0); //should definitely be less than a second
-	for(unsigned int i=0; i<TRIALS; i++) {
-		//measure overhead
-		TimeET cur;
-		TimeET elapsed(cur.Age());
-		if(elapsed<minover)
-			minover=elapsed;
-	}
-	if(mintime<minover) { // something went wrong -- overhead is greater than total
-		mintime=0L;
-		cout << "usleep granularity couldn't be measured, default to 10ms" << endl;
-	} else {
-		//subtract overhead
-		mintime-=minover;
-		cout << "usleep granularity is " << mintime.Value()*1.0e6 << "us";
-		if(mintime<2L) {
-			mintime=2L;
-			cout << ", reset to 2ms";
-		}
-		cout << endl;
-	}
-	return static_cast<unsigned>(mintime.Value()*1.0e6);
-}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/sim/sim.h ./local/sim/sim.h
--- ../Tekkotsu_3.0/local/sim/sim.h	2006-10-03 19:11:37.000000000 -0400
+++ ./local/sim/sim.h	1969-12-31 19:00:00.000000000 -0500
@@ -1,91 +0,0 @@
-//-*-c++-*-
-#ifndef INCLUDED_sim_h_
-#define INCLUDED_sim_h_
-
-#include "Events/EventTranslator.h"
-#include "IPC/MessageQueue.h"
-#include "SharedGlobals.h"
-#include "IPC/SharedObject.h"
-#include "IPC/Thread.h"
-#include "Wireless/Wireless.h"
-#include "Shared/ProjectInterface.h"
-#include <vector>
-class SimConfig;
-
-class sim {
-public:
-	sim();
-	bool processCommandLine(int argc, const char* argv[]);
-	bool run();
-	~sim();
-	
-	typedef MessageQueue<50> EventQueue_t;
-	typedef MessageQueue<50> MotionCommandQueue_t;
-	typedef MessageQueue<50> SoundPlayQueue_t;
-	typedef MessageQueue<1> CameraQueue_t;
-	typedef MessageQueue<1> SensorQueue_t;
-	typedef MessageQueue<1> TimerWakeup_t;
-	typedef MessageQueue<1> MotionWakeup_t;
-	typedef MessageQueue<ProcessID::NumProcesses+1> StatusRequest_t;
-	typedef MessageQueue<1> MotionOutput_t;
-	
-	static SimConfig config;
-	static std::vector<std::string> assignments;
-	
-protected:
-	unsigned int measure_usleep_cost();
-	void wait_runlevel(SharedGlobals::runlevel_t level);
-	template<class T> void manage_process();
-	template<class T> bool fork_process();
-
-	static unsigned int sim_get_time() { return globals?globals->get_time():0; }
-	static float sim_getTimeScale() { return globals?globals->getTimeScale():0; }
-	
-	static void handle_signal(int sig);
-	static void handle_exit();
-
-	SharedObject<SemaphoreManager> mutexSemMgr;
-	SharedObject<SharedGlobals> glob;
-	SharedObject<ipc_setup_t> subj;
-	static bool original;
-	static const char * const usage;
-	pid_t child;
-};
-
-class WirelessThread : public Thread {
-public:
-	//! constructor
-	WirelessThread() : Thread() {}
-	//! destructor -- stop thread
-	virtual ~WirelessThread() {
-		if(isRunning()) {
-			stop();
-			join();
-		}
-	}
-	virtual unsigned int runloop() {
-		// initial setup done by wireless's own constructor
-		wireless->pollTest(NULL); // by passing NULL, we wait indefinitely, so no need to usleep in the Thread code
-		wireless->pollProcess();
-		wireless->pollSetup(); // reinitialize for next test
-		return 0; //no sleep time because pollTest blocks
-	}
-	virtual void stop() {
-		Thread::stop();
-		wireless->wakeup();
-	}
-};
-
-
-/*! @file
- * @brief 
- * @author ejt (Creator)
- *
- * $Author: ejt $
- * $Name: tekkotsu-3_0 $
- * $Revision: 1.11 $
- * $State: Exp $
- * $Date: 2006/10/03 23:11:37 $
- */
-
-#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Main.cc ./local/tekkotsu/Main.cc
--- ../Tekkotsu_3.0/local/tekkotsu/Main.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Main.cc	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,449 @@
+#include "Main.h"
+#include "SoundPlay.h"
+#include "Motion.h"
+#include "Simulator.h"
+#include "TimerExecThread.h"
+#include "local/LoadDataThread.h"
+#include "SimConfig.h"
+#include "MotionExecThread.h"
+
+#include "IPC/RegionRegistry.h"
+#include "IPC/MessageReceiver.h"
+#include "IPC/PollThread.h"
+#include "Motion/Kinematics.h"
+#include "Motion/PostureEngine.h"
+#include "Wireless/Wireless.h"
+#include "Shared/ProjectInterface.h"
+#include "Behaviors/BehaviorBase.h"
+#include "Events/DataEvent.h"
+#include "Events/EventRouter.h"
+#include "Shared/Config.h"
+#include "Shared/MarkScope.h"
+
+#include "Events/EventBase.h"
+#include "Events/LocomotionEvent.h"
+#include "Events/TextMsgEvent.h"
+#include "Events/VisionObjectEvent.h"
+
+using namespace std;
+
+Main::Main()
+	: Process(getID(),getClassName()),
+	sounds(ipc_setup->registerRegion(SoundPlay::getSoundPlayID(),sizeof(sim::SoundPlayQueue_t))),
+	motions(ipc_setup->registerRegion(Motion::getMotionCommandID(),sizeof(sim::MotionCommandQueue_t))),
+	events(ipc_setup->registerRegion(getEventsID(),sizeof(sim::EventQueue_t))),
+	cameraFrames(ipc_setup->registerRegion(Simulator::getCameraQueueID(),sizeof(sim::CameraQueue_t))),
+	sensorFrames(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
+	timerWakeup(ipc_setup->registerRegion(Simulator::getTimerWakeupID(),sizeof(sim::TimerWakeup_t))),
+	statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
+	motionmanager(ipc_setup->registerRegion(Motion::getMotionManagerID(),sizeof(MotionManager))),
+	soundmanager(ipc_setup->registerRegion(SoundPlay::getSoundManagerID(),sizeof(SoundManager))),
+	worldstatepool(ipc_setup->registerRegion(getWorldStatePoolID(),sizeof(WorldStatePool))),
+	motionProf(ipc_setup->registerRegion(Motion::getMotionProfilerID(),sizeof(motionProfiler_t))),
+	soundProf(ipc_setup->registerRegion(SoundPlay::getSoundProfilerID(),sizeof(soundProfiler_t))),
+	visrecv(NULL), sensrecv(NULL), evtrecv(NULL), timerrecv(NULL), statusrecv(NULL), timerExec(NULL),
+	visionRead(true), wireless_thread(), worldStateCache(), behaviorLock(*worldstatepool),
+	curimgregion(NULL), img(), lastVisionSN(-1U), lastSensorSN(-1U), lastSensorUpdateTime(0)
+{
+	new (&(*events)) sim::EventQueue_t;
+	new (&(*worldstatepool)) WorldStatePool;
+	state=NULL;
+	motman=&(*motionmanager);
+	sndman=&(*soundmanager);
+	::mainProfiler=new mainProfiler_t;
+	::motionProfiler=&(*motionProf);
+	::soundProfiler=&(*soundProf);
+
+	if(sim::config.multiprocess) {
+		//Setup wireless
+		ASSERT(wireless==NULL,"global wireless already initialized before Main?");
+		wireless = new Wireless();
+		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(Socket::FLUSH_BLOCKING);
+		sout->setTextForward();
+		serr->setForward(sout);
+		
+		//Setup Kinematics
+		ASSERT(kine==NULL,"global kine already initialized before Main?");
+		kine=new Kinematics();
+	}
+	wireless->setCallbackLock(behaviorLock);
+
+	//EventRouter and Config are set up for all processes by main() before fork
+}
+
+Main::~Main() {
+	if(sim::config.multiprocess) {
+		delete wireless;
+		wireless=NULL;
+		delete kine;
+		kine=NULL;
+	}
+}
+
+
+void Main::DoStart() {
+try {
+	Process::DoStart();
+	//These are constructed by other processes, so need to wait
+	//until the construction runlevel is complete
+	sndman->InitAccess(*sounds);
+	motman->InitAccess(*motions,behaviorLock);
+
+	wireless->listen(sout, config->main.console_port);
+	wireless->listen(serr, config->main.stderr_port);
+	wireless_thread.start();
+	statusrecv=new MessageReceiver(*statusRequest,statusReport);
+
+	if(globals->waitForSensors)
+		erouter->addListener(this,EventBase::sensorEGID);
+	evtrecv=new MessageReceiver(*events,gotEvent,false);
+	visrecv=new MessageReceiver(*cameraFrames,gotCamera,false);
+	sensrecv=new MessageReceiver(*sensorFrames,gotSensors,false);
+	timerrecv=new MessageReceiver(*timerWakeup,gotTimer,false);
+	timerExec=new TimerExecThread(behaviorLock,false);
+	
+} catch(const std::exception& ex) {
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStart",&ex))
+		throw;
+} catch(...) {
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStart",NULL))
+		throw;
+}
+}
+
+void Main::run() {
+try {
+	evtrecv->start();
+	if(globals->waitForSensors) {
+		sensrecv->start();
+		globals->waitSensors();
+	}
+
+	// might have shutdown triggered while waiting
+	// (perhaps device isn't available, user's killing the process...)
+	if(globals->isShutdown())
+		return; // skip running altogether
+	
+	{
+		MarkScope bl(behaviorLock);
+		ProjectInterface::startupBehavior().DoStart();
+		globals->setNextTimer(erouter->getNextTimer());
+	}
+	
+	if(!globals->waitForSensors)
+		sensrecv->start();
+	visrecv->start();
+	timerrecv->start();
+	timerExec->reset();
+	
+	// this is a bit of a hack, but once we're done launching, display the prompt:
+	cout << sim::config.cmdPrompt << flush;
+	
+	Process::run();
+
+	sensrecv->finish();
+	visrecv->finish();
+	evtrecv->finish();
+	timerrecv->finish();
+	
+	{
+		MarkScope bl(behaviorLock);
+		ProjectInterface::startupBehavior().DoStop();
+		globals->setNextTimer(erouter->getNextTimer());
+	}
+	timerExec->reset();
+
+} catch(const std::exception& ex) {
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main 'run' runlevel (startupBehavior initialization and startup)",&ex))
+		throw;
+} catch(...) {
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main 'run' runlevel (startupBehavior initialization and startup)",NULL))
+		throw;
+}
+}
+
+void Main::DoStop() {
+try {
+
+	delete sensrecv;
+	sensrecv=NULL;
+	delete visrecv;
+	visrecv=NULL;
+	delete evtrecv;
+	evtrecv=NULL;
+	delete timerrecv;
+	timerrecv=NULL;
+	delete statusrecv;
+	statusrecv=NULL;
+	
+	motman->RemoveAccess();
+	
+	if(curimgregion!=NULL)
+		curimgregion->RemoveReference();
+
+	wireless_thread.stop();
+	wireless_thread.join();
+	wireless->setDaemon(sout,false);
+	wireless->close(sout);
+	sout=NULL;
+	wireless->setDaemon(serr,false);
+	wireless->close(serr);
+	serr=NULL;
+	
+	Process::DoStop();
+
+} catch(const std::exception& ex) {
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStop",&ex))
+		throw;
+} catch(...) {
+	if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during Main DoStop",NULL))
+		throw;
+}
+}
+
+void Main::processEvent(const EventBase&) {
+	erouter->removeListener(this);
+	for(unsigned int i=0; i<NumOutputs; i++)
+		motman->setOutput(NULL,i,state->outputs[i]);
+	globals->signalHaveSensors();
+}
+
+bool Main::gotCamera(RCRegion* msg) {
+	if(msg==NULL)
+		return true;
+	Main * main=dynamic_cast<Main*>(Process::getCurrent());
+	ASSERTRETVAL(main!=NULL,"gotCamera, but not within Main process!",true);
+	MarkScope bl(main->behaviorLock);
+	PROFSECTION("GotImage()",*mainProfiler);
+
+	try {
+		BufferedImageGenerator::ImageSource& img=main->img;
+		
+		unsigned int verbose;
+		unsigned int sn;
+		string file;
+		unsigned int payload;
+		int l;
+		char* buf=LoadDataThread::deserializeHeader(msg->Base(),msg->Size(),&verbose,&sn,&file,NULL,&payload);
+		unsigned int remain=payload;
+		if(verbose>=1 && sn-main->lastVisionSN!=1)
+			cout << "Main dropped " << (sn-main->lastVisionSN-1) << " camera frame(s)" << endl;
+		main->lastVisionSN=sn;
+		if(verbose>=3 && remain==0)
+			cout << "Main received image heartbeat at " << get_time() << endl;
+		else if(verbose>=2 && remain!=0)
+			cout << "Main received image data \"" << file << "\" at " << get_time() << endl;
+		
+		img.frameIndex=sn;
+		if(remain==0) {
+			if(img.width==0 || img.height==0 || img.img==NULL)
+				return true; // can't do the heartbeat, don't have an initial image to replicate
+		} else {
+			LoadSave::decodeIncT(l,buf,remain);
+			LoadSave::decodeIncT(img.width,buf,remain);
+			LoadSave::decodeIncT(img.height,buf,remain);
+			LoadSave::decodeIncT(img.channels,buf,remain);
+			if(l!=0) {
+				img.layer = (l<0)?ProjectInterface::defRawCameraGenerator->getNumLayers()+l:l-1;
+			} else {
+				// using "automatic" mode, pick the layer closest to resolution of provided image
+				// assumes each layer doubles in size, with smallest layer at 0
+				float fullRes=sqrt(CameraResolutionX*CameraResolutionY); // from RobotInfo
+				float givenRes=sqrt(img.width*img.height);
+				if(givenRes==0) {
+					cerr << "Main received empty image!" << endl;
+					return true;
+				} else {
+					float ratio=log2f(givenRes/fullRes);
+					int layerOff=static_cast<int>(rintf(ratio));
+					int tgtLayer=static_cast<int>(ProjectInterface::fullLayer)+layerOff;
+					if(tgtLayer<0)
+						img.layer=0;
+					else if(ProjectInterface::defRawCameraGenerator!=NULL && static_cast<unsigned int>(tgtLayer)>=ProjectInterface::defRawCameraGenerator->getNumLayers())
+						img.layer=ProjectInterface::defRawCameraGenerator->getNumLayers()-1;
+					else
+						img.layer=tgtLayer;
+					if(static_cast<unsigned int>(tgtLayer)!=img.layer)
+						cerr << "Image dimensions of " << img.width << "x" << img.height << " are well beyond the available resolution layers (full is " << CameraResolutionX << "x" << CameraResolutionY << ")" << endl;
+				}
+			}
+			img.img=reinterpret_cast<unsigned char*>(buf);
+			msg->AddReference();
+			if(main->curimgregion!=NULL)
+				main->curimgregion->RemoveReference();
+			main->curimgregion=msg;
+		}
+		DataEvent<BufferedImageGenerator::ImageSource> dev(img,EventBase::visOFbkEGID,0,EventBase::activateETID);
+		erouter->postEvent(dev);
+		dev.setTypeID(EventBase::statusETID);
+		erouter->postEvent(dev);
+		dev.setTypeID(EventBase::deactivateETID);
+		erouter->postEvent(dev);
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during camera frame processing",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during camera frame processing",NULL))
+			throw;
+	}
+	try {
+		erouter->processTimers();
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
+			throw;
+	}
+	if(globals->setNextTimer(erouter->getNextTimer()))
+		main->timerExec->reset();
+	return true;
+}
+
+bool Main::gotSensors(RCRegion* msg) {
+	Main * main=dynamic_cast<Main*>(Process::getCurrent());
+	ASSERTRETVAL(main!=NULL,"gotSensors, but not within Main process!",true);
+
+	PROFSECTION("GotSensorFrame()",*mainProfiler);
+	MarkScope l(main->behaviorLock);
+
+	string exceptionPhase="sensor";
+	try {
+		unsigned int orgSN=main->lastSensorSN;
+		WorldStatePool::UpdateInfo * info=main->worldstatepool->isUnread(*msg,globals->motion.frameNumber,main->lastSensorSN,false,globals->motion.override);
+		int dif=0;
+		if(info!=NULL) {
+			bool generateFeedback=(globals->motion.hasUnprovidedOutput() || globals->motion.override) && globals->motion.feedbackDelay>=0;
+			EntryPoint::WorldStateWrite wsw(info->frameNumber);
+			MarkScope lw(main->behaviorLock, wsw);
+			if(state!=NULL && wsw.frame==globals->motion.frameNumber) {
+				// ^-- make sure a newer one didn't come in while we were waiting for the lock
+				// (if one did, we'll report the accumulated drops next time we get one we don't drop)
+				if(main->worldstatepool->read(*info,wsw,generateFeedback,globals->motion.zeroPIDFeedback,NULL)) {
+					if(wsw.frame-main->lastSensorSN!=1 && info->verbose>=1)
+						cout << ProcessID::getIDStr() << " dropped " << (wsw.frame-main->lastSensorSN-1) << " sensor frame(s)" << endl;
+					main->lastSensorSN=wsw.frame;
+				}
+				if(wsw.getComplete()) {
+					dif=state->lastSensorUpdateTime - main->lastSensorUpdateTime;
+					ASSERT(dif>=0,"sensor update time is negative? " << dif);
+					main->lastSensorUpdateTime=state->lastSensorUpdateTime;
+					erouter->postEvent(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,dif,"SensorSrcID::UpdatedSID",1);
+					exceptionPhase="timer";
+					erouter->processTimers();
+				}
+			}
+		} else if(orgSN!=main->lastSensorSN) {
+			// received update after sensor frame was already parsed by other process
+			l.reset(); //update state
+			dif=state->lastSensorUpdateTime - main->lastSensorUpdateTime;
+			ASSERT(dif>=0,"sensor update time is negative? " << dif);
+			main->lastSensorUpdateTime=state->lastSensorUpdateTime;
+			erouter->postEvent(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,dif,"SensorSrcID::UpdatedSID",1);
+			exceptionPhase="timer";
+			erouter->processTimers();
+		}
+		if(dif==0) {
+			exceptionPhase="timer";
+			erouter->processTimers();
+		}
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,("Occurred during "+exceptionPhase+" processing").c_str(),&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,("Occurred during "+exceptionPhase+" processing").c_str(),NULL))
+			throw;
+	}
+	if(globals->setNextTimer(erouter->getNextTimer()))
+		main->timerExec->reset();
+	return true;
+}
+
+bool Main::gotEvent(RCRegion* msg) {
+	if(msg==NULL)
+		return true;
+	Main * main=dynamic_cast<Main*>(Process::getCurrent());
+	ASSERTRETVAL(main!=NULL,"gotEvent, but not within Main process!",true);
+	MarkScope l(main->behaviorLock);
+	EventBase* evt=NULL;
+	try {
+		evt=EventTranslator::decodeEvent(msg->Base(),msg->Size());
+		if(evt==NULL) {
+			cerr << "ERROR: Main::gotEvent() failed to decode message" << endl;
+			return true;
+		}
+		if(evt->getGeneratorID()==EventBase::sensorEGID)
+			main->lastSensorUpdateTime=evt->getTimeStamp();
+		erouter->postEvent(*evt);
+	} catch(const std::exception& ex) {
+		std::string emsg("Occurred during inter-process event processing");
+		if(evt!=NULL)
+			emsg+=": "+evt->getName();
+		delete evt;
+		evt=NULL;
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,emsg.c_str(),&ex))
+			throw;
+	} catch(...) {
+		std::string emsg("Occurred during inter-process event processing");
+		if(evt!=NULL)
+			emsg+=": "+evt->getName();
+		delete evt;
+		evt=NULL;
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,emsg.c_str(),NULL))
+			throw;
+	}
+	delete evt;
+	evt=NULL;
+	try {
+		erouter->processTimers();
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
+			throw;
+	}
+	if(globals->setNextTimer(erouter->getNextTimer()))
+		main->timerExec->reset();
+	return true;
+}
+
+bool Main::gotTimer(RCRegion* /*msg*/) {
+	Main * main=dynamic_cast<Main*>(Process::getCurrent());
+	ASSERTRETVAL(main!=NULL,"gotTimer, but not within Main process!",true);
+
+	ASSERTRETVAL(main->timerExec!=NULL,"timerExec thread is NULL when timer wakeup received",true);
+	main->timerExec->reset();
+	
+	if(globals->timeScale<=0) {
+		MarkScope bl(main->behaviorLock);
+		try {
+			erouter->processTimers();
+		} catch(const std::exception& ex) {
+			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
+				throw;
+		} catch(...) {
+			if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
+				throw;
+		}
+		globals->setNextTimer(erouter->getNextTimer());
+		// don't need to reset timerExec (again) because we're only here if speed<=0, in which case timerExec isn't running	main->timerExec->reset();
+	}
+	return true;
+}
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.4 $
+ * $State: Exp $
+ * $Date: 2007/11/11 23:57:30 $
+ */
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Main.h ./local/tekkotsu/Main.h
--- ../Tekkotsu_3.0/local/tekkotsu/Main.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Main.h	2007-11-09 14:01:17.000000000 -0500
@@ -0,0 +1,88 @@
+//-*-c++-*-
+#ifndef INCLUDED_Main_h_
+#define INCLUDED_Main_h_
+
+#include "Process.h"
+#include "sim.h"
+#include "IPC/SharedObject.h"
+#include "SharedGlobals.h"
+#include "Motion/MotionManager.h"
+#include "Sound/SoundManager.h"
+#include "Shared/WorldStatePool.h"
+#include "local/EntryPoint.h"
+#include "Vision/BufferedImageGenerator.h"
+#include "Shared/Profiler.h"
+#include "Events/EventListener.h"
+
+class Main : public Process, public virtual EventListener {
+public:
+	//! constructor
+	Main();
+	//! destructor
+	~Main();
+
+	virtual void DoStart();
+	virtual void run();
+	virtual void DoStop();
+	
+	//! listens for a sensor update event, then calls SharedGlobals::signalHaveSensors()
+	virtual void processEvent(const EventBase& event);
+
+	static const char* getClassName() { return "Main"; }
+	static ProcessID::ProcessID_t getID() { return ProcessID::MainProcess; }
+	
+	static const char * getEventsID() { return "MainEvents"; }
+	static const char * getWorldStatePoolID() { return "WorldStatePool"; }
+	
+protected:
+	SharedObject<sim::SoundPlayQueue_t> sounds;
+	SharedObject<sim::MotionCommandQueue_t> motions;
+	SharedObject<sim::EventQueue_t> events;
+	SharedObject<sim::CameraQueue_t> cameraFrames;
+	SharedObject<sim::SensorQueue_t> sensorFrames;
+	SharedObject<sim::TimerWakeup_t> timerWakeup;
+	SharedObject<sim::StatusRequest_t> statusRequest;
+	SharedObject<MotionManager> motionmanager;
+	SharedObject<SoundManager> soundmanager;
+	SharedObject<WorldStatePool> worldstatepool;
+	SharedObject<motionProfiler_t> motionProf;
+	SharedObject<soundProfiler_t> soundProf;
+	
+	class MessageReceiver * visrecv;
+	class MessageReceiver * sensrecv;
+	class MessageReceiver * evtrecv;
+	class MessageReceiver * timerrecv;
+	class MessageReceiver * statusrecv;
+	class TimerExecThread * timerExec;
+	bool visionRead;
+	WirelessThread wireless_thread;
+	WorldState worldStateCache; //!< used for temporary storage when parsing sensor frames, allocation here avoids rather costly constructor call on every sensor frame
+	EntryPoint behaviorLock;
+
+	static bool gotCamera(RCRegion* msg);
+	static bool gotSensors(RCRegion* msg);
+	static bool gotEvent(RCRegion* msg);
+	static bool gotTimer(RCRegion* msg);
+	RCRegion * curimgregion;
+	BufferedImageGenerator::ImageSource img; //!< root data source for vision stream, references data in #curimgregion
+	unsigned int lastVisionSN; //!< serial number of last camera frame, just so we can give warning message when we drop (if verbose is set)
+	unsigned int lastSensorSN; //!< serial number of last sensor frame, just so we can give warning message when we drop (if verbose is set)
+	unsigned int lastSensorUpdateTime; //!< time that last sensor update was posted
+	
+private:
+	Main(const Main&); //!< don't call (copy constructor)
+	Main& operator=(const Main&); //!< don't call (assignment operator)
+};
+
+/*! @file
+ * @brief Defines Main, which DESCRIPTION
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/11/09 19:01:17 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Motion.cc ./local/tekkotsu/Motion.cc
--- ../Tekkotsu_3.0/local/tekkotsu/Motion.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Motion.cc	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,255 @@
+#include "Motion.h"
+#include "Main.h"
+#include "SoundPlay.h"
+#include "Simulator.h"
+#include "SimConfig.h"
+#include "Shared/Config.h"
+#include "MotionExecThread.h"
+
+#include "IPC/RegionRegistry.h"
+#include "IPC/MessageReceiver.h"
+#include "Motion/Kinematics.h"
+#include "Wireless/Wireless.h"
+#include "Events/EventRouter.h"
+#include "Shared/MarkScope.h"
+
+#include "local/MotionHooks/IPCMotionHook.h"
+
+using namespace std;
+
+Motion::Motion()
+	: Process(getID(),getClassName()),
+	sounds(ipc_setup->registerRegion(SoundPlay::getSoundPlayID(),sizeof(sim::SoundPlayQueue_t))),
+	motions(ipc_setup->registerRegion(getMotionCommandID(),sizeof(sim::MotionCommandQueue_t))),
+	motionout(ipc_setup->registerRegion(getMotionOutputID(),sizeof(sim::MotionOutput_t))),
+	events(ipc_setup->registerRegion(Main::getEventsID(),sizeof(sim::EventQueue_t))),
+	sensorFrames(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
+	statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
+	motionmanager(ipc_setup->registerRegion(getMotionManagerID(),sizeof(MotionManager))),
+	soundmanager(ipc_setup->registerRegion(SoundPlay::getSoundManagerID(),sizeof(SoundManager))),
+	worldstatepool(ipc_setup->registerRegion(Main::getWorldStatePoolID(),sizeof(WorldStatePool))),
+	motionWakeup(ipc_setup->registerRegion(Simulator::getMotionWakeupID(),sizeof(sim::MotionWakeup_t))),
+	motionProf(ipc_setup->registerRegion(getMotionProfilerID(),sizeof(motionProfiler_t))),
+	etrans(NULL), sensrecv(NULL), statusrecv(NULL), wakeuprecv(NULL), motionExec(NULL), motionfwd(NULL),
+	wireless_thread(), motionLock(*worldstatepool), lastSensorSN(-1U)
+{
+	new (&(*motions)) sim::MotionCommandQueue_t;
+	new (&(*motionout)) sim::MotionOutput_t;
+	new (&(*motionmanager)) MotionManager;
+	new (&(*motionProf)) motionProfiler_t;
+	motman=&(*motionmanager);
+	motman->InitAccess(*motions,motionLock);
+	sndman=&(*soundmanager);
+	state=NULL;
+	::motionProfiler=&(*motionProf);
+	
+	if(sim::config.multiprocess) {
+		//Setup wireless
+		ASSERT(wireless==NULL,"global wireless already initialized before Motion?");
+		wireless = new Wireless();
+		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(Socket::FLUSH_BLOCKING);
+		sout->setTextForward();
+		serr->setForward(sout);
+
+		//Setup Kinematics
+		ASSERT(kine==NULL,"global kine already initialized before Motion?");
+		kine=new Kinematics();
+	}
+
+	//EventRouter and Config are set up for all processes by main() before fork
+}
+
+Motion::~Motion() {
+	MotionManager::setTranslator(NULL);
+	delete etrans;
+	etrans=NULL;
+	if(sim::config.multiprocess) {
+		delete wireless;
+		wireless=NULL;
+		delete kine;
+		kine=NULL;
+	}
+}
+
+void Motion::DoStart() {
+	Process::DoStart();
+	//These are constructed by other processes, so need to wait
+	//until the construction runlevel is complete before we access them
+	sndman->InitAccess(*sounds);
+	if(!sim::config.multiprocess) {
+		// don't use our own etrans here, because erouter will delete it for us, don't want a double-delete in our destructor...
+		EventTranslator * forwardTrans = new IPCEventTranslator(*events);
+		forwardTrans->setTrapEventValue(true);
+		erouter->setForwardingAgent(getID(),forwardTrans);
+		MotionManager::setTranslator(forwardTrans);
+	} else {
+		etrans=new IPCEventTranslator(*events);
+		MotionManager::setTranslator(etrans);
+		
+		// Set up Event Translator to trap and send events to main process
+		//send everything over except erouter events
+		for(unsigned int i=0; i<EventBase::numEGIDs; i++)
+			if(i!=EventBase::erouterEGID)
+				erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
+		
+		wireless->listen(sout, config->motion.console_port);
+		wireless->listen(serr, config->motion.stderr_port);
+		wireless_thread.start();
+	}
+	
+	sensrecv=new MessageReceiver(*sensorFrames,gotSensors);
+	statusrecv=new MessageReceiver(*statusRequest,statusReport);
+	wakeuprecv=new MessageReceiver(*motionWakeup,gotWakeup,false);
+
+	motionExec=new MotionExecThread(motionLock);
+	if(sim::config.multiprocess) {
+		Simulator::registerMotionHook(*(motionfwd=new IPCMotionHook(*motionout)));
+		Simulator::setMotionStarting();
+		if(globals->timeScale>0)
+			Simulator::setMotionEnteringRealtime();
+	}
+}
+
+
+void Motion::run() {
+	if(globals->waitForSensors)
+		globals->waitSensors();
+	
+	// might have shutdown triggered while waiting
+	// (perhaps device isn't available, user's killing the process...)
+	if(globals->isShutdown())
+		return; // skip running altogether
+	
+	motionExec->reset(); //starts the thread if appropriate
+	wakeuprecv->start();
+	Process::run();
+	wakeuprecv->stop();
+}
+
+void Motion::DoStop() {
+	Simulator::deregisterMotionHook(*motionfwd);
+	delete motionfwd;
+	
+	wakeuprecv->finish();
+	statusrecv->finish();
+
+	delete motionExec;
+	motionExec=NULL;
+	delete wakeuprecv;
+	wakeuprecv=NULL;
+	delete statusrecv;
+	statusrecv=NULL;
+	
+	sensrecv->finish();
+	delete sensrecv;
+	sensrecv=NULL;
+	
+	if(sim::config.multiprocess) {
+		if(globals->timeScale>0)
+			Simulator::setMotionLeavingRealtime(false);
+		Simulator::setMotionStopping();
+		
+		erouter->removeTrapper(etrans);
+		delete etrans;
+		etrans=NULL;
+		
+		wireless_thread.stop();
+		wireless_thread.join();
+		wireless->setDaemon(sout,false);
+		wireless->close(sout);
+		sout=NULL;
+		wireless->setDaemon(serr,false);
+		wireless->close(serr);
+		serr=NULL;
+	}
+	motman->RemoveAccess();
+	
+	Process::DoStop();
+}
+
+bool Motion::gotWakeup(RCRegion* /*msg*/) {
+	Motion * motion=dynamic_cast<Motion*>(Process::getCurrent());
+	ASSERTRETVAL(motion!=NULL,"gotWakeup, but not within motion process!",true);
+	ASSERTRETVAL(motion->motionExec!=NULL,"motionExec thread is NULL when motion wakeup received",true);
+	
+	MarkScope l(motion->motionLock);
+	if(sim::config.multiprocess) {
+		if(globals->timeScale<=0 && motion->motionExec->isStarted())
+			Simulator::setMotionLeavingRealtime(globals->timeScale<0);
+		else if(globals->timeScale>0 && !motion->motionExec->isStarted())
+			Simulator::setMotionEnteringRealtime();
+	}
+	if(globals->timeScale<=0 && get_time()>=globals->getNextMotion())
+		motion->motionExec->poll();
+	motion->motionExec->reset(); //reset will set globals->getNextMotion(), so have to do this after the poll itself
+	return true;
+}
+
+bool Motion::gotSensors(RCRegion* msg) {
+	Motion * motion=dynamic_cast<Motion*>(Process::getCurrent());
+	ASSERTRETVAL(motion!=NULL,"gotSensors, but not within Motion process!",true);
+	
+	PROFSECTION("GotSensorFrame()",*motionProfiler);
+	MarkScope l(motion->motionLock);
+	
+	EntryPoint::WorldStateWrite wsw(-1U);
+	try {
+		WorldStatePool::UpdateInfo * info=motion->worldstatepool->isUnread(*msg,globals->motion.frameNumber,motion->lastSensorSN,globals->motion.feedbackDelay>=0,globals->motion.override);
+		int dif=0;
+		if(info!=NULL) {
+			bool generateFeedback=(globals->motion.hasUnprovidedOutput() || globals->motion.override) && globals->motion.feedbackDelay>=0;
+			const PostureEngine* pose = generateFeedback ? &motion->motionExec->getPostureFeedback() : NULL;
+			wsw.frame=info->frameNumber;
+			MarkScope lw(motion->motionLock, wsw);
+			if(state==NULL || wsw.frame<globals->motion.frameNumber) {
+				//a newer one came in while we were waiting for the lock (we'll report the accumulated drops next time we get one we don't drop)
+				return true;
+			}
+			ASSERT((wsw.getStatus()&WorldStatePool::FEEDBACK_APPLIED)==0,"motion feedback already applied?");
+			bool completedPartial=!wsw.getComplete() && (wsw.getStatus()&WorldStatePool::SENSORS_APPLIED)!=0;
+			if(generateFeedback && info->verbose>=2)
+				cout << "Motion filling in sensor feedback" << endl;
+			ASSERT(!completedPartial || generateFeedback,"partially complete, yet no feedback?");
+			if(motion->worldstatepool->read(*info,wsw,generateFeedback,globals->motion.zeroPIDFeedback,pose)) {
+				if(wsw.frame-motion->lastSensorSN!=1 && info->verbose>=1)
+					cout << ProcessID::getIDStr() << " dropped " << (wsw.frame-motion->lastSensorSN-1) << " sensor frame(s)" << endl;
+				motion->lastSensorSN=wsw.frame;
+			}
+			if(completedPartial && wsw.getComplete()) { // was partial before, now completed as well
+				dif=state->lastSensorUpdateTime - wsw.src->lastSensorUpdateTime;
+				ASSERT(dif>=0,"sensor update time is negative? " << dif << ' ' << state << ' ' << wsw.src);
+			}
+		}
+		if(dif>0) {
+			// need to notify main that the sensor update it started is now complete
+			// do it outside the write lock so if main gets this instantly it can use the new data
+			// some sleight of hand here -- we've previously registered an IPCEventTranslator as an event trapper.  By posting here, the event will be sent to the Main process
+			erouter->postEvent(EventBase::sensorEGID,SensorSrcID::UpdatedSID,EventBase::statusETID,dif,"SensorSrcID::UpdatedSID",1);
+		}
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during sensor processing",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during sensor processing",NULL))
+			throw;
+	}
+	
+	return true;
+}
+	
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.3 $
+ * $State: Exp $
+ * $Date: 2007/11/11 23:57:30 $
+ */
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Motion.h ./local/tekkotsu/Motion.h
--- ../Tekkotsu_3.0/local/tekkotsu/Motion.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Motion.h	2007-06-14 11:37:41.000000000 -0400
@@ -0,0 +1,79 @@
+//-*-c++-*-
+#ifndef INCLUDED_Motion_h_
+#define INCLUDED_Motion_h_
+
+#include "Process.h"
+#include "sim.h"
+#include "IPC/ProcessID.h"
+#include "IPC/SharedObject.h"
+#include "SharedGlobals.h"
+#include "Motion/MotionManager.h"
+#include "Sound/SoundManager.h"
+#include "Shared/WorldStatePool.h"
+#include "Shared/Profiler.h"
+#include "local/EntryPoint.h"
+#include <list>
+
+class Motion : public Process {
+public:
+	//! constructor
+	Motion();
+	//! destructor
+	~Motion();
+
+	virtual void DoStart();
+	virtual void run();
+	virtual void DoStop();
+
+	static const char * getClassName() { return "Motion"; }
+	static ProcessID::ProcessID_t getID() { return ProcessID::MotionProcess; }
+	
+	static const char * getMotionCommandID() { return "MotionCommands"; }
+	static const char * getMotionOutputID() { return "MotionOutput"; }
+	static const char * getMotionManagerID() { return "MotionManager"; }
+	static const char * getMotionProfilerID() { return "MotionProfiler"; }
+
+protected:
+	SharedObject<sim::SoundPlayQueue_t> sounds;
+	SharedObject<sim::MotionCommandQueue_t> motions;
+	SharedObject<sim::MotionOutput_t> motionout;
+	SharedObject<sim::EventQueue_t> events;
+	SharedObject<sim::SensorQueue_t> sensorFrames;
+	SharedObject<sim::StatusRequest_t> statusRequest;
+	SharedObject<MotionManager> motionmanager;
+	SharedObject<SoundManager> soundmanager;
+	SharedObject<WorldStatePool> worldstatepool;
+	SharedObject<sim::MotionWakeup_t> motionWakeup;
+	SharedObject<motionProfiler_t> motionProf;
+	
+	IPCEventTranslator * etrans;
+	class MessageReceiver * sensrecv;
+	class MessageReceiver * statusrecv;
+	class MessageReceiver * wakeuprecv;
+	class MotionExecThread * motionExec;
+	class IPCMotionHook * motionfwd;
+	WirelessThread wireless_thread;
+
+	EntryPoint motionLock;
+	
+	static bool gotSensors(RCRegion* msg);
+	static bool gotWakeup(RCRegion* msg);
+	unsigned int lastSensorSN;
+	
+private:
+	Motion(const Motion&); //!< don't call (copy constructor)
+	Motion& operator=(const Motion&); //!< don't call (assignment operator)
+};
+
+/*! @file
+ * @brief Defines Motion, which DESCRIPTION
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/14 15:37:41 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/MotionExecThread.cc ./local/tekkotsu/MotionExecThread.cc
--- ../Tekkotsu_3.0/local/tekkotsu/MotionExecThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/MotionExecThread.cc	2007-10-12 12:55:05.000000000 -0400
@@ -0,0 +1,192 @@
+#include "MotionExecThread.h"
+#include "Simulator.h"
+#include "SharedGlobals.h"
+#include "Shared/ProjectInterface.h"
+#include "Shared/WorldState.h"
+#include "Shared/MarkScope.h"
+#include "Motion/MotionManager.h"
+#include "IPC/MessageQueue.h"
+#include "Shared/debuget.h"
+#include "Shared/Profiler.h"
+#include "local/EntryPoint.h"
+
+using namespace std; 
+
+void MotionExecThread::reset() {
+	globals->setNextMotion(getNextMotion());
+	if(globals->timeScale<=0 && isStarted())
+		stop();
+	else if(globals->timeScale>0 && !isStarted())
+		start();
+	else if(isStarted()) {
+		interrupt();
+	}
+}
+
+/*void MotionExecThread::start() {
+	lastPoll=-1U;
+	launching=initialPoll=true;
+	Thread::start(); //skipping PollThread::start() because we don't want to reset startTime
+}*/
+
+bool MotionExecThread::poll() {
+	MarkScope l(motionLock);
+	PROFSECTION("ReadySendJoints()",*motionProfiler);
+	//this is OK: (can happen if the thread gets behind and the last one finished late, still want to do the current one, which appears to come early)
+	//ASSERTRETVAL(get_time()>=globals->getNextMotion()-1,"MotionExecThread::poll() early (time="<<get_time()<< " vs. nextMotion=" <<globals->getNextMotion()<<")",true);
+	if(get_time()<globals->getNextMotion())
+		return true;
+	try {
+		if(globals->motion.verbose>=3)
+			cout << "Motion processing at " << get_time() << endl;
+		const unsigned int bufTime=NumFrames*FrameTime;
+		unsigned int tgtSize=(globals->motion.feedbackDelay>0 ? (globals->motion.feedbackDelay)/bufTime+1 : 1);
+		if(motionBuffers.size()<tgtSize) {
+			motionBuffers.insert(motionBufferPos,new float[NumFrames][NumOutputs]);
+			motionBufferPos--;
+		} else {
+			while(motionBuffers.size()>tgtSize) {
+				std::list<float(*)[NumOutputs]>::iterator tmp=motionBufferPos++;
+				delete [] *tmp;
+				motionBuffers.erase(tmp);
+				if(motionBufferPos==motionBuffers.end())
+					motionBufferPos=motionBuffers.begin();
+			}
+		}
+		if(lastPoll!=-1U && motionBuffers.size()>1) {
+			std::list<float(*)[NumOutputs]>::iterator prev=motionBufferPos;
+			if(prev==motionBuffers.begin())
+				prev=motionBuffers.end();
+			prev--;
+			unsigned int cnt=motionBuffers.size()-1;
+			while(get_time()>=lastPoll+bufTime*2) {
+				lastPoll+=bufTime;
+				if(globals->motion.verbose>=2)
+					cout << "Dropped motion frame in poll() (late call)" << endl;
+				if(cnt==0)
+					continue; //we've overwritten all of the buffer, no need wrap through it again
+				memcpy(*motionBufferPos,*prev,sizeof(float[NumFrames][NumOutputs]));
+				prev=motionBufferPos;
+				if(++motionBufferPos==motionBuffers.end())
+					motionBufferPos=motionBuffers.begin();
+				cnt--;
+			}
+		}
+		motman->getOutputs(*motionBufferPos);
+		Simulator::updateMotion(*motionBufferPos);
+		if(++motionBufferPos==motionBuffers.end())
+			motionBufferPos=motionBuffers.begin();
+		{
+			EntryPoint::WorldStateWrite wsw(globals->motion.frameNumber==-1U?0:globals->motion.frameNumber);
+			MarkScope lw(motionLock,wsw);
+			if(state==NULL) {
+				// This should not be possible -- we requested the most recent frame, it should be available
+				cerr << "WARNING: Motion received NULL state for PID update on frame " << wsw.frame << " (now " << globals->motion.frameNumber << ")" << endl;
+				//just in case, try again one time
+				lw.getResource().releaseResource(wsw);
+				wsw.frame=globals->motion.frameNumber;
+				lw.getResource().useResource(wsw);
+			}
+			if(state==NULL) {
+				cerr << "WARNING: Motion PID update retry failed, falling back to previous WorldState (tried " << wsw.frame << ", now " << globals->motion.frameNumber << ")" << endl;
+				state=wsw.src;
+			}	
+			if(state==NULL)
+				cerr << "ERROR: Fallback failed, Motion unable to update PID values for frame " << wsw.frame << endl;
+			else {
+				if(!wsw.getComplete())
+					state=wsw.src;
+				motman->updatePIDs();
+			}
+		}
+		globals->setNextMotion(getNextMotion());
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionManager processing",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during MotionManager processing",NULL))
+			throw;
+	}
+	lastPoll=get_time();
+	return true;
+}
+
+bool MotionExecThread::launched() {
+	if(globals->timeScale<=0)
+		return false;
+	startTime.Set();
+	globals->setNextMotion(getNextMotion());
+	//reset startTime to last motion time
+	startTime-=(get_time()-(getNextMotion()-FrameTime*NumFrames))/globals->timeScale/1000;
+	interrupted();
+	//delay=(getNextMotion()>get_time()) ? (getNextMotion()-get_time())/globals->timeScale/1000 : 0;
+	return PollThread::launched();
+}
+
+/*void MotionExecThread::cancelled() {
+	bool isFullSpeed=(globals->timeScale<0);
+}*/
+
+void MotionExecThread::interrupted() {
+	period=FrameTime*NumFrames/globals->timeScale/1000;
+	delay=(globals->getNextMotion()-get_time())/globals->timeScale/1000+startTime.Age();
+	//cout << "interrupt " << get_time() << ' ' << globals->getNextMotion() << ' ' << startTime.Age() << ' ' << delay << ' ' << period << ' ' << isStarted() << ' ' << globals->timeScale << endl;
+}
+
+const PostureEngine& MotionExecThread::getPostureFeedback() {
+	if(globals->motion.feedbackDelay<0)
+		return curPose;
+	
+	const unsigned int bufTime=NumFrames*FrameTime;
+	MarkScope l(motionLock);
+	if(lastPoll!=-1U && motionBuffers.size()>1) {
+		std::list<float(*)[NumOutputs]>::iterator prev=motionBufferPos;
+		if(prev==motionBuffers.begin())
+			prev=motionBuffers.end();
+		prev--;
+		unsigned int cnt=motionBuffers.size()-1;
+		while(get_time()>=lastPoll+bufTime*2) {
+			lastPoll+=bufTime;
+			cout << "Dropped motion frame in getPostureFeedback()" << endl;
+			if(cnt==0)
+				continue; //we've overwritten all of the buffer, no need wrap through it again
+			memcpy(*motionBufferPos,*prev,sizeof(float[NumFrames][NumOutputs]));
+			prev=motionBufferPos;
+			if(++motionBufferPos==motionBuffers.end())
+				motionBufferPos=motionBuffers.begin();
+			cnt--;
+		}
+	}
+	unsigned int bufDelay=globals->motion.feedbackDelay/bufTime;
+	unsigned int frameDelay=(globals->motion.feedbackDelay-bufDelay*bufTime)/FrameTime;
+	int bufAdvance=motionBuffers.size()-1-bufDelay;
+	std::list<float(*)[NumOutputs]>::iterator tgt=motionBufferPos;
+	if(bufAdvance<0) {
+		//cout << "negative bufAdvance " << bufAdvance << ' ' << globals->motion.feedbackDelay << ' ' << motionBuffers.size() << endl;
+		frameDelay=0;
+	} else if(bufAdvance>0) {
+		//cout << "positive bufAdvance " << bufAdvance << ' ' << globals->motion.feedbackDelay << ' ' << motionBuffers.size() << endl;
+		while(bufAdvance-- > 0) {
+			if(++tgt==motionBuffers.end())
+				tgt=motionBuffers.begin();
+		}
+	}
+	float * outputs = (*tgt)[NumFrames-1-frameDelay];
+	for(unsigned int i=0; i<NumOutputs; ++i) {
+		curPose(i).value = outputs[i];
+		curPose(i).weight = (globals->motion.override || globals->motion.providedOutputs[i]==0) ? 1 : 0;
+	}
+	return curPose;
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.3 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:55:05 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/MotionExecThread.h ./local/tekkotsu/MotionExecThread.h
--- ../Tekkotsu_3.0/local/tekkotsu/MotionExecThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/MotionExecThread.h	2007-10-12 12:55:05.000000000 -0400
@@ -0,0 +1,85 @@
+//-*-c++-*-
+#ifndef INCLUDED_MotionExecThread_h_
+#define INCLUDED_MotionExecThread_h_
+
+#include "IPC/PollThread.h"
+#include "Shared/RobotInfo.h"
+#include "IPC/MessageQueue.h"
+#include "Shared/get_time.h"
+#include "Motion/PostureEngine.h"
+#include "SharedGlobals.h"
+#include <list>
+#include <fcntl.h>
+
+#include "local/MotionHook.h"
+
+class RCRegion;
+class EntryPoint;
+
+//! description of MotionExecThread
+class MotionExecThread : public PollThread {
+public:
+	//! constructor, enables trackPollTime, but not auto-start (call reset() when you're ready to start it)
+	/*! @arg bl a process lock to ensure mutual exclusion between MotionExecThread::poll() and other threads in the process */
+	MotionExecThread(EntryPoint& bl)
+		: PollThread(0L, FrameTime*NumFrames/globals->timeScale/1000, true,false), motionLock(bl),
+		motionBuffers(), motionBufferPos(), curPose(), lastPoll(-1U)
+	{
+		motionBuffers.push_front(new float[NumFrames][NumOutputs]);
+		for(unsigned int f=0; f<NumFrames; ++f)
+			for(unsigned int o=0; o<NumOutputs; ++o)
+				motionBuffers.front()[f][o]=0;
+		motionBufferPos=motionBuffers.begin();
+		curPose.setWeights(1);
+	}
+	virtual ~MotionExecThread() {
+		if(isStarted()) {
+			stop();
+			join();
+		}
+		while(motionBuffers.size()>0) {
+			delete [] motionBuffers.front();
+			motionBuffers.pop_front();
+		}
+	}
+	
+	virtual void reset(); //!< starts and stops thread as needed, or interrupts thread to reset sleep time if already running
+	
+	//virtual void start();
+	virtual bool poll();
+
+	//! returns time (in milliseconds) of next motion frame -- multiples of FrameTime*NumFrames
+	static unsigned int getNextMotion() {
+		unsigned int pd=FrameTime*NumFrames;
+		return (get_time()/pd+1)*pd;
+	}
+
+	//! returns a posture storing the "current" output values, delayed by SharedGlobals::MotionSimConfig::feedbackDelay
+	const PostureEngine& getPostureFeedback();
+	
+protected:
+	virtual bool launched();
+	//! resets PollThread::delay and PollThread::period to appropriate values for current SharedGlobals::timeScale value
+	virtual void interrupted();
+	
+	EntryPoint& motionLock; //!< a lock on the motions which should be obtained before updating
+
+	std::list<float(*)[NumOutputs]> motionBuffers;
+	std::list<float(*)[NumOutputs]>::iterator motionBufferPos;
+	PostureEngine curPose;
+	
+	unsigned int lastPoll;
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:55:05 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Process.cc ./local/tekkotsu/Process.cc
--- ../Tekkotsu_3.0/local/tekkotsu/Process.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Process.cc	2007-06-14 11:37:42.000000000 -0400
@@ -0,0 +1,64 @@
+#include "Process.h"
+#include "SharedGlobals.h"
+#include "Sound/SoundManager.h"
+#include "IPC/SharedObject.h"
+#include "Shared/MarkScope.h"
+#include "Shared/debuget.h"
+#include <unistd.h>
+
+using namespace std;
+
+Process* Process::procs[ProcessID::NumProcesses];
+
+Process::Process(ProcessID::ProcessID_t pid, const std::string& pname) {
+	ProcessID::setID(pid);
+	procs[pid]=this;
+	globals->pids[ProcessID::getID()]=getpid();
+	strncpy(globals->processNames[ProcessID::getID()],pname.c_str(),SharedGlobals::MAX_PROCESS_NAME_LEN);
+}
+
+Process::~Process() {
+	procs[ProcessID::getID()]=NULL;
+}
+
+void Process::run() {
+	globals->waitShutdown();
+}
+
+void Process::statusReport(std::ostream& os) {
+	os << getName() << " (" << ProcessID::getID() << ") Attached Regions -----------" << endl;
+	RCRegion::attachedRegions_t::const_iterator it=RCRegion::attachedBegin(true);
+	for(; it!=RCRegion::attachedEnd(); RCRegion::attachedAdvance(it)) {
+		//subtract one from the reference counts to discount iterator's own reference (using thread-safe iterator access, uses a reference)
+		unsigned int lref=(it->second->NumberOfLocalReference()-1);
+		unsigned int ref=(it->second->NumberOfReference()-1);
+		os << '\t' << setw(16) << left << it->first << setw(8) << right << it->second->Size() << " bytes" << setw(8) << lref<<'/'<<ref << " references" << endl;
+	}
+	os << '\t' << setw(16) << left << "Next RCRegion ID: " << setw(8) << right << RCRegion::getNextKey() << endl;
+	os << '\t' << setw(16) << left << "Next ShdObj ID: " << setw(8) << right << SharedObjectBase::getNextKey() << endl;
+	if(sndman!=NULL)
+		os << '\t' << setw(16) << left << "Next SndRgn ID: " << setw(8) << right << sndman->getNextKey() << endl;
+}
+
+bool Process::statusReport(RCRegion* msg) {
+	Process* cur=Process::getCurrent();
+	ASSERTRETVAL(cur!=NULL,"statusReport, but NULL process!",true);
+	if(strcasecmp(msg->Base(),getName())==0 || strcasecmp(msg->Base(),"all")==0) {
+		MarkScope l(globals->lock); //prevent jumbling reports
+		cur->statusReport(cout);
+		cout << endl;
+	}
+	return true;
+}
+
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/14 15:37:42 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Process.h ./local/tekkotsu/Process.h
--- ../Tekkotsu_3.0/local/tekkotsu/Process.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Process.h	2007-06-14 11:37:42.000000000 -0400
@@ -0,0 +1,44 @@
+//-*-c++-*-
+#ifndef INCLUDED_Process_h_
+#define INCLUDED_Process_h_
+
+#include "IPC/ProcessID.h"
+#include <string>
+
+class RCRegion;
+
+//! Represents a common interface for each process being run
+class Process {
+public:
+	Process(ProcessID::ProcessID_t pid, const std::string& pname);
+	virtual ~Process();
+	virtual void DoStart() {}
+	virtual void DoStop() {}
+	virtual void run();
+
+	static const char* getName() { return ProcessID::getIDStr(); }
+	static Process * getCurrent() { return procs[ProcessID::getID()]; }
+	
+	virtual void statusReport(std::ostream& os);
+	static bool statusReport(RCRegion* msg);
+
+protected:
+	static Process* procs[ProcessID::NumProcesses];
+	
+private:
+	Process(const Process&);            //!< don't call
+	Process& operator=(const Process&); //!< don't call
+};
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/14 15:37:42 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/SharedGlobals.cc ./local/tekkotsu/SharedGlobals.cc
--- ../Tekkotsu_3.0/local/tekkotsu/SharedGlobals.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/SharedGlobals.cc	2007-06-14 11:37:42.000000000 -0400
@@ -0,0 +1,67 @@
+#include "SharedGlobals.h"
+#include "Simulator.h"
+
+const char * const SharedGlobals::runlevel_names[SharedGlobals::NUM_RUNLEVELS+1] = {
+	"CREATED",
+	"CONSTRUCTING",
+	"STARTING",
+	"RUNNING",
+	"STOPPING",
+	"DESTRUCTING",
+	"DESTRUCTED",
+	""
+};
+
+ipc_setup_t * ipc_setup=NULL;
+SharedGlobals * globals=NULL;
+
+unsigned int SharedGlobals::get_time() {
+	float lastLastTimeScale=lastTimeScale; // used to avoid repeated "pause" commands if we're past autoPauseTime
+	if(timeScale<=0) {
+		//just need to update lastTimeScale in case it had been realtime mode
+		//adding an 'if' to test before the assignment is slower than just always doing the assignment
+		lastTimeScale=timeScale;
+	} else {
+		if(lastTimeScale<=0) {
+			//switching from non-realtime to realtime mode -- reset time offset
+			timeOffset=bootTime.Age().Value()*timeScale*1000-simulatorTime;
+			lastTimeScale=timeScale;
+			//we reset timeOffset such that simulatorTime hasn't changed
+		} else if(lastTimeScale!=timeScale) {
+			//switching speeds -- reset time offset
+			simulatorTime=get_real_time(lastTimeScale);
+			timeOffset=bootTime.Age().Value()*timeScale*1000-simulatorTime;
+			lastTimeScale=timeScale;
+		} else {
+			simulatorTime=get_real_time(timeScale);
+		}
+		//cout << timeOffset << ' ' << lastTimeScale << ' ' << timeScale << endl;
+	}
+	if(simulatorTime>autoPauseTime) {
+		simulatorTime=autoPauseTime;
+		if(ProcessID::getID()==ProcessID::SimulatorProcess) {
+			if(timeScale!=0) // don't reset it if it's already set -- triggers infinite recursion if/when the hook calls get_time
+				timeScale=0;
+		} else {
+			// can't set timeScale directly because Simulator process has hooks registered and we aren't in the Simulator process
+			if(lastLastTimeScale!=0) {
+				lastTimeScale=0;
+				Simulator::sendCommand("pause quiet"); // so do this instead
+			}
+		}
+	}
+	return simulatorTime;
+}
+
+float SharedGlobals::getTimeScale() const { return timeScale; }
+
+/*! @file
+ * @brief A class to hold various simulator parameters which need to be accessed from multiple processes
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/14 15:37:42 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/SharedGlobals.h ./local/tekkotsu/SharedGlobals.h
--- ../Tekkotsu_3.0/local/tekkotsu/SharedGlobals.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/SharedGlobals.h	2007-11-09 14:01:17.000000000 -0500
@@ -0,0 +1,273 @@
+//-*-c++-*-
+#ifndef INCLUDED_CLASSNAME_h_
+#define INCLUDED_CLASSNAME_h_
+
+#include "IPC/MutexLock.h"
+#include "IPC/SemaphoreManager.h"
+#include "IPC/ProcessID.h"
+#include "Shared/plist.h"
+#include "Shared/TimeET.h"
+#include "Shared/RobotInfo.h"
+
+//! A class to hold various simulator parameters which need to be accessed from multiple processes
+class SharedGlobals {
+public:
+	//! constructor
+	SharedGlobals()
+		: waitForSensors(false), simulatorTime(0), timeScale(1), motion(), lock(), 
+		nextTimer(-1U), nextMotion(-1U), nextSensorUpdate(-1U), bootTime(), timeOffset(0), lastTimeScale(0), autoPauseTime(-1U),
+			semgr(2), running(semgr.getSemaphore()), sensorValid(semgr.getSemaphore())
+	{
+		for(unsigned int i=0; i<NUM_RUNLEVELS; i++)
+			level_count[i]=0;
+		semgr.raise(running,1);
+		semgr.raise(sensorValid,1);
+	}
+	//! destructor
+	~SharedGlobals() {
+		semgr.releaseSemaphore(running);
+		semgr.releaseSemaphore(sensorValid);
+	}
+	
+	//       ****************
+	//!@name Startup Control
+	//       ****************
+	
+	//! Controls whether to wait for initial sensor readings before triggering the startup behavior or starting the motion polling thread.
+	/*! This can avoid jumping to the 0-point on simulator launch.  Changes after initial launch are ignored. */
+	plist::Primitive<bool> waitForSensors;
+	
+	//! call this to cause "system shutdown" -- clean halt of the simulator (not actually the host system)
+	void signalHaveSensors() {
+		semgr.setValue(sensorValid,0);
+	}
+	//! test to see if the shutdown flag has been set (non-blocking)
+	bool haveSensors() const {
+		return semgr.testZero(sensorValid,false);
+	}
+	//! blocks until shutdown flag has been set
+	bool waitSensors() {
+		return semgr.testZero(sensorValid,true);
+	}
+	
+	//@}
+	
+	
+	//       ****************
+	//!@name Shutdown Control
+	//       ****************
+
+	//! call this to cause "system shutdown" -- clean halt of the simulator (not actually the host system)
+	void signalShutdown() {
+		semgr.setValue(running,0);
+		if(waitForSensors && !haveSensors())
+			signalHaveSensors(); // break out of deadlock in Main and Motion if we were waiting for the first sensor
+	}
+	//! test to see if the shutdown flag has been set (non-blocking)
+	bool isShutdown() const {
+		return semgr.testZero(running,false);
+	}
+	//! blocks until shutdown flag has been set
+	bool waitShutdown() {
+		return semgr.testZero(running,true);
+	}
+	
+	//! access to #semgr, returns SemaphoreManager::hadFault()
+	bool hadFault() const { return semgr.hadFault(); }
+	
+	//! access to #semgr's SemaphoreManager::faultShutdown() -- call this *after* a fault has occured from the signal handler; doesn't signal the fault itself
+	void faultShutdown() { semgr.faultShutdown(); }
+	
+	//@}
+
+
+	//       ************
+	//!@name Time Control
+	//       ************
+
+	//! returns the current simulator time, in milliseconds since startup
+	/*! the simulator should set project_get_time::get_time_callback to call this,
+	 *  so calls to ::get_time() will be forwarded here.  That wall all processes
+	 *  will share the same time */
+	unsigned int get_time();
+	
+	//! returns the current simulator #timeScale (speed factor), as a ratio of real time (e.g. '2' means simulation is running two times wall clock)
+	/*! the simulator should set project_get_time::get_timeScale_callback to call this,
+	 *  so calls to ::getTimeScale() will be forwarded here. */
+	float getTimeScale() const;
+	
+	//! the current time within the simulation, only applicable when timeScale is negative (non-realtime)
+	unsigned int simulatorTime;
+	
+	//! Controls the speed at which time from get_time() will move
+	/*! You can use this to pretend your hardware is faster or slower
+	 *  than it actually is.  For instance, a value of .5 means time
+	 *  will move at half speed (pretending your hardware is twice as
+	 *  fast)  This can be useful for "slow motion" analysis, or you
+	 *  can speed up time to simulate a more processor-restrictive platform.
+	 *
+	 *  Negative values indicate full-speed processing -- time will be
+	 *  incremented only as quickly as it can be without dropping any
+	 *  video or sensor frames. (may be faster or slower than realtime)
+	 *  in this case, #simulatorTime is used by calls to get_time()
+	 *
+	 *  A value of zero halts time. */
+	plist::Primitive<double> timeScale;
+
+	//! sets #autoPauseTime
+	void setAutoPauseTime(unsigned int t) { autoPauseTime=t; }
+	//! returns #autoPauseTime
+	unsigned int getAutoPauseTime() const { return autoPauseTime; }
+	
+	//@}
+
+
+	//       **********************
+	//!@name Runlevel Communication
+	//       **********************
+
+	//! defines the runlevels that each process passes through; runlevels should monotonically increase (can't go backwards)
+	enum runlevel_t {
+		CREATED=0,    //!< corresponding element of #level_count is incremented prior to each fork -- not strictly a runlevel per se
+		CONSTRUCTING, //!< currently initializing
+		STARTING,     //!< setting up shared memory regions with other processes
+		RUNNING,      //!< full activity, stay here until the #running semaphore is set to 0
+		STOPPING,     //!< dereferencing shared regions, waiting for threads to finish
+		DESTRUCTING,  //!< destructors are in progress
+		DESTRUCTED,   //!< destruction has completed, corresponding element of #level_count is incremented immediately prior to process completion
+	};
+	static const unsigned int NUM_RUNLEVELS=DESTRUCTED+1; //!< symbolic access to the total number of runlevel stages
+
+	//! string versions of runlevel_t for runtime user-feedback
+	static const char * const runlevel_names[NUM_RUNLEVELS+1];
+
+	//! a count of the number of processes which have passed through each runlevel
+	unsigned int level_count[NUM_RUNLEVELS];
+
+	//@}
+
+
+	//       **********************
+	//!@name Configuration Parameters
+	//       **********************
+
+	//! holds configuration parameters for the motion process
+	class MotionSimConfig : public virtual plist::Dictionary {
+	public:
+		//! constructor
+		MotionSimConfig() : plist::Dictionary(), verbose(1), feedbackDelay(0),
+			zeroPIDFeedback(false), /*speedLimit(0),*/ override(false), frameNumber(-1U)
+		{
+			setLoadSavePolicy(FIXED,SYNC);
+			addEntry("Verbose",verbose,"Report whenever motion commands are being processed or joints are updated\n0 - nothing, 1 - errors, 2 - warnings (e.g. dropped frames), 3 - notification every frame");
+			addEntry("FeedbackDelay",feedbackDelay,"Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)");
+			addEntry("ZeroPIDFeedback",zeroPIDFeedback,"When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative");
+			//addEntry("EnforceSpeedLimit",speedLimit,"The simulated motion of joints is limited to this factor of model's recommended speed limits.  0 (or negative) disables speed limit altogether.");
+			addEntry("OverrideSensors",override,"Allows motion feedback to override position values from sensor data loaded from disk.\nIf false, feedback is only provided when no other sensor data is being provided");
+			
+			for(unsigned int i=0; i<NumOutputs; i++)
+				providedOutputs[i]=0;
+		}
+		plist::Primitive<int> verbose; //!< Report whenever motion commands are being processed or joints are updated; 0 - nothing, 1 - errors, 2 - warnings (e.g. dropped frames), 3 - notification every frame
+		plist::Primitive<int> feedbackDelay; //!< Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)
+		plist::Primitive<bool> zeroPIDFeedback; //!< When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative
+		//plist::Primitive<float> speedLimit; //!< The simulated motion of joints is limited to this factor of model's recommended speed limits.  0 (or negative) disables speed limit altogether.
+		plist::Primitive<bool> override; //!< Allows motion feedback to override position values from sensor data loaded from disk; if false, feedback is only provided when no other sensor data is being provided
+		unsigned int frameNumber; //!< a monotonically increasing count of the number of sensor frames which have been "completed".  Needed to allow coordination between sensor loading from disk and feedback from motion.  Count is increased by the simulator process, which will send a heartbeat message over Simulator::sensorQueue when it does so.
+		
+		//! Counts the number of sensor data sources which are providing readings for each output
+		/*! This isn't a configuration setting per se, but needed so motion process can tell if it
+		 *  should provide feedback for each output.  If an output doesn't have any sensor feedback
+		 *  (or #override is true), then motion should provide feedback.  If more than one
+		 *  sensor is providing the same output, that could be a problem, but not dealt with here.
+		 *
+		 *  The simulator's initialization routines will pass this to DataSource::setOutputTracker(). */
+		unsigned int providedOutputs[NumOutputs];
+		
+		//! returns true if any of #providedOutputs is greater than zero
+		bool hasProvidedOutput() const { for(unsigned int i=0; i<NumOutputs; i++) if(providedOutputs[i]>0) return true; return false; }
+		//! returns true if any of #providedOutputs is zero
+		bool hasUnprovidedOutput() const { for(unsigned int i=0; i<NumOutputs; i++) if(providedOutputs[i]==0) return true; return false; }
+	} motion;
+	
+	//@}
+	
+	//! allows mutually exclusive access to the fields of SharedObject
+	MutexLock<ProcessID::NumProcesses> lock;
+
+	//! holds the host system's process ID for each simulator process
+	pid_t pids[ProcessID::NumProcesses];
+
+	//! maximum storage size of strings in #processNames
+	static const unsigned int MAX_PROCESS_NAME_LEN=32;
+
+	//! each process should set a string version of its name for user feedback
+	char processNames[ProcessID::NumProcesses][MAX_PROCESS_NAME_LEN];
+	
+	bool setNextTimer(unsigned int t) { if(nextTimer==t) return false; nextTimer=t; return true; } //!< sets #nextTimer, returns true if the new value differs from previous value
+	unsigned int getNextTimer() { return nextTimer; } //!< gets #nextTimer
+	
+	void setNextMotion(unsigned int t) { nextMotion=t; } //!< sets #nextMotion
+	unsigned int getNextMotion() { return nextMotion; } //!< gets #nextMotion
+	
+	void setNextSensorUpdate(unsigned int t) { nextSensorUpdate=t; } //!< sets #nextSensorUpdate
+	unsigned int getNextSensorUpdate() { return nextSensorUpdate; } //!< gets #nextSensorUpdate
+	
+	void resetBootTime() { timeOffset=bootTime.Age().Value()*timeScale*1000; simulatorTime=0; }
+	
+protected:
+	//! this returns time since boot (#bootTime), scaled by @a scale, relative to #timeOffset
+	unsigned int get_real_time(double scale) const {
+		return static_cast<unsigned int>(bootTime.Age().Value()*scale*1000-timeOffset);
+	}
+
+	//! set by setNextTimer, called with the current value of EventRouter::getNextTimer() after each user code section, indicates time of next timer event
+	unsigned int nextTimer;
+	
+	//! updated by Motion process after each motion update
+	unsigned int nextMotion;
+	
+	//! updated by Main process after each sensor update
+	unsigned int nextSensorUpdate;
+	
+	//! real time since simulator startup (or, at least, since SharedGlobals was constructed... close enough)
+	TimeET bootTime; 
+
+	//! the scaled value of #bootTime at which isRealTime was last activated, allows you to start and stop realtime fluidly
+	double timeOffset; 
+	
+	//! updated by each call to get_time(), if timeScale differs, allows timeOffset to be updated fluidly
+	double lastTimeScale;
+	
+	//! if simulatorTime is about to move past this value, timeScale is set to 0 instead, and simulatorTime is set to this
+	unsigned int autoPauseTime;
+	
+	SemaphoreManager semgr; //!< a semaphore set, only used for #running and #sensorValid
+	SemaphoreManager::semid_t running; //!< the semaphore within #semgr to communicate shutdown status between processes -- when the semaphore is set to 0, shutdown is requested
+	SemaphoreManager::semid_t sensorValid; //!< the semaphore within #semgr to notify processes when the first sensor frame is available
+};
+
+const unsigned int MAX_SUBJECTS=50; //!< maximum number of message queues the simulator can maintain
+const unsigned int MAX_SUBJECT_NAME=50; //!< maximum storage capacity of subject names
+
+// just a forward definition of RegionRegistry
+template<unsigned int MAX_SUBJECTS, unsigned int MAX_SUBJECT_NAME> class RegionRegistry;
+//! the type to use for the inter-process communication registry
+typedef RegionRegistry<MAX_SUBJECTS,MAX_SUBJECT_NAME> ipc_setup_t;
+
+extern ipc_setup_t * ipc_setup; //!< a global pointer to the inter-process message queue registry (a RegionRegistry)
+extern SharedGlobals * globals; //!< a global pointer to the SharedGlobals instance
+extern float getTimeScale(); //!< a prototype for accessing current time scale without referencing ::globals directly
+
+/*! @file
+ * @brief A class to hold various simulator parameters which need to be accessed from multiple processes
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.3 $
+ * $State: Exp $
+ * $Date: 2007/11/09 19:01:17 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/SimConfig.h ./local/tekkotsu/SimConfig.h
--- ../Tekkotsu_3.0/local/tekkotsu/SimConfig.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/SimConfig.h	2007-10-26 18:33:16.000000000 -0400
@@ -0,0 +1,60 @@
+//-*-c++-*-
+#ifndef INCLUDED_SimConfig_h_
+#define INCLUDED_SimConfig_h_
+
+#include "Shared/plist.h"
+#include "SharedGlobals.h"
+#include "IPC/RCRegion.h"
+
+//! Provides the root dictionary of the simulator configuration, items from SharedGlobals and LoadFileThreads are added as entries in this dictionary
+class SimConfig : public plist::Dictionary {
+public:
+	SimConfig() : plist::Dictionary(false),
+		cmdPrompt("hal> "),
+		initSimTime(0),
+		tgtRunlevel(SharedGlobals::RUNNING, SharedGlobals::runlevel_names),
+		multiprocess(false),
+		lastfile()
+	{
+		sim::config.setUnusedWarning(false);
+		addEntry("InitialTime",initSimTime,"The value to initialize the simulator's clock (in milliseconds)");
+		addEntry("InitialRunlevel",tgtRunlevel,"Specifies how far startup should proceed before pausing for user interaction.\nThis value only affects startup, and setting this value from the simulator command prompt will have no effect.  (Use the 'runlevel' command instead.)");
+		addEntry("Multiprocess",multiprocess,"The processing/threading model to use - true to use real process forks a la Aibo/Aperios, or false to just more threads like a sane person would do");
+	}
+	
+	std::string cmdPrompt; //!< Not persistently stored -- [re]set by main(...) on each run
+	plist::Primitive<unsigned int> initSimTime; //!< The "boot" time to start the simulator clock at (default 0)
+	plist::NamedEnumeration<SharedGlobals::runlevel_t> tgtRunlevel; //!< The runlevel the simulator should move to (i.e. stop before 'running' to debug startup code)
+	plist::Primitive<bool> multiprocess; //!< The processing/threading model to use -- true to use real process forks a la Aibo/Aperios, or false to just more threads like a sane person would do
+
+	void setLastFile(const std::string& str) const {
+		lastfile=str;
+	}
+	const std::string& getLastFile() const {
+		return lastfile;
+	}
+	virtual unsigned int loadFile(const char* filename) {
+		lastfile=filename;
+		return plist::Dictionary::loadFile(filename);
+	}
+	virtual unsigned int saveFile(const char* filename) const {
+		lastfile=filename;
+		return plist::Dictionary::saveFile(filename);
+	}
+	
+protected:
+	mutable std::string lastfile;
+};
+
+/*! @file
+ * @brief Provides the root dictionary of the simulator configuration, items from SharedGlobals and LoadFileThreads are added as entries in this dictionary
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/10/26 22:33:16 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Simulator.cc ./local/tekkotsu/Simulator.cc
--- ../Tekkotsu_3.0/local/tekkotsu/Simulator.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Simulator.cc	2007-11-19 16:00:41.000000000 -0500
@@ -0,0 +1,1198 @@
+#include "Simulator.h"
+#include "Main.h"
+#include "Motion.h"
+#include "sim.h"
+#include "Shared/string_util.h"
+#include "Shared/RobotInfo.h"
+#include "SimConfig.h"
+#include "Shared/debuget.h"
+#include "Shared/MarkScope.h"
+#include "IPC/MessageReceiver.h"
+#include "IPC/RegionRegistry.h"
+#include "local/DataSources/FileSystemDataSource.h"
+#include "local/DataSources/FileSystemImageSource.h"
+#include "local/CommPort.h"
+#include "local/DeviceDriver.h"
+
+#include <iostream>
+#include <libxml/tree.h>
+
+#ifndef DISABLE_READLINE
+#  include <readline/readline.h>
+#  include <readline/history.h>
+#endif
+
+using namespace std;
+
+const float Simulator::avgSpeedupGamma=.99;
+
+Simulator* Simulator::theSim=NULL;
+std::set<MotionHook*> Simulator::motionHooks;
+
+Simulator::Simulator()
+: Process(getID(),getClassName()), plist::PrimitiveListener(), plist::CollectionListener(), MessageQueueStatusThread::StatusListener(), frameCounter(), cmdThread(),
+cameraQueue(ipc_setup->registerRegion(Simulator::getCameraQueueID(),sizeof(sim::CameraQueue_t))),
+sensorQueue(ipc_setup->registerRegion(Simulator::getSensorQueueID(),sizeof(sim::SensorQueue_t))),
+timerWakeup(ipc_setup->registerRegion(Simulator::getTimerWakeupID(),sizeof(sim::TimerWakeup_t))),
+motionWakeup(ipc_setup->registerRegion(Simulator::getMotionWakeupID(),sizeof(sim::MotionWakeup_t))),
+statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
+events(ipc_setup->registerRegion(Main::getEventsID(),sizeof(sim::EventQueue_t))),
+motionout(ipc_setup->registerRegion(Motion::getMotionOutputID(),sizeof(sim::MotionOutput_t))),
+commandQueue(ipc_setup->registerRegion(Simulator::getCommandQueueID(),sizeof(CommandQueue_t))),
+cameraStatus(*cameraQueue), sensorStatus(*sensorQueue), timerStatus(*timerWakeup), motionStatus(*motionWakeup), eventsStatus(), commandrecv(NULL), motionrecv(NULL),
+vision(&DeviceDriver::getImageSources,30, *cameraQueue),
+sensors(&DeviceDriver::getSensorSources,1000.f/NumFrames/FrameTime, *sensorQueue),
+frameTimes(), runSpeed(1), lastTimeScale(0), step(STEP_NONE), waitingSteps(0), curLevel(SharedGlobals::CONSTRUCTING),
+fullspeedWallStart(), fullspeedSimStart(), lastFrameWallStart(), avgWallTime(), avgSimTime(),
+simLock()
+{
+	theSim=this;
+	new (&(*cameraQueue)) sim::CameraQueue_t;
+	new (&(*sensorQueue)) sim::SensorQueue_t;
+	new (&(*timerWakeup)) sim::TimerWakeup_t;
+	new (&(*motionWakeup)) sim::MotionWakeup_t;
+	new (&(*statusRequest)) sim::StatusRequest_t;
+	new (&(*commandQueue)) CommandQueue_t;
+	statusRequest->setOverflowPolicy(MessageQueueBase::WAIT);
+	commandQueue->setOverflowPolicy(MessageQueueBase::WAIT);
+	
+	DeviceDriver::getRegistry().addCollectionListener(this);
+	
+	/* Since we do a two stage loading (some stuff in sim.cc launcher, then some command line
+	 *  stuff, then the rest of it now that we're loaded), this is a little tricker than it normally would be. */
+	// don't remove entries from parse tree, we're going to be adding more and want their values...
+	sim::config.setSavePolicy(plist::Collection::UNION);
+	// write out the current values for entries we do have, which may have been modified since originally loaded
+	sim::config.writeParseTree();
+	// now add the rest of our entries (could just get away with addEntry()'s, but this function is a little more robust)
+	replaceEntry("CommPorts",CommPort::getRegistry(),"Communication portals for use by device drivers");
+	replaceEntry("Drivers",DeviceDriver::getRegistry(),"Settings for device drivers");
+	replaceEntry("Sensors",sensors,"Settings for the loading of sensor values");
+	replaceEntry("Vision",vision,"Settings for the loading of camera frames");
+	// now we're done adding entries, so if there's anything extra in the file, make note of it
+	sim::config.setUnusedWarning(true);
+	// reload from parse tree to get values for these new entries
+	sim::config.readParseTree();
+	// any future saves should be strict and remove those unused values (...maybe?)
+	sim::config.setSavePolicy(plist::Collection::SYNC);
+	
+	motionWakeup->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+	timerWakeup->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+	cameraQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+	sensorQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+	sensorQueue->addMessageFilter(frameCounter);
+	
+	//handle arguments passed from command line
+	vector<vector<string> > delayed; // will delay setting data queue sources until after other arguments
+	for(unsigned int i=0; i<sim::cmdlineArgs.size(); i++) {
+		if(sim::cmdlineArgs[i].find(".Source=")==string::npos) {
+			if(!processCommand(sim::cmdlineArgs[i],false))
+				cerr << "Occurred while processing " << sim::cmdlineArgs[i] << endl;
+		} else {
+			vector<string> setarg;
+			setarg.push_back("set");
+			setarg.push_back(sim::cmdlineArgs[i]);
+			delayed.push_back(setarg); // delay setting of source until after options like Frozen or Speed have been set
+		}
+	}
+	for(unsigned int i=0; i<delayed.size(); i++) {
+		//this avoids dropping initial frame(s)
+		//if we had set the source before freezing or pausing, might've dropped something between them
+		if(!cmdSet(delayed[i]))
+			cerr << "Occurred while processing " << delayed[i][1] << endl;
+	}
+	
+	// if we were supposed to start up paused, reset clock now that we've set the speed
+	if(globals->timeScale<=0)
+		globals->resetBootTime();
+
+	globals->timeScale.addPrimitiveListener(this);
+	globals->motion.verbose.addPrimitiveListener(this);
+	
+	cmdThread.start();
+	
+	if(sim::config.tgtRunlevel>SharedGlobals::RUNNING)
+		globals->signalShutdown();
+	processRunlevel(SharedGlobals::CONSTRUCTING);
+}
+
+Simulator::~Simulator() {
+	DeviceDriver::getRegistry().clear();
+	CommPort::getRegistry().clear();
+	DeviceDriver::getRegistry().removeCollectionListener(this);
+	globals->timeScale.removePrimitiveListener(this);
+	globals->motion.verbose.removePrimitiveListener(this);
+	processRunlevel(SharedGlobals::DESTRUCTING);
+	//::close(STDIN_FILENO); // seems to prevent proper terminal reset on exit...
+}
+
+void Simulator::DoStart() {
+	Process::DoStart();
+	eventsStatus.setMessageQueue(*events);
+	commandrecv = new MessageReceiver(*commandQueue, gotCommand);
+	class : public Thread {
+	public:
+		virtual void* run() { Simulator::setMotionStarting(); return NULL; }
+	} doStartThread;
+	cmdThread.runInitThread(doStartThread);
+	processRunlevel(SharedGlobals::STARTING);
+}
+
+void Simulator::run() {
+	for(unsigned int i=0; i<ProcessID::NumProcesses; ++i)
+		cout << globals->processNames[i] << " pid=" << globals->pids[i] << ";  ";
+	cout << endl;
+	if(globals->timeScale!=0)
+		runSpeed=globals->timeScale;
+
+	motionrecv = new MessageReceiver(*motionout, gotMotion);
+	
+	DataSource::setNeedsSensor(globals->waitForSensors);
+	resetSpeedMode();
+	if(globals->timeScale<0)
+		incrementTime();
+	
+	if(globals->waitForSensors) {
+		if(sensors.source.size()==0) {
+			cout << "Ignoring WaitForSensors flag because Sensors has no source" << endl;
+		} else {
+			if(DeviceDriver::getRegistry().getInstance(sensors.source)==NULL) {
+				cout << "Ignoring WaitForSensors flag because Sensors source is invalid" << endl;
+			} else {				
+				class : public Thread {
+				public:
+					virtual void* run() { globals->waitSensors(); return NULL; }
+				} waitSensorsThread;
+				cmdThread.runInitThread(waitSensorsThread);
+			}
+		 }
+	}
+	DataSource::setNeedsSensor(false);
+
+	if(sim::config.tgtRunlevel==SharedGlobals::RUNNING)
+		Process::run();
+
+	sensors.source="";
+	vision.source="";
+	if(sensors.isStarted())
+		sensors.stop();
+	if(vision.isStarted())
+		vision.stop();
+	
+	if(globals->timeScale<0) {
+		motionStatus.removeStatusListener(this);
+		timerStatus.removeStatusListener(this);
+		sensorStatus.removeStatusListener(this);
+		cameraStatus.removeStatusListener(this);
+	}
+	globals->signalShutdown();
+}
+
+void Simulator::plistValueChanged(const plist::PrimitiveBase& pl) {
+	MarkScope l(simLock);
+	if(&pl==&globals->timeScale) {
+		get_time(); // force SharedGlobals to notice the change and update its state
+		resetSpeedMode();
+		if(globals->timeScale<0)
+			incrementTime();
+		timerWakeup->sendMessage(NULL);
+		motionWakeup->sendMessage(NULL);
+	} else if(&pl==&globals->motion.verbose) {
+		for(std::set<MotionHook*>::iterator it=motionHooks.begin(); it!=motionHooks.end(); ++it)
+			(*it)->setMotionHookVerbose(globals->motion.verbose);
+	} else {
+		cerr << "WARNING: Simulator got a plistValueChanged for an unknown plist primitive";
+	}
+}
+void Simulator::plistCollectionEntryAdded(plist::Collection& col, plist::ObjectBase& primitive) {
+	MarkScope l(simLock);
+	if(&col==&DeviceDriver::getRegistry()) {
+		if(DeviceDriver * d=dynamic_cast<DeviceDriver*>(&primitive)) {
+			if(MotionHook * mh = d->getMotionSink()) {
+				mh->setMotionHookVerbose(globals->motion.verbose);
+				motionHooks.insert(mh);
+				if(curLevel==SharedGlobals::RUNNING) {
+					mh->motionStarting();
+					if(globals->timeScale>0)
+						mh->enteringRealtime();
+				}
+			}
+		} else {
+			cerr << "WARNING: Simulator got a plistCollectionEntryAdded for an unknown primitive type";
+		}
+	} else {
+		cerr << "WARNING: Simulator got a plistCollectionEntryAdded for an unknown plist collection";
+	}
+}
+void Simulator::plistCollectionEntryRemoved(plist::Collection& col, plist::ObjectBase& primitive) {
+	MarkScope l(simLock);
+	if(&col==&DeviceDriver::getRegistry()) {
+		if(DeviceDriver * d=dynamic_cast<DeviceDriver*>(&primitive)) {
+			motionHooks.erase(d->getMotionSink());
+		} else {
+			cerr << "WARNING: Simulator got a plistCollectionEntryRemoved for an unknown primitive type";
+		}
+	} else {
+		cerr << "WARNING: Simulator got a plistCollectionEntryRemoved for an unknown plist collection";
+	}
+}
+void Simulator::plistCollectionEntriesChanged(plist::Collection& col) {
+	MarkScope l(simLock);
+	if(&col==&DeviceDriver::getRegistry()) {
+		std::set<MotionHook*> oldmh;
+		motionHooks.swap(oldmh);
+		for(DeviceDriver::registry_t::const_iterator it=DeviceDriver::getRegistry().begin(); it!=DeviceDriver::getRegistry().end(); ++it) {
+			if(DeviceDriver * d=DeviceDriver::getRegistry().getInstance(it->first)) {
+				if(MotionHook * mh = d->getMotionSink()) {
+					mh->setMotionHookVerbose(globals->motion.verbose);
+					motionHooks.insert(mh);
+					if(oldmh.find(mh)==oldmh.end() && curLevel==SharedGlobals::RUNNING) {
+						mh->motionStarting();
+						if(globals->timeScale>0)
+							mh->enteringRealtime();
+					}
+				}
+			} else {
+				cerr << "WARNING: In Simulator::plistCollectionEntriesChanged, driver " << it->first << " does not correspond to a known instance" << endl;
+			}
+		}
+	} else {
+		cerr << "WARNING: Simulator got a plistCollectionEntriesChanged for an unknown plist collection";
+	}
+}
+
+void Simulator::messagesRead(MessageQueueBase& mq, unsigned int /*n*/) {
+	MarkScope l(simLock);
+	if(globals->timeScale<0) {
+		//clear corresponding bit in waitingSteps
+		 if(&mq==&(*cameraQueue)) {
+			//cout << "Camera read, ";
+			waitingSteps&=~(1<<STEP_CAMERA);
+		} else if(&mq==&(*sensorQueue)) {
+			//cout << "Sensor read, ";
+			waitingSteps&=~(1<<STEP_SENSOR);
+		} else if(&mq==&(*timerWakeup)) {
+			//cout << "Timer read, ";
+			waitingSteps&=~(1<<STEP_TIMER);
+		} else if(&mq==&(*motionWakeup)) {
+			//cout << "Motion read, ";
+			waitingSteps&=~(1<<STEP_MOTION);
+		} else if(&mq==&(*events)) {
+			//cout << "Main read event queue (" << events->getMessagesUnread() << "remain), ";
+			// nothing to do, just waiting for main to catch up before incrementing
+		} else {
+			cout << "Unknown message base read (either you meant to add some code to Simulator::messagesRead, or why did you bother to register a listener?)" << endl;
+		}
+		//cout << " waiting " << waitingSteps << " events " << events->getMessagesUnread() << endl;
+		
+		if(waitingSteps==0 && events->getMessagesUnread()==0) //if that was the last one we were waiting for -- go for the next!
+			incrementTime();
+	}
+}
+
+void Simulator::sendCommand(const std::string& cmd) {
+	static unsigned int cmdSN=0;
+	char msgname[30];
+	snprintf(msgname,30,"SimCommand.%d.%d",ProcessID::getID(),cmdSN++);
+	RCRegion * msg = new RCRegion(msgname,cmd.size());
+	strcpy(msg->Base(),cmd.c_str());
+	SharedObject<CommandQueue_t> commandQ(ipc_setup->registerRegion(Simulator::getCommandQueueID(),sizeof(CommandQueue_t)));
+	commandQ->sendMessage(msg,true);
+}
+
+void Simulator::setMotionStarting() {
+	// don't need lock, this is only called during single-threaded operation (DoStart())
+	//MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+	for(std::set<MotionHook*>::iterator it=theSim->motionHooks.begin(); it!=theSim->motionHooks.end(); ++it)
+		(*it)->motionStarting();
+}
+void Simulator::setMotionStopping() {
+	// don't need lock, this is only called during single-threaded operation (DoStop())
+	//MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+	for(std::set<MotionHook*>::iterator it=theSim->motionHooks.begin(); it!=theSim->motionHooks.end(); ++it)
+		(*it)->motionStopping();
+}
+void Simulator::updateMotion(const float outputs[][NumOutputs]) {
+	MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+	for(std::set<MotionHook*>::iterator it=theSim->motionHooks.begin(); it!=theSim->motionHooks.end(); ++it)
+		(*it)->motionCheck(outputs);
+}
+void Simulator::setMotionLeavingRealtime(bool isFullSpeed) {
+	MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+	for(std::set<MotionHook*>::iterator it=theSim->motionHooks.begin(); it!=theSim->motionHooks.end(); ++it)
+		(*it)->leavingRealtime(isFullSpeed);
+}
+void Simulator::setMotionEnteringRealtime() {
+	MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+	for(std::set<MotionHook*>::iterator it=theSim->motionHooks.begin(); it!=theSim->motionHooks.end(); ++it)
+		(*it)->enteringRealtime();
+}
+
+
+void Simulator::DoStop() {
+	if(sensors.isStarted() || vision.isStarted())
+		sleep(1);
+	if(sensors.isStarted() || vision.isStarted())
+		sleep(1);
+	if(sensors.isStarted())
+		sensors.kill();
+	if(vision.isStarted())
+		vision.kill();
+	commandrecv->finish();
+	delete commandrecv;
+	commandrecv=NULL;
+	motionrecv->finish();
+	delete motionrecv;
+	motionrecv=NULL;
+	setMotionStopping();
+	processRunlevel(SharedGlobals::STOPPING);
+	Process::DoStop();
+}
+
+
+void* Simulator::CommandThread::run() {
+	Simulator * simp=dynamic_cast<Simulator*>(Process::getCurrent());
+	ASSERTRETVAL(simp!=NULL,"CommandThread not in Simulator!",NULL);
+	string prompt; // initially prompt is empty because it will be buried in startup text anyway
+	// we'll display another prompt at the end of launch (or if user hits enter)
+	while(true) {
+		testCancel();
+		string line;
+#ifndef DISABLE_READLINE
+		char* readin=readline(prompt.c_str());
+		if(readin==NULL) {
+			cout << endl;
+			simp->cmdQuit(vector<string>());
+			break;
+		}
+		line=readin;
+		free(readin);
+#else
+		cout << prompt << flush;
+		getline(cin,line);
+		if(!cin) {
+			cout << endl;
+			simp->cmdQuit(vector<string>());
+			break;
+		}
+#endif
+		simp->processCommand(line,true);
+		prompt = sim::config.cmdPrompt;
+	}
+	return NULL;
+}
+
+void Simulator::CommandThread::cancelled() {
+#ifndef DISABLE_READLINE
+	rl_reset_terminal(NULL);
+#endif
+}
+
+void Simulator::CommandThread::runInitThread(Thread& th) {
+	initThread=&th;
+	th.start();
+	th.join();
+	initThread=NULL;
+}
+
+void Simulator::resetSpeedMode() {
+	if(globals->timeScale<=0) {
+		if(vision.isStarted()) {
+			vision.stop();
+			//vision.join(); // can't join because runfor/runto pause might be triggered within LoadFileThread's get_time() call
+		}
+		if(sensors.isStarted()) {
+			sensors.stop();
+			//sensors.join(); // can't join because runfor/runto pause might be triggered within LoadFileThread's get_time() call
+		}
+	} else {
+		if(sim::config.tgtRunlevel==SharedGlobals::RUNNING) { 
+			vision.start();
+			sensors.start();
+		}
+	}
+	if(lastTimeScale>0 && globals->timeScale<=0) {
+		setMotionLeavingRealtime(globals->timeScale<0);
+	} else if(lastTimeScale<=0 && globals->timeScale>0) {
+		setMotionEnteringRealtime();
+	}
+	if(globals->timeScale<0) {
+		cameraQueue->setOverflowPolicy(MessageQueueBase::WAIT);
+		sensorQueue->setOverflowPolicy(MessageQueueBase::WAIT);
+		// these status listener calls check to prevent duplicate listeners
+		cameraStatus.addStatusListener(this);
+		sensorStatus.addStatusListener(this);
+		timerStatus.addStatusListener(this);
+		motionStatus.addStatusListener(this);
+		eventsStatus.addStatusListener(this);
+		fullspeedWallStart.Set();
+		fullspeedSimStart=globals->simulatorTime;
+		lastFrameWallStart.Set();
+		avgWallTime=avgSimTime=0;
+	} else {
+		cameraQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+		sensorQueue->setOverflowPolicy(MessageQueueBase::DROP_OLDEST);
+		eventsStatus.removeStatusListener(this);
+		motionStatus.removeStatusListener(this);
+		timerStatus.removeStatusListener(this);
+		sensorStatus.removeStatusListener(this);
+		cameraStatus.removeStatusListener(this);
+	}
+	if(globals->timeScale==0)
+		globals->setAutoPauseTime(-1U);
+	lastTimeScale=globals->timeScale;
+}
+
+void Simulator::replaceEntry(const std::string& name, plist::Dictionary& d, const std::string& comment) {
+	plist::Dictionary::const_iterator it = sim::config.findEntry(name);
+	if(it==sim::config.end()) {
+		sim::config.addEntry(name,d,comment);
+	} else {
+		d.set(*it->second);
+		sim::config.setEntry(name,d);
+		sim::config.setComment(name,comment);
+	}
+}
+
+void Simulator::incrementTime() {
+	MarkScope l(simLock);
+	waitingSteps=getNextFrame();
+	if(waitingSteps==0)
+		return;
+	unsigned int next=*frameTimes.begin();
+	if(next>globals->simulatorTime) {
+		unsigned int adv=next-globals->simulatorTime;
+		avgWallTime=avgWallTime*avgSpeedupGamma + lastFrameWallStart.Age().Value()*(1-avgSpeedupGamma);
+		avgSimTime=avgSimTime*avgSpeedupGamma + adv*(1-avgSpeedupGamma);
+		lastFrameWallStart.Set();
+		//cout << "inc " << (avgSimTime/avgWallTime/1000) << " " << waitingSteps << endl;
+		globals->simulatorTime=next;
+	}
+	if(waitingSteps & (1<<STEP_CAMERA))
+		vision.advanceFrame(false);
+	if(waitingSteps & (1<<STEP_SENSOR))
+		sensors.advanceFrame(false);
+	if(waitingSteps & (1<<STEP_TIMER))
+		timerWakeup->sendMessage(NULL);
+	if(waitingSteps & (1<<STEP_MOTION))
+		motionWakeup->sendMessage(NULL);
+	if(globals->getAutoPauseTime()<=globals->simulatorTime || (1<<step) & waitingSteps) {
+		//that was the step we were waiting for, pause sim
+		globals->timeScale=0;
+		step=STEP_NONE;
+		globals->setAutoPauseTime(-1U);
+	}
+}
+
+unsigned int Simulator::getNextFrame() {
+	frameTimes.clear();
+	/*set<unsigned int>::iterator past=frameTimes.begin();
+	while(past!=frameTimes.end() && *past<=globals->simulatorTime)
+	past++;
+	frameTimes.erase(frameTimes.begin(),past);*/
+	unsigned int vis = vision.frozen && !vision.heartbeat ? -1U : vision.nextTimestamp();
+	frameTimes.insert(vis);
+	unsigned int sen = sensors.frozen && !sensors.heartbeat ? -1U : sensors.nextTimestamp();
+	frameTimes.insert(sen);
+	unsigned int tim=globals->getNextTimer();
+	frameTimes.insert(tim);
+	unsigned int mot=globals->getNextMotion();
+	frameTimes.insert(mot);
+	unsigned int next=*frameTimes.begin();
+	//cout << "Testing: " << globals->simulatorTime << " => next camera: "<< vis << " next sensor: " << sen << " next timer: " << tim << " next motion: " << mot << " => " << next << endl;
+	unsigned int steps=0;
+	if(next!=-1U) {
+		if(next==vis) {
+			steps |= 1<<STEP_CAMERA;
+		}
+		if(next==sen) {
+			steps |= 1<<STEP_SENSOR;
+		}
+		if(next==tim) {
+			steps |= 1<<STEP_TIMER;
+		}
+		if(next==mot) {
+			steps |= 1<<STEP_MOTION;
+		}
+	}
+	return steps;
+}
+
+void Simulator::processRunlevel(SharedGlobals::runlevel_t curRunLevel) {
+	curLevel=curRunLevel;
+	if(sim::config.tgtRunlevel==curLevel && (!globals->isShutdown() || curLevel>SharedGlobals::RUNNING))
+		cout << sim::config.cmdPrompt << flush;
+	while(sim::config.tgtRunlevel==curLevel && (!globals->isShutdown() || curLevel>SharedGlobals::RUNNING)) {
+		usleep(500000); // recheck status every half second
+	}
+}
+
+bool Simulator::processCommand(const std::string& line, bool addToHistory) {
+	vector<string> args;
+	vector<unsigned int> offs;
+	if(!string_util::parseArgs(line,args,offs)) {
+		cerr << "Mismatched quotes" << endl;
+		return false;
+	}
+	if(args.size()==0)
+		return true;
+#ifndef DISABLE_READLINE
+	/*		if(current_history()==NULL)
+		cout << "current_history()==NULL" << endl;
+	else if(current_history()->line==NULL)
+		cout << "line == NULL" << endl;
+	else if(line!=current_history()->line)
+		cout << "line is different" << endl;
+	else {
+		cout << "not added" << endl;
+		cout << "new line: " << line << endl;
+		cout << "old line: " << current_history()->line << endl;
+	}
+	if(history_get(-1)==NULL)
+		cout << "history_get(0)==NULL" << endl;
+	else if(history_get(-1)->line==NULL)
+		cout << "line 0 == NULL" << endl;
+	else {
+		cout << "line 0: " << history_get(-1)->line << endl;
+		if(line!=history_get(-1)->line)
+			cout << "line 0 is different" << endl;
+		else
+			cout << "0 not added" << endl;
+	}
+	*/	
+	if(addToHistory && (current_history()==NULL || current_history()->line==NULL || line!=current_history()->line))
+		add_history(line.c_str());
+#endif
+	if(args[0]=="shutdown" || args[0]=="quit" || args[0]=="exit") {
+		cmdQuit(args);
+	} else if(args[0]=="load") {
+		cmdLoad(args);
+	} else if(args[0]=="save") {
+		cmdSave(args);
+	} else if(args[0]=="runlevel") {
+		cmdRunlevel(args);
+	} else if(args[0]=="get_time") {
+		cout << "Current time is " << get_time() << endl;
+	} else if(args[0]=="set") {
+		cmdSet(args);
+	} else if(args[0]=="runto") {
+		cmdRun(args,false);
+	} else if(args[0]=="runfor") {
+		cmdRun(args,true);
+	} else if(args[0]=="run" || args[0]=="r") {
+		cmdRun(args);
+	} else if(args[0]=="pause" || args[0]=="p") {
+		cmdPause(args);
+	} else if(args[0]=="help") {
+		cmdHelp(args);
+	} else if(args[0]=="step") {
+		cmdStep(args);
+	} else if(args[0]=="status") {
+		cmdStatus(args);
+	} else if(args[0]=="advance") {
+		cmdAdvance(args);
+	} else if(args[0]=="freeze") {
+		cmdFreeze(true,args);
+	} else if(args[0]=="unfreeze") {
+		cmdFreeze(false,args);
+	} else if(args[0]=="reset") {
+		cmdReset(args);
+	} else if(args[0]=="new") {
+		cmdNew(args);
+	} else if(args[0]=="delete") {
+		cmdDelete(args);
+	} else {
+		unsigned int i;
+		for(i=0; i<args.size(); ++i) {
+			if(args[i].find("=")!=string::npos) {
+				cmdSet(args);
+				break;
+			}
+		}
+		if(i==args.size()) {
+			cout << "Unknown command '" << args[0] << "'" << endl;
+			return false;
+		}
+	}
+	return true;
+}
+
+bool Simulator::gotCommand(RCRegion* msg) {
+	Simulator * simp=dynamic_cast<Simulator*>(Process::getCurrent());
+	ASSERTRETVAL(simp!=NULL,"gotCommand, but not within Simulator process!",true);
+	simp->processCommand(msg->Base(),false);
+	return true;
+}	
+
+bool Simulator::gotMotion(RCRegion* msg) {
+#ifdef DEBUG
+	Simulator * simp=dynamic_cast<Simulator*>(Process::getCurrent());
+	ASSERTRETVAL(simp!=NULL,"gotMotion, but not within Simulator process!",true);
+#endif
+	updateMotion(reinterpret_cast<float(*)[NumOutputs]>(msg->Base()));
+	return true;
+}
+
+void Simulator::cmdQuit(const std::vector<std::string>& /*args*/) {
+	sim::config.tgtRunlevel=SharedGlobals::DESTRUCTED;
+	globals->signalShutdown();
+	cmdThread.abortInitThread();
+}
+void Simulator::cmdLoad(const std::vector<std::string>& args) {
+	if(args.size()>1)
+		for(unsigned int i=1; i<args.size(); i++) {
+			cout << "Loading from " << args[i] << "... " << flush;
+			size_t res=sim::config.loadFile(args[i].c_str());
+			cout << (res>0 ? "done." : "load failed.") << endl;
+		}
+	else {
+		cout << "Loading from " << sim::config.getLastFile() << "... " << flush;
+		size_t res=sim::config.loadFile(sim::config.getLastFile().c_str());
+		cout << (res>0 ? "done." : "load failed.") << endl;
+	}
+}
+void Simulator::cmdSave(const std::vector<std::string>& args) {
+	if(args.size()>1)
+		for(unsigned int i=1; i<args.size(); i++)
+			sim::config.saveFile(args[i].c_str());
+	else {
+		cout << "Saving to " << sim::config.getLastFile() << "... " << flush;
+		size_t res=sim::config.saveFile(sim::config.getLastFile().c_str());
+		cout << (res>0 ? "done." : "save failed.") << endl;
+	}
+}
+void Simulator::cmdRunlevel(const std::vector<std::string>& args) {
+	if(args.size()<=1) {
+		sim::config.tgtRunlevel=static_cast<SharedGlobals::runlevel_t>(sim::config.tgtRunlevel+1);
+		cout << "Moving to next runlevel: " << SharedGlobals::runlevel_names[sim::config.tgtRunlevel] << endl;
+	} else {
+		try {
+			sim::config.tgtRunlevel=string_util::makeUpper(args[1]);
+		} catch(...) {
+			cout << "Invalid runlevel specification.  Try one of:\n\t";
+			for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++)
+				cout << i << ' ' << SharedGlobals::runlevel_names[i] << ", ";
+			cout << "\nCurrently at " << SharedGlobals::runlevel_names[curLevel] << endl;
+			return;
+		}
+		if(sim::config.tgtRunlevel<curLevel) {
+			sim::config.tgtRunlevel=curLevel;
+			cout << "Cannot reduce runlevel, currently at " << curLevel << ' ' << SharedGlobals::runlevel_names[curLevel] << "\n\t";
+			for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++)
+				cout << i << ' ' << SharedGlobals::runlevel_names[i] << ", ";
+			cout << endl;
+			return;
+		} else if(sim::config.tgtRunlevel==curLevel) {
+			cout << "Already at " << curLevel << ' ' << SharedGlobals::runlevel_names[curLevel] << "\n\t";
+			for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++)
+				cout << i << ' ' << SharedGlobals::runlevel_names[i] << ", ";
+			cout << endl;
+			return;
+		}
+	}
+	if(sim::config.tgtRunlevel>SharedGlobals::RUNNING && curLevel<=SharedGlobals::RUNNING)
+		globals->signalShutdown();
+}
+bool Simulator::cmdSet(const std::vector<std::string>& args) {
+	if(args.size()==0 || args[0]=="set" && args.size()==1) {
+		plist::filteredDisplay(cout,sim::config,"^[^.].*",REG_EXTENDED,3);
+		return false;
+	}
+	string arg;
+	for(unsigned int i=(args[0]=="set"?1:0); i<args.size(); i++) {
+		arg+=args[i];
+		if(i!=args.size()-1)
+			arg+=" ";
+	}
+	if(arg.rfind("=")==string::npos) {
+		plist::ObjectBase* ob=sim::config.resolveEntry(arg);
+		if(ob==NULL) {
+			cout << "'" << arg << "' is unknown" << endl;
+			return false;
+		}
+		plist::filteredDisplay(cout,*ob,"^[^.].*",REG_EXTENDED,3);
+	} else {
+		string value=string_util::trim(arg.substr(arg.find("=")+1));
+		string key=string_util::trim(arg.substr(0,arg.find("=")));
+		plist::ObjectBase* ob=sim::config.resolveEntry(key);
+		if(ob==NULL) {
+			cout << "'" << key << "' is unknown" << endl;
+			return false;
+		}
+		if(plist::PrimitiveBase* pbp=dynamic_cast<plist::PrimitiveBase*>(ob)) {
+			try {
+				pbp->set(value);
+				return true;
+			} catch(const XMLLoadSave::bad_format& bf) {
+				cout << "'" << value << "' is a bad value for '" << key << "'" << endl;
+				cout << bf.what() << endl;
+			} catch(const std::exception& e) {
+				cout << "An exception occured: " << e.what() << endl;
+			}
+		} else {
+			cout << "Cannot assign to a dictionary" << endl;
+			return false;
+		}
+	}
+	return false; //exception occurred
+}
+void Simulator::cmdRun(const std::vector<std::string>& args, bool isRelative) {
+	if(args.size()<=1) {
+		cout << "runfor/runto requires an argument" << endl;
+		return;
+	}
+	if(isRelative)
+		globals->setAutoPauseTime(get_time()+atoi(args[1].c_str()));
+	else
+		globals->setAutoPauseTime(atoi(args[1].c_str()));
+	if(globals->timeScale==0)
+		globals->timeScale=runSpeed;
+}
+void Simulator::cmdRun(const std::vector<std::string>& args) {
+	if(args.size()<=1) {
+		if(globals->timeScale!=0) {
+			cout << "Already running" << endl;
+			return;
+		}
+		globals->timeScale=runSpeed;
+	} else {
+		float speed=atof(args[1].c_str());
+		if(speed!=0)
+			runSpeed=speed;
+		globals->timeScale=speed;
+	}
+}
+void Simulator::cmdPause(const std::vector<std::string>& args) {
+	if(globals->timeScale==0) {
+		if(find(args.begin(),args.end(),"quiet")==args.end())
+			cout << "Already paused" << endl;
+		return;
+	}
+	runSpeed=globals->timeScale;
+	globals->timeScale=0;
+}
+void Simulator::cmdHelp(const std::vector<std::string>& args) {
+	map<string,string> syntax;
+	syntax["load"]="[file]";
+	syntax["save"]="[file]";
+	syntax["runlevel"]="[";
+	for(unsigned int i=0; i<SharedGlobals::NUM_RUNLEVELS; i++) {
+		stringstream ss;
+		ss << i << "|" << SharedGlobals::runlevel_names[i];
+		if(i!=SharedGlobals::NUM_RUNLEVELS-1)
+			ss << " | ";
+		syntax["runlevel"]+=ss.str();
+	}
+	syntax["runlevel"]+="]";
+	syntax["get_time"]="";
+	syntax["set"]="[var=value]";
+	syntax["runto"]="time";
+	syntax["runfor"]="time";
+	syntax["run"]="[speed]";
+	syntax["pause"]="";
+	syntax["step"]="[camera|sensor|timer|motion]";
+	syntax["status"]="[Main|Motion|SoundPlay|Simulator|all]*";
+	syntax["advance"]=syntax["freeze"]=syntax["unfreeze"]="[camera|sensors|all]*";
+	syntax["reset"]="[camera|sensors|all]";
+	syntax["new"]="type [name]";
+	syntax["delete"]="name";
+	
+	map<string,string> help;
+	
+	help["load"]="Load HAL configuration from file; if file unspecified, uses last specified file ('hal-$MODEL.plist' by default).\n"
+		"Note that these files are human-readable XML (with comments!), and you can remove values to specify only a subset of settings.";
+	
+	help["save"]="Save HAL configuration to file; if file unspecified, uses last specified file ('hal-$MODEL.plist' by default).\n"
+		"Note that these files are human-readable XML (with comments!), and you can remove values to specify only a subset of settings.";
+	
+	help["runlevel"]="You can specify a runlevel to move to, or if unspecified, the next one.\n"
+		"You can only move forward runlevels, not backward.  Usually you'll only need RUNNING, "
+		"unless you are debugging startup/shutdown code or the Tekkotsu itself.";
+	
+	help["get_time"]="Displays the simulator time.";
+	
+	help["set"]="Sets HAL configuration variables.  Without any arguments, displays all available variables and their current values.\n"
+		"Type 'help set <variable>' to get more information about a particular variable.";
+	
+	help["runto"]="Triggers 'run' until the simulator time reaches the specified value and then pauses.";
+	
+	help["runfor"]="Triggers 'run' until the simulator time has moved by the specified number of milliseconds, then pauses.";
+	
+	help["run"]="Resets speed to last non-zero value (i.e. value prior to last 'pause'), can override by passing a new value as argument.  Can be abbreviated 'r'.";
+	
+	help["pause"]="Equivalent to 'set Speed=0'.  Can be abbreviated 'p'.  Stops the flow of time within the simulator.";
+	
+	help["step"]="Runs at \"full\" speed until the next indicated time frame, or the next available frame if no type is specified.\n"
+		"See 'status' for available frames.";
+	
+	help["status"]="Displays a status report regarding current time, upcoming keyframes, and semaphore usage.  Specify one or more processes to get more in-depth, per-process status reports.";
+	
+	help["advance"]="Sends the next frame for the specified queue(s) in their listed order (can be listed more than once).\n"
+		"Disregards timestamp information, and doesn't advance time, unlike 'step' command.  No arguments and \"all\" is the same as \"sensors camera\".";
+	
+	help["freeze"]="Equivalent to 'set queue.Frozen=true'.\n"
+		"Stops sending frames from the specified queue(s), but still allows time to move (unlike 'pause').  No arguments is the same as \"all\".  See 'advance' and 'unfreeze'.";
+	
+	help["unfreeze"]="Equivalent to 'set queue.Frozen=false'.\n"
+		"Begin sending frames from the specified queue(s) again.  Timestamps for the file listing are offset by the time spent frozen minus frames advanced so the queue(s) will continue from their current position.  No arguments is the same as \"all\".";
+	
+	help["reset"]="Moves the specified data queue(s) back to the first entry in their list.";
+	
+	help["new"]="Creates a new driver or communication port instance.\n  Driver types are:";
+	set<string> driverNames;
+	DeviceDriver::getRegistry().getTypeNames(driverNames);
+	for(set<string>::iterator it=driverNames.begin(); it!=driverNames.end(); ++it)
+		help["new"]+=" "+*it;
+	set<string> commNames;
+	CommPort::getRegistry().getTypeNames(commNames);
+	help["new"]+="\n  Communication ports types are:";
+	for(set<string>::iterator it=commNames.begin(); it!=commNames.end(); ++it)
+		help["new"]+=" "+*it;
+	
+	help["delete"]="Remove an entry from the CommPort or Drivers list";
+		
+	if(args.size()==1) {
+		cout << "Available commands: " << endl;
+		for(map<string,string>::const_iterator it=help.begin(); it!=help.end(); ++it) {
+			cout << '\t' << it->first << " " << syntax[it->first] << endl;
+		}
+		cout << "type 'help <command>' for more information" << endl;
+	} else {
+		if(help.find(args[1])==help.end()) {
+			cout << "The command '"<< args[1] << "' was not found" << endl;
+			return;
+		}
+		if(args.size()==2) {
+			cout << args[1] << " " << syntax[args[1]] << endl;
+			cout << help[args[1]] << endl;
+		} else {
+			if(args[1]=="set") {
+				plist::ObjectBase* ob=sim::config.resolveEntry(args[2]);
+				if(ob==NULL) {
+					cout << "'" << args[2] << "' is unknown" << endl;
+					return;
+				}
+				size_t n=args[2].rfind('.');
+				if(n==string::npos)
+					cout << sim::config.getComment(args[2]) << endl;
+				else {
+					ob=sim::config.resolveEntry(args[2].substr(0,n));
+					if(const plist::Dictionary * dict=dynamic_cast<const plist::Dictionary*>(ob))
+						cout << dict->getComment(args[2].substr(n+1)) << endl;
+					else
+						cout << "'" << args[2].substr(0,n) << "' is not a dictionary" << endl;
+				}
+			} else {
+				cout << args[1] << " " << syntax[args[1]] << endl;
+				cout << help[args[1]] << endl;
+			}
+		}
+	}
+}
+void Simulator::cmdStep(const std::vector<std::string>& args) {
+	if(args.size()<=1) {
+		if(globals->timeScale!=0)
+			globals->timeScale=0;
+		step=STEP_NONE;
+		incrementTime();
+		return;
+	}
+	if(args.size()>2) {
+		cout << args[0] << " takes 0 or 1 arguments; " << args.size()-1 << " supplied" << endl;
+		return;
+	}
+	if(args[1]=="camera")
+		step=STEP_CAMERA;
+	else if(args[1]=="sensor" || args[1]=="sensors")
+		step=STEP_SENSOR;
+	else if(args[1]=="timer")
+		step=STEP_TIMER;
+	else if(args[1]=="motion")
+		step=STEP_MOTION;
+	else {
+		cout << args[1] << " is not a valid argument for 'step'.  Type 'help step'." << endl;
+		return;
+	}
+	if(step==STEP_CAMERA && vision.frozen && !vision.heartbeat) {
+		cout << "Camera queue is frozen and has no heartbeat, cannot step (use 'advance' instead)" << endl;
+		step=STEP_NONE;
+	} else if(step==STEP_SENSOR && sensors.frozen && !sensors.heartbeat) {
+		cout << "Sensor queue is frozen and has no heartbeat, cannot step (use 'advance' instead)" << endl;
+		step=STEP_NONE;
+	} else {
+		unsigned int steps=getNextFrame();
+		if((1<<step) & steps) { // the desired step is the next step -- just increment
+			if(globals->timeScale!=0)
+				globals->timeScale=0;
+			step=STEP_NONE;
+			incrementTime();
+		} else if(globals->timeScale!=-1)
+			globals->timeScale=-1;
+	}
+}
+void Simulator::cmdStatus(const std::vector<std::string>& args) {
+	cout << "Speed is " << static_cast<float>(globals->timeScale);
+	if(globals->timeScale<0)
+		cout << " (full speed mode: avg speed=" << ((globals->simulatorTime-fullspeedSimStart)/fullspeedWallStart.Age().Value()/1000) << "x, "
+			<< " current speed=" << (avgSimTime/avgWallTime/1000) << "x)";
+	cout << endl;
+	cout << "Current time is " << get_time() << endl;
+	unsigned int vis=vision.nextTimestamp();
+	unsigned int sen=sensors.nextTimestamp();
+	unsigned int tim=globals->getNextTimer();
+	unsigned int mot=globals->getNextMotion();
+	cout << "Next camera: ";
+	if(vis==-1U) cout << "(none)"; else {
+		if(vision.frozen)
+			cout << "Frozen@";
+		cout << vision.getDataSource()->nextName();
+		if(!vision.frozen || vision.heartbeat) {
+			if(vision.frozen && vision.heartbeat && vision.getDataSource()->nextName()!="heartbeat")
+				cout << " heartbeat";
+			cout << " scheduled at " << vis;
+		}
+	}
+	cout << endl;
+	cout << "Next sensor: ";
+	if(sen==-1U) cout << "(none)"; else {
+		if(sensors.frozen)
+			cout << "Frozen@";
+		cout << sensors.getDataSource()->nextName();
+		if(!sensors.frozen || sensors.heartbeat) {
+			if(sensors.frozen && sensors.heartbeat && sensors.getDataSource()->nextName()!="heartbeat")
+				cout << " heartbeat";
+			cout << " scheduled at " << sen;
+		}
+	}
+	cout << endl;
+	cout << "Next timer: ";
+	if(tim==-1U) cout << "(none)"; else cout << tim;
+	cout << endl;
+	cout << "Next motion: ";
+	if(mot==-1U) cout << "(none)"; else cout << mot;
+	cout << endl;
+	unsigned int semUsed=MessageQueueBase::getSemaphoreManager()->used();
+	unsigned int semMax=semUsed+MessageQueueBase::getSemaphoreManager()->available();
+	cout << "Semaphores used: " << semUsed << "/" << semMax << " (" << ((semUsed*10000+5)/semMax/10)/10.f << "%)" << endl;
+	cout << endl;
+	if(args.size()>1) {
+		SemaphoreManager::semid_t sem=statusRequest->addReadStatusListener();
+		for(unsigned int i=1; i<args.size(); ++i) {
+			RCRegion * region=new RCRegion(args[i].size()+1);
+			strncpy(region->Base(),args[i].c_str(),args[i].size()+1);
+			statusRequest->sendMessage(region);
+			region->RemoveReference();
+		}
+		//wait until they're done to put the prompt back up
+		if(sem!=statusRequest->getSemaphoreManager()->invalid()) {
+			statusRequest->getSemaphoreManager()->lower(sem,args.size()-1);
+			statusRequest->removeReadStatusListener(sem);
+		}
+		//check to see if we're included:
+		//haha, now I remember why I don't use functional programming
+		/*if(find_if(args.begin()+1,args.end(),not1(__gnu_cxx::compose1(bind2nd(ptr_fun(strcasecmp),getName().c_str()),mem_fun_ref(&string::c_str))))!=args.end())
+			statusReport(cout);*/
+		for(unsigned int i=1; i<args.size(); ++i) {
+			if(strcasecmp(args[i].c_str(),getName())==0 || strcasecmp(args[i].c_str(),"all")==0) {
+				statusReport(cout);
+				cout << endl;
+			}
+		}
+	}
+}
+void Simulator::cmdAdvance(const std::vector<std::string>& args) {
+	if(curLevel!=SharedGlobals::RUNNING) {
+		cout << args[0] << " can only be used in the RUNNING runlevel" << endl;
+		return;
+	}
+	std::string senstr="sensors";
+	std::string camstr="camera";
+	std::vector<std::string> queuenames;
+	bool isAll=false;
+	if(args.size()<=1) { // no arguments supplied, advance all
+		queuenames.push_back(senstr);
+		queuenames.push_back(camstr);
+		isAll=true;
+	}
+	for(unsigned int i=1; i<args.size(); ++i) {
+		if(args[i]==camstr)
+			queuenames.push_back(camstr);
+		else if(args[i]==senstr)
+			queuenames.push_back(senstr);
+		else if(args[i]=="all") {
+			queuenames.push_back(senstr);
+			queuenames.push_back(camstr);
+			isAll=true;
+		} else {
+			cout << "invalid argument for advance command: " << args[i] << endl;
+			return;
+		}
+	}
+	for(std::vector<std::string>::iterator it=queuenames.begin(); it!=queuenames.end(); ++it) {
+		LoadDataThread * lft=NULL;
+		MessageQueueBase* q=NULL;
+		if(*it==camstr) {
+			lft=&vision;
+			q=&(*cameraQueue);
+		} else if(*it==senstr) {
+			lft=&sensors;
+			q=&(*sensorQueue);
+		} else {
+			cout << "Simulator: internal error, invalid queue " << *it << endl;
+			return;
+		}
+		SemaphoreManager::semid_t sem=q->addReadStatusListener(); //register read status listener before sending!
+		bool sent=lft->advanceFrame(true); // send frame
+		if(!sent) { // no data in queue
+			sent=lft->heartbeat; // but there may have been a heartbeat?
+			if(!isAll) {
+				// only report empty queue if the queue was explicitly specified
+				cout << "No data in " << *it << " queue";
+				if(lft->heartbeat)
+					cout << ", sent heartbeat";
+				cout << endl;
+			}
+		}
+		if(sent)
+			q->getSemaphoreManager()->lower(sem,true); //block until we know message was read
+		q->removeReadStatusListener(sem);
+	}
+}
+void Simulator::cmdFreeze(bool v, const std::vector<std::string>& args) {
+	std::string senstr="sensors";
+	std::string camstr="camera";
+	std::set<std::string> queuenames;
+	if(args.size()<=1) {
+		queuenames.insert(camstr);
+		queuenames.insert(senstr);
+	}
+	for(unsigned int i=1; i<args.size(); ++i) {
+		if(args[i]==camstr)
+			queuenames.insert(camstr);
+		else if(args[i]==senstr)
+			queuenames.insert(senstr);
+		else if(args[i]=="all") {
+			queuenames.insert(camstr);
+			queuenames.insert(senstr);
+		} else {
+			cout << "invalid argument for freeze/unfreeze command: " << args[i] << endl;
+			return;
+		}
+	}
+	for(std::set<std::string>::iterator it=queuenames.begin(); it!=queuenames.end(); ++it) {
+		if(*it==camstr)
+			vision.frozen=v;
+		else if(*it==senstr)
+			sensors.frozen=v;
+		else {
+			cout << "Simulator: internal error, invalid queue " << *it << endl;
+			return;
+		}
+	}
+}
+void Simulator::cmdReset(const std::vector<std::string>& args) {
+	std::string senstr="sensors";
+	std::string camstr="camera";
+	for(unsigned int i=1; i<args.size(); ++i) {
+		if(args[i]==camstr) {
+			if(vision.getDataSource()!=NULL)
+				vision.getDataSource()->reset();
+		} else if(args[i]==senstr) {
+			if(sensors.getDataSource()!=NULL)
+				sensors.getDataSource()->reset();
+		} else if(args[i]=="all") {
+			if(vision.getDataSource()!=NULL)
+				vision.getDataSource()->reset();
+			if(sensors.getDataSource()!=NULL)
+				sensors.getDataSource()->reset();
+		} else
+			cout << "invalid argument for reset command: " << args[i] << endl;
+	}
+}
+void Simulator::cmdNew(const std::vector<std::string>& args) {
+	set<string> driverNames;
+	DeviceDriver::getRegistry().getTypeNames(driverNames);
+	set<string> commNames;
+	CommPort::getRegistry().getTypeNames(commNames);
+	if(args.size()<2) {
+		cerr << "Must specify type to instantiate:\n";
+		cerr << "  Communication Ports:";
+		for(set<string>::iterator it=commNames.begin(); it!=commNames.end(); ++it)
+			cerr << ' ' << *it;
+		cerr << endl;
+		cerr << "  Device Drivers:";
+		for(set<string>::iterator it=driverNames.begin(); it!=driverNames.end(); ++it)
+			cerr << ' ' << *it;
+		cerr << endl;
+		return;
+	}
+	std::string type = args[1];
+	std::string name = (args.size()>2) ? args[2] : args[1];
+	try {
+		if(driverNames.find(type)!=driverNames.end()) {
+			DeviceDriver * d = DeviceDriver::getRegistry().create(type,name);
+			if(d==NULL) {
+				cerr << "Error instantiating " << type << " (instance with same name already exists?)" << endl;
+				return;
+			}
+		} else if(commNames.find(type)!=commNames.end()) {
+			CommPort * c = CommPort::getRegistry().create(type,name);
+			if(c==NULL) {
+				cerr << "Error instantiating " << type << " (instance with same name already exists?)" << endl;
+				return;
+			}
+		} else {
+			cerr << "'" << type << "' is not a valid type for instantiation.  Please choose one of:\n";
+			cerr << "  Communication Ports:";
+			for(set<string>::iterator it=commNames.begin(); it!=commNames.end(); ++it)
+				cerr << ' ' << *it;
+			cerr << endl;
+			cerr << "  Device Drivers:";
+			for(set<string>::iterator it=driverNames.begin(); it!=driverNames.end(); ++it)
+				cerr << ' ' << *it;
+			cerr << endl;
+		}
+	} catch(const std::exception& e) {
+		cout << "An exception occured during construction of "<<type<<": " << e.what() << endl;
+	} catch(...) {
+		cout << "An exception occured during construction of "<<type << endl;
+	}
+}
+
+void Simulator::cmdDelete(const std::vector<std::string>& args) {
+	if(args.size()<2) {
+		cerr << "Must specify instance to delete:\n";
+		cerr << "  Communication Ports:";
+		for(CommPort::registry_t::const_iterator it=CommPort::getRegistry().begin(); it!=CommPort::getRegistry().end(); ++it)
+			cerr << ' ' << it->first;
+		cerr << endl;
+		cerr << "  Device Drivers:";
+		for(DeviceDriver::registry_t::const_iterator it=DeviceDriver::getRegistry().begin(); it!=DeviceDriver::getRegistry().end(); ++it)
+			cerr << ' ' << it->first;
+		cerr << endl;
+		return;
+	}
+	if(DeviceDriver::getRegistry().getInstance(args[1])!=NULL) {
+		if(!DeviceDriver::getRegistry().destroy(args[1]))
+			cerr << "Could not delete driver named '" << args[1] << "'" << endl;
+	} else if(CommPort::getRegistry().getInstance(args[1])!=NULL) {
+		if(!CommPort::getRegistry().destroy(args[1]))
+			cerr << "Could not delete comm port named '" << args[1] << "'" << endl;
+	} else {
+		cerr << "Could not find driver to delete named '" << args[1] << "'" << endl;
+		return;
+	}
+}
+
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.13 $
+ * $State: Exp $
+ * $Date: 2007/11/19 21:00:41 $
+ */
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/Simulator.h ./local/tekkotsu/Simulator.h
--- ../Tekkotsu_3.0/local/tekkotsu/Simulator.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/Simulator.h	2007-11-19 16:00:42.000000000 -0500
@@ -0,0 +1,193 @@
+//-*-c++-*-
+#ifndef INCLUDED_Simulator_h_
+#define INCLUDED_Simulator_h_
+
+#include "Process.h"
+#include "sim.h"
+#include "IPC/SharedObject.h"
+#include "IPC/MessageQueueStatusThread.h"
+#include "SharedGlobals.h"
+#include "Shared/plist.h"
+#include "Shared/RobotInfo.h"
+#include "Shared/debuget.h"
+#include "local/LoadDataThread.h"
+#include "local/MotionHook.h"
+#include <set>
+
+class MessageReceiver;
+
+class Simulator : public Process,  public plist::PrimitiveListener, public plist::CollectionListener, public MessageQueueStatusThread::StatusListener {
+public:
+	//! constructor
+	Simulator();
+	
+	~Simulator();
+
+	virtual void DoStart();
+	virtual void DoStop();
+	virtual void run();
+	
+	static const char * getClassName() { return "Simulator"; }
+	static ProcessID::ProcessID_t getID() { return ProcessID::SimulatorProcess; }
+	
+	static const char * getCameraQueueID() { return "CameraData"; }
+	static const char * getSensorQueueID() { return "SensorData"; }
+	static const char * getTimerWakeupID() { return "TimerWakeup"; }
+	static const char * getMotionWakeupID() { return "MotionWakeup"; }
+	static const char * getStatusRequestID() { return "StatusRequest"; }
+	static const char * getCommandQueueID() { return "CommandQueue"; }
+	
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	virtual void plistCollectionEntryAdded(plist::Collection& col, plist::ObjectBase& primitive);
+	virtual void plistCollectionEntryRemoved(plist::Collection& col, plist::ObjectBase& primitive);
+	virtual void plistCollectionEntriesChanged(plist::Collection& col);
+		
+	virtual void messagesRead(MessageQueueBase& mq, unsigned int n);
+	
+	static void sendCommand(const std::string& cmd);
+	
+	//! Registers the MotionHook to have its motionCheck() called following each motion update.
+	/*! Responsibility for memory (de)allocation is NOT assumed by registration. */
+	static void registerMotionHook(MotionHook& h) {
+		MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+		theSim->motionHooks.insert(&h);
+	}
+	
+	//! Removes the MotionHook from the list, no longer receives any notifications
+	/*! Responsibility for memory (de)allocation is NOT assumed by registration, so this doesn't affect @a h directly. */
+	static void deregisterMotionHook(MotionHook& h) {
+		MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+		theSim->motionHooks.erase(&h);
+	}
+	
+	static void clearMotionHooks() {
+		MarkScope l(theSim ? dynamic_cast<Resource&>(theSim->simLock) : ::emptyResource);
+		theSim->motionHooks.clear();
+	}
+	
+	static void setMotionStarting();
+	static void setMotionStopping();
+	static void updateMotion(const float outputs[][NumOutputs]);
+	static void setMotionLeavingRealtime(bool isFullSpeed);
+	static void setMotionEnteringRealtime();
+	
+protected:
+	static void replaceEntry(const std::string& name, plist::Dictionary& d, const std::string& comment);
+	
+	//! subscribed by Simulator to message queue's send; ensures that SharedGlobals::MotionSimConfig::frameNumber stays in sync with the message serial number
+	class FrameCounter : public MessageQueueBase::MessageFilter {
+	public:
+		virtual bool filterSendRequest(RCRegion* /*rcr*/) {
+			globals->motion.frameNumber++;
+			//ASSERT(globals->motion.frameNumber==LoadFileThread::recoverSN(rcr),"globals->motion.frameNumber does not match frame number sent! (" << globals->motion.frameNumber << " vs " << LoadDataThread::recoverSN(rcr));
+			return true;
+		}
+	} frameCounter;
+	
+	class CommandThread : public Thread {
+	public:
+		CommandThread() : Thread(), initThread(NULL) {}
+		virtual void * run();
+		virtual void cancelled();
+		virtual void runInitThread(Thread& th);
+		virtual void abortInitThread() { if(initThread!=NULL) initThread->stop(); }
+	protected:
+		Thread* initThread;
+	private:
+		CommandThread(const CommandThread&); //!< do not call
+		CommandThread& operator=(const CommandThread&); //!< do not call
+	} cmdThread;
+	
+	enum step_t {
+		STEP_NONE,
+		STEP_CAMERA,
+		STEP_SENSOR,
+		STEP_TIMER,
+		STEP_MOTION
+	};
+	
+	void incrementTime();
+	void sendTimerWakeup();
+	unsigned int getNextFrame();
+	void resetSpeedMode();
+	
+	void processRunlevel(SharedGlobals::runlevel_t curRunLevel);
+	bool processCommand(const std::string& line, bool addToHistory); //!< process an individual command
+	static bool gotCommand(RCRegion* msg); //!< for commands coming from other processes via #commandQueue and #commandrecv
+	static bool gotMotion(RCRegion* msg); //!< when running in multi-process mode, receives output value updates from motion process
+	
+	void cmdQuit(const std::vector<std::string>& args);
+	void cmdLoad(const std::vector<std::string>& args);
+	void cmdSave(const std::vector<std::string>& args);
+	void cmdRunlevel(const std::vector<std::string>& args);
+	bool cmdSet(const std::vector<std::string>& args);
+	void cmdRun(const std::vector<std::string>& args, bool isRelative);
+	void cmdRun(const std::vector<std::string>& args);
+	void cmdPause(const std::vector<std::string>& args);
+	void cmdHelp(const std::vector<std::string>& args);
+	void cmdStep(const std::vector<std::string>& args);
+	void cmdStatus(const std::vector<std::string>& args);
+	void cmdAdvance(const std::vector<std::string>& args);
+	void cmdFreeze(bool v, const std::vector<std::string>& args);
+	void cmdReset(const std::vector<std::string>& args);
+	void cmdNew(const std::vector<std::string>& args);
+	void cmdDelete(const std::vector<std::string>& args);
+	
+	SharedObject<sim::CameraQueue_t> cameraQueue;
+	SharedObject<sim::SensorQueue_t> sensorQueue;
+	SharedObject<sim::TimerWakeup_t> timerWakeup;
+	SharedObject<sim::MotionWakeup_t> motionWakeup;
+	SharedObject<sim::StatusRequest_t> statusRequest;
+	SharedObject<sim::EventQueue_t> events;
+	SharedObject<sim::MotionOutput_t> motionout;
+	typedef MessageQueue<10> CommandQueue_t;
+	SharedObject<CommandQueue_t> commandQueue;
+	
+	MessageQueueStatusThread cameraStatus;
+	MessageQueueStatusThread sensorStatus;
+	MessageQueueStatusThread timerStatus;
+	MessageQueueStatusThread motionStatus;
+	MessageQueueStatusThread eventsStatus;
+
+	MessageReceiver * commandrecv;
+	MessageReceiver * motionrecv;
+	
+protected:
+	LoadDataThread vision;
+	LoadDataThread sensors;
+	static Simulator* theSim;
+	std::set<unsigned int> frameTimes;
+	float runSpeed;
+	float lastTimeScale;
+	step_t step;
+	unsigned int waitingSteps;
+	SharedGlobals::runlevel_t curLevel;
+	
+	static std::set<MotionHook*> motionHooks;
+	
+	TimeET fullspeedWallStart; //!< "real" wall-clock time that full-speed mode was entered
+	unsigned int fullspeedSimStart; //!< simulator time at which full-speed mode was entered
+	TimeET lastFrameWallStart; //!< "real" wall-clock time that processing started on last frame (only valid in full-speed mode)
+	float avgWallTime; //!< running average of frame processing time
+	float avgSimTime; //!< running average of frame increments
+	static const float avgSpeedupGamma; //!< gamma parameter for calculating running average in #avgWallTime and #avgSimTime
+	
+	ThreadNS::Lock simLock;
+
+private:
+	Simulator(const Simulator&); //!< don't call (copy constructor)
+	Simulator& operator=(const Simulator&); //!< don't call (assignment operator)
+};
+
+/*! @file
+ * @brief Defines Simulator, which DESCRIPTION
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.7 $
+ * $State: Exp $
+ * $Date: 2007/11/19 21:00:42 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/SoundPlay.cc ./local/tekkotsu/SoundPlay.cc
--- ../Tekkotsu_3.0/local/tekkotsu/SoundPlay.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/SoundPlay.cc	2007-11-10 17:58:13.000000000 -0500
@@ -0,0 +1,91 @@
+#include "SoundPlay.h"
+#include "Simulator.h"
+#include "SharedGlobals.h"
+#include "Main.h"
+#include "IPC/MessageReceiver.h"
+#include "IPC/RegionRegistry.h"
+#include "Events/EventRouter.h"
+#include "SimConfig.h"
+
+SoundPlayThread * SoundPlay::player;
+
+SoundPlay::SoundPlay()
+	: Process(getID(),getClassName()),
+		requests(ipc_setup->registerRegion(getSoundPlayID(),sizeof(sim::SoundPlayQueue_t))),
+		events(ipc_setup->registerRegion(Main::getEventsID(),sizeof(sim::EventQueue_t))),
+		statusRequest(ipc_setup->registerRegion(Simulator::getStatusRequestID(),sizeof(sim::StatusRequest_t))),
+		soundmanager(ipc_setup->registerRegion(getSoundManagerID(),sizeof(SoundManager))),
+		soundProf(ipc_setup->registerRegion(getSoundProfilerID(),sizeof(soundProfiler_t))),
+		etrans(NULL), sndrecv(NULL), statusrecv(NULL)
+{
+	new (&(*requests)) sim::SoundPlayQueue_t;
+	new (&(*soundmanager)) SoundManager;
+	new (&(*soundProfiler)) soundProfiler_t;
+	sndman=&(*soundmanager);
+	::soundProfiler=&(*soundProf);
+}
+
+SoundPlay::~SoundPlay() {
+	delete etrans;
+	etrans=NULL;
+	MotionManager::setTranslator(NULL);
+}
+
+void SoundPlay::DoStart() {
+	Process::DoStart();
+	//These are constructed by other processes, so need to wait
+	//until the construction runlevel is complete before we access them
+	if(!sim::config.multiprocess) {
+		// don't use our own etrans here, because erouter will delete it for us, don't want a double-delete in our destructor...
+		EventTranslator * forwardTrans = new IPCEventTranslator(*events);
+		forwardTrans->setTrapEventValue(true);
+		erouter->setForwardingAgent(getID(),forwardTrans);
+	} else {
+		etrans=new IPCEventTranslator(*events);
+		MotionManager::setTranslator(etrans); //although SoundPlay shouldn't use any motions...
+
+		// Set up Event Translator to trap and send events to main process
+		//send everything over except erouter events
+		for(unsigned int i=0; i<EventBase::numEGIDs; i++)
+			if(i!=EventBase::erouterEGID)
+				erouter->addTrapper(etrans,static_cast<EventBase::EventGeneratorID_t>(i));
+	}
+	
+	player = new SoundPlayThread;
+	player->start();
+	sndrecv=new MessageReceiver(*requests,gotSnd);
+	statusrecv=new MessageReceiver(*statusRequest,statusReport);
+}
+
+void SoundPlay::DoStop() {
+	sndrecv->finish();
+	statusrecv->finish();
+	
+	delete sndrecv;
+	sndrecv=NULL;
+	delete statusrecv;
+	statusrecv=NULL;
+	delete player;
+	player=NULL;
+	
+	sndman->stopPlay();
+	if(sim::config.multiprocess) {
+		erouter->removeTrapper(etrans);
+		delete etrans;
+		etrans=NULL;
+	}
+	Process::DoStop();
+}
+
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/11/10 22:58:13 $
+ */
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/SoundPlay.h ./local/tekkotsu/SoundPlay.h
--- ../Tekkotsu_3.0/local/tekkotsu/SoundPlay.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/SoundPlay.h	2007-06-14 11:37:42.000000000 -0400
@@ -0,0 +1,61 @@
+//-*-c++-*-
+#ifndef INCLUDED_SoundPlay_h_
+#define INCLUDED_SoundPlay_h_
+
+#include "Process.h"
+#include "sim.h"
+#include "IPC/ProcessID.h"
+#include "IPC/SharedObject.h"
+#include "SharedGlobals.h"
+#include "Sound/SoundManager.h"
+#include "Shared/Profiler.h"
+#include "local/SoundPlayThread.h"
+
+class SoundPlay : public Process {
+public:
+	//! constructor
+	SoundPlay();
+	//! destructor
+	~SoundPlay();
+
+	virtual void DoStart();
+	virtual void DoStop();
+
+	static const char * getClassName() { return "SoundPlay"; }
+	static ProcessID::ProcessID_t getID() { return ProcessID::SoundProcess; }
+	
+	static const char * getSoundPlayID() { return "Sounds"; }
+	static const char * getSoundManagerID() { return "SoundManager"; }
+	static const char * getSoundProfilerID() { return "SoundProfiler"; }
+
+protected:
+	SharedObject<sim::SoundPlayQueue_t> requests;
+	SharedObject<sim::EventQueue_t> events;
+	SharedObject<sim::StatusRequest_t> statusRequest;
+	SharedObject<SoundManager> soundmanager;
+	SharedObject<soundProfiler_t> soundProf;
+	
+	static SoundPlayThread * player;
+	
+	IPCEventTranslator * etrans;
+	class MessageReceiver * sndrecv;
+	class MessageReceiver * statusrecv;
+	static bool gotSnd(RCRegion* msg) { sndman->ProcessMsg(msg); player->reset(); return true; }
+	
+private:
+	SoundPlay(const SoundPlay&); //!< don't call (copy constructor)
+	SoundPlay& operator=(const SoundPlay&); //!< don't call (assignment operator)
+};
+
+/*! @file
+ * @brief Defines SoundPlay, which DESCRIPTION
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/14 15:37:42 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/TimerExecThread.cc ./local/tekkotsu/TimerExecThread.cc
--- ../Tekkotsu_3.0/local/tekkotsu/TimerExecThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/TimerExecThread.cc	2007-10-12 12:55:05.000000000 -0400
@@ -0,0 +1,69 @@
+#include "TimerExecThread.h"
+#include "SharedGlobals.h"
+#include "Shared/ProjectInterface.h"
+#include "Shared/MarkScope.h"
+#include "Shared/get_time.h"
+#include "Events/EventRouter.h"
+
+//better to put this here instead of the header
+using namespace std; 
+
+
+void TimerExecThread::reset() {
+	if((globals->getNextTimer()==-1U || globals->timeScale<=0) && isStarted())
+		stop();
+	else if(globals->timeScale>0 && !isStarted())
+		start();
+	else if(isStarted()) {
+		interrupt();
+	}
+}
+
+long TimerExecThread::calcSleepTime() {
+	startTime.Set();
+	return static_cast<long>((globals->getNextTimer()-get_time())/globals->timeScale);
+}
+
+bool TimerExecThread::launched() {
+	if(globals->timeScale<=0)
+		return false;
+	delay=calcSleepTime();
+	return PollThread::launched();
+}
+
+bool TimerExecThread::poll() {
+	MarkScope bl(behaviorLock);
+	//cout << "Poll at " << get_time() << " next timer " << globals->getNextTimer() << " (vs. " << erouter->getNextTimer() << ")" << endl;
+	//this happens normally:
+	//ASSERT(get_time()>=globals->getNextTimer(),"TimerExecThread::poll() early (time="<<get_time()<< " vs. nextTimer=" <<globals->getNextTimer()<<")");
+	try {
+		erouter->processTimers();
+	} catch(const std::exception& ex) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",&ex))
+			throw;
+	} catch(...) {
+		if(!ProjectInterface::uncaughtException(__FILE__,__LINE__,"Occurred during timer processing",NULL))
+			throw;
+	}
+	globals->setNextTimer(erouter->getNextTimer());
+	if(globals->getNextTimer()==-1U)
+		return false;
+	period=calcSleepTime();
+	return true;
+}
+
+void TimerExecThread::interrupted() {
+	delay=calcSleepTime();
+}
+
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:55:05 $
+ */
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/TimerExecThread.h ./local/tekkotsu/TimerExecThread.h
--- ../Tekkotsu_3.0/local/tekkotsu/TimerExecThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/TimerExecThread.h	2007-06-14 11:37:42.000000000 -0400
@@ -0,0 +1,34 @@
+//-*-c++-*-
+#ifndef INCLUDED_TimerExecThread_h_
+#define INCLUDED_TimerExecThread_h_
+
+#include "IPC/PollThread.h"
+#include "Shared/Resource.h"
+
+//! executes EventRouter::processTimers() as necessary (allows timers to work without any other vision or sensor processing)
+class TimerExecThread : public PollThread {
+public:
+	explicit TimerExecThread(Resource& bl, bool autoStart=true) : PollThread(), behaviorLock(bl) { if(autoStart) reset(); }
+	virtual void reset(); //!< starts and stops thread as needed, or interrupts thread to reset sleep time if already running
+	
+protected:
+	virtual long calcSleepTime(); //!< returns the time in milliseconds to sleep until the next timer; resets PollThread::startTime
+	virtual bool launched();
+	virtual bool poll();
+	virtual void interrupted();
+
+	Resource& behaviorLock; //!< a lock on behaviors which should be obtained before processing timer events
+};
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.1 $
+ * $State: Exp $
+ * $Date: 2007/06/14 15:37:42 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/sim.cc ./local/tekkotsu/sim.cc
--- ../Tekkotsu_3.0/local/tekkotsu/sim.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/sim.cc	2007-11-21 18:47:53.000000000 -0500
@@ -0,0 +1,599 @@
+#include "sim.h"
+#include "Main.h"
+#include "Motion.h"
+#include "SoundPlay.h"
+#include "Simulator.h"
+#include "SharedGlobals.h"
+#include "SimConfig.h"
+#include "local/DataSource.h"
+#include "IPC/SharedObject.h"
+#include "IPC/RegionRegistry.h"
+#include "Shared/Config.h"
+#include "Shared/string_util.h"
+#include "Shared/StackTrace.h"
+#include "Shared/zignor.h"
+#include "Shared/RobotInfo.h"
+#include "IPC/SemaphoreManager.h"
+#include "Events/EventRouter.h"
+#include <iostream>
+#include <sstream>
+#include <iomanip>
+#include <sys/ipc.h>
+#include <signal.h>
+#include <unistd.h>
+#include <sys/wait.h>
+#include <sys/stat.h>
+#include <errno.h>
+#include <pwd.h>
+
+#ifndef DISABLE_READLINE
+#  include <readline/readline.h>
+#endif
+
+#include "Events/EventBase.h"
+#include "Events/LocomotionEvent.h"
+#include "Events/TextMsgEvent.h"
+#include "Events/VisionObjectEvent.h"
+
+#ifndef TEKKOTSU_SHM_STYLE
+#  error TEKKOTSU_SHM_STYLE unset!
+#endif
+
+using namespace std;
+
+//declare explicit instances of the NamedEnumerations we're using
+//(cuts down on some pretty significant binary size / debugging symbol bloat)
+template<> std::map<std::string,SharedGlobals::runlevel_t> plist::NamedEnumeration<SharedGlobals::runlevel_t>::namesToVals = std::map<std::string,SharedGlobals::runlevel_t>();
+template<> std::map<SharedGlobals::runlevel_t,std::string> plist::NamedEnumeration<SharedGlobals::runlevel_t>::valsToNames = std::map<SharedGlobals::runlevel_t,std::string>();
+
+const char * const sim::usage=
+"[-h|--help] [-c|--config config-file] [cmd1 cmd2 ...]\n"
+"Commands passed as arguments are commonly of the form var=val, but can\n"
+"also be any valid simulator command, such as 'freeze'.  If you wish to\n"
+"pass a multi-word command, encase the command in quotes.";
+	
+//only true for the first process -- children should set this to false when they fork
+bool sim::original=true;
+	
+SimConfig sim::config;
+vector<string> sim::cmdlineArgs;
+pid_t sim::child=static_cast<pid_t>(-1);
+vector<Thread*> sim::primaries;
+sim::ConfigErrorCheck sim::cfgCheck;
+	
+/* Although I generally dislike the "can't have main function without a class declaration" style of java,
+ * sometimes it does come in handy.  See the class notes for sim for more information. */
+int main(int argc, const char* argv[]) {
+	
+	//This should match the ID of the process sent to manage_process by sim::run()
+	// *must* be done before we create any shared regions to provide proper reference counting
+	ProcessID::setID(ProcessID::SimulatorProcess);
+			
+	//initialize some threading globals
+	Thread::initMainThread();
+	
+#if TEKKOTSU_SHM_STYLE==POSIX_SHM
+#ifndef USE_UNBACKED_SHM
+	//append username to shared memory root avoid permission denied
+	struct passwd * pw=getpwuid(getuid());
+	if(pw!=NULL) {
+		if(RCRegion::shmRoot[RCRegion::shmRoot.size()-1]=='/') {
+			RCRegion::shmRoot[RCRegion::shmRoot.size()-1]='-';
+			RCRegion::shmRoot+=pw->pw_name;
+			RCRegion::shmRoot+='/';
+		} else {
+			RCRegion::shmRoot+=pw->pw_name;
+		}
+	}
+#endif
+#elif TEKKOTSU_SHM_STYLE==NO_SHM
+	sim::cfgCheck.holdMultiprocess();
+#endif
+
+	{
+		sim s;
+		if(!s.processCommandLine(argc,argv))
+			return 2;
+		//now the real meat begins
+		if(!s.run()) //when this eventually returns, we're done (and all our children forks as well)
+			return 1;
+		return 0;
+	}
+}
+	
+sim::sim() :
+	mutexSemMgr(),
+	glob(),
+	subj()
+{
+	//what's the granularity of usleep on this platform?
+	MutexLockBase::usleep_granularity=measure_usleep_cost();
+	//use our own custom get_time routine
+	project_get_time::get_time_callback=&sim_get_time;
+	project_get_time::get_timeScale_callback=&sim_getTimeScale;
+		
+	ProjectInterface::sendCommand=Simulator::sendCommand;
+		
+	//setup signal handlers
+	signal(SIGHUP, handle_signal);
+	signal(SIGINT, handle_signal);
+	signal(SIGQUIT, handle_signal);
+	signal(SIGILL, handle_signal);
+	signal(SIGABRT, handle_signal);
+	signal(SIGFPE, handle_signal);
+	signal(SIGBUS, handle_signal);
+	signal(SIGSEGV, handle_signal);
+	signal(SIGSYS, handle_signal);
+	signal(SIGPIPE, handle_signal);
+	signal(SIGTERM, handle_signal);
+	atexit(handle_exit);
+		
+#if TEKKOTSU_SHM_STYLE!=NO_SHM
+	//Set up mutex's semaphore manager
+	MutexLockBase::setSemaphoreManager(&(*mutexSemMgr));
+#endif
+	//Set up MessageQueue's semaphore manager
+	MessageQueueBase::setSemaphoreManager(&(*mutexSemMgr));
+	
+	//Set up shared global parameters -- e.g. clock and runlevel info
+	globals = &(*glob);
+	sim::config.addEntry("WaitForSensors",globals->waitForSensors,"If true, wait for initial sensor readings before triggering the startup behavior or starting the motion polling thread.  On some platforms, sensed output values can be used to initialize output positions.  On others, you may be unable to get any feedback, or can only expect feedback if the robot was left running and the executable is reconnecting.");
+	sim::config.addEntry("Speed",globals->timeScale,"The speed at which to run the simulation, as a multiple of \"real-time\".\nFor example, '1' is normal, '0.5' is half-speed, '0' is paused.\nAny negative value requests non-realtime mode, where the clock is moved as fast as processing (or manual control) allows.");
+	globals->simulatorTime=sim::config.initSimTime;
+	sim::config.addEntry("Motion",globals->motion,"Parameters for motion simulation");
+	DataSource::setOutputTracker(globals->motion.providedOutputs);
+		
+	//Set up the subject registration area
+	ipc_setup = &(*subj);
+		
+	//everyone uses config and erouter, might as well set it up here
+	::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;
+	}
+	if(::config->loadFile("config/sim_ovrd.xml")==0)
+		if(::config->loadFile("config/sim_ovrd.cfg")!=0)
+			std::cerr << "Successfully imported settings from old-format simulator.cfg" << std::endl;
+	::erouter = new EventRouter;
+	
+	//we won't have sensor values yet, but the system clock is good enough
+	if(::config->main.seed_rng) {
+		struct timeval tp;
+		gettimeofday(&tp,NULL);
+		tp.tv_sec+=tp.tv_usec;
+		RanNormalSetSeedZig32((int*)&tp.tv_sec,tp.tv_usec);
+		
+		double t=TimeET().Value(); //current time with nanosecond resolution
+		unsigned int * tm=reinterpret_cast<unsigned int*>(&t);
+		unsigned int seed=tm[0]+tm[1];
+		cout << "RNG seed=" << seed << ", zignor seeds: " << tp.tv_sec << ',' << tp.tv_usec << endl;;
+		srand(seed);
+	} else {
+		int t=12345;
+		int u=54321;
+		RanNormalSetSeedZig32(&t,u);
+	}
+}
+	
+bool sim::processCommandLine(int argc, const char* argv[]) {
+	int i=0;
+	
+	//try to load the configuration file
+	string halconfigfile;
+	halconfigfile.append("hal-").append(RobotName).append(".plist");
+	struct stat sb;
+	if(stat(halconfigfile.c_str(),&sb)==0) {
+		if(!sim::config.loadFile(halconfigfile.c_str())) {
+			cerr << "Error loading default configuration file '" << halconfigfile << "', may be malformed." << endl;
+			return false;
+		}
+	} else {
+		// no user settings available, load the defaults
+		string defaultfile;
+		defaultfile.assign("defaults/hal-common.plist");
+		if(stat(defaultfile.c_str(),&sb)==0) {
+			if(!sim::config.loadFile(defaultfile.c_str())) {
+				cerr << "Error loading defaults file '" << defaultfile << "', may be malformed." << endl;
+				return false;
+			}
+		}
+		defaultfile.assign("defaults/hal-").append(RobotName).append(".plist");
+		if(stat(defaultfile.c_str(),&sb)==0) {
+			if(!sim::config.loadFile(defaultfile.c_str())) {
+				cerr << "Error loading defaults file '" << defaultfile << "', may be malformed." << endl;
+				return false;
+			}
+		}
+		sim::config.setLastFile(halconfigfile); // don't want to save over the defaults file
+	}
+	
+	//set the prompt from the binary name
+	/*config.cmdPrompt=argv[i];
+	if(config.cmdPrompt.rfind('/')!=string::npos)
+		config.cmdPrompt=config.cmdPrompt.substr(config.cmdPrompt.rfind('/')+1);
+	config.cmdPrompt+="> ";*/
+	
+	//set the prompt from the robot name
+	config.cmdPrompt="HAL:";
+	config.cmdPrompt.append(RobotName).append("> ");
+	
+	//now run through the rest of the arguments
+	for(i++; i<argc; i++) {
+		if(!strcmp(argv[i],"-h") || !strcmp(argv[i],"--help")) {
+			cerr << argv[0] << ": " << usage << endl;
+			return false;
+		} else if(!strcmp(argv[i],"-c") || !strcmp(argv[i],"--config")) {
+			if(!sim::config.loadFile(argv[++i]))
+				return false;
+		} else if(strchr(argv[i],'=')!=NULL) {
+			string value=string_util::trim(strchr(argv[i],'=')+1);
+			string key=string_util::trim(string(argv[i],strchr(argv[i],'=')-argv[i]));
+			plist::ObjectBase* ob=sim::config.resolveEntry(key);
+			if(ob==NULL)
+				cmdlineArgs.push_back(argv[i]); //might be a key which is added by Simulator, we'll come back to it once Simulator has been launched
+			else if(plist::PrimitiveBase* pbp=dynamic_cast<plist::PrimitiveBase*>(ob)) {
+				try {
+					pbp->set(value);
+				} catch(const XMLLoadSave::bad_format& bf) {
+					cout << "'" << value << "' is a bad value for '" << key << "'" << endl;
+					cout << bf.what() << endl;
+					return false;
+				} catch(const std::exception& e) {
+					cout << "An exception occured: " << e.what() << endl;
+					return false;
+				}
+			} else {
+				cout << "Cannot assign to a dictionary ("<<key<<")" << endl;
+				return false;
+			}
+		} else {
+			cmdlineArgs.push_back(argv[i]); //command to run in simulator
+		}
+	}
+	
+	return true;
+}
+	
+bool sim::run() {
+	// point of no return for setting multiprocess mode
+	cfgCheck.holdMultiprocess();
+	RCRegion::setMultiprocess(config.multiprocess);
+	if(!config.multiprocess) {
+		ProcessID::setIDHooks(getProcessID,setProcessID);
+		
+		//Setup wireless
+		if(wireless==NULL) { // if running single-process, may already be set up
+			wireless = new Wireless();
+			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(Socket::FLUSH_BLOCKING);
+			sout->setTextForward();
+			serr->setForward(sout);
+		}
+		
+		//Setup Kinematics
+		if(kine==NULL)
+			kine=new Kinematics();
+	}
+	
+	//this will force all of the processes to wait at the end of construction
+	//until we're done spawning all of them
+	globals->level_count[SharedGlobals::CREATED]++;
+		
+	cout << "Spawning processes..." << endl;
+	cout.setf(ios::left);
+	cout << "  Initializing runlevel " << setw(12) << SharedGlobals::runlevel_names[SharedGlobals::CONSTRUCTING] << endl;
+	cout.unsetf(ios::left);
+	if(fork_process<Main>()) ;
+	else if(fork_process<Motion>()) ;
+	else if(fork_process<SoundPlay>()) ;
+	else if(config.multiprocess)
+		manage_process<Simulator>();
+	else {
+		fork_process<Simulator>();
+		globals->level_count[SharedGlobals::CREATED]--;
+		while(primaries.size()>0) {
+			primaries.back()->join();
+			delete primaries.back();
+			primaries.pop_back();
+		}
+	}	
+	
+	//every process is going to pass through here on their way out
+	globals->level_count[SharedGlobals::DESTRUCTED]++;
+	
+	return true;
+}
+	
+sim::~sim() {
+#if TEKKOTSU_SHM_STYLE!=NO_SHM
+	MutexLockBase::setSemaphoreManager(NULL);
+#endif
+	MessageQueueBase::setSemaphoreManager(NULL);
+	globals=NULL;
+	ipc_setup=NULL;
+	
+	if(child==static_cast<pid_t>(-1)) // never got to the fork (or had an error at the fork)
+		return;
+	
+	if(original)
+		cout << ProcessID::getIDStr() << ": Waiting for children to exit..." << endl;
+	if(child!=0) {
+		int status;
+		int res=waitpid(child,&status,0);
+		if(res<0 && errno!=ECHILD)
+			perror("wait");
+		if(!WIFEXITED(status))
+			cout << ProcessID::getIDStr() << ": waiting for " << child << "..." << endl;
+		while(!WIFEXITED(status)) {
+			sleep(1);
+			res=waitpid(child,&status,0);
+			if(res<0 && errno!=ECHILD)
+				perror("wait");
+		}
+	}
+}
+	
+void sim::wait_runlevel(SharedGlobals::runlevel_t level) {
+	globals->lock.lock(ProcessID::getID());
+	globals->level_count[level]++;
+	if(globals->level_count[level]==1) {
+		cout.setf(ios::left);
+		cout << "Collecting for runlevel " << setw(12) << SharedGlobals::runlevel_names[level] << "  |=" << flush;
+		cout.unsetf(ios::left);
+	}
+	string nm=Process::getName();
+	cout << nm << '=' << flush;
+	if(globals->level_count[level]==globals->level_count[SharedGlobals::CREATED])
+		cout << "|  done" << endl;
+	globals->lock.unlock();
+	while(globals->level_count[level]!=globals->level_count[SharedGlobals::CREATED])
+		usleep(150*1000);
+	globals->lock.lock(ProcessID::getID());
+	globals->lock.unlock();
+}
+	
+template<class T>
+void sim::manage_process() {
+	//initialize the first runlevel
+	globals->lock.lock(T::getID());
+	globals->level_count[SharedGlobals::CONSTRUCTING]++;
+	cout << setw(35) << T::getClassName() << ":  ProcessID::getID()=" << T::getID() << "   pid=" << getpid() << endl;
+
+	T t;
+	ASSERT(T::getID()==ProcessID::getID(),"Process ID set incorrectly!");
+	
+	globals->lock.unlock();
+	while(globals->level_count[SharedGlobals::CONSTRUCTING]!=globals->level_count[SharedGlobals::CREATED])
+		usleep(150*1000);
+	globals->lock.lock(ProcessID::getID());
+	globals->lock.unlock();
+	
+	//now just walk through each of the other steps
+	wait_runlevel(SharedGlobals::STARTING);
+	t.DoStart();
+	wait_runlevel(SharedGlobals::RUNNING);
+	t.run(); //should return if/when SharedGlobals::shutdown flag is set
+	wait_runlevel(SharedGlobals::STOPPING);
+	t.DoStop();
+	wait_runlevel(SharedGlobals::DESTRUCTING);
+}
+	
+template<class T>
+bool sim::fork_process() {
+	if(config.multiprocess) {
+		RCRegion::aboutToFork(T::getID());
+		MutexLockBase::aboutToFork();
+	}
+	//increment this *before* the fork to guarantee everyone knows to wait for the new process
+	globals->level_count[SharedGlobals::CREATED]++;
+	if(config.multiprocess) {
+		child=fork();
+		if(child==static_cast<pid_t>(-1)) {
+			cerr << "Unable to spawn simulator process!" << endl;
+			exit(1);
+		}
+		if(child!=0) {
+			manage_process<T>();
+			return true;
+		}
+		original=false;
+	} else {
+		primaries.push_back(new PrimaryThread<T>());
+		primaries.back()->start();
+	}
+	return false;
+}
+
+ProcessID::ProcessID_t sim::getProcessID() {
+	Thread* th=Thread::getCurrent();
+	if(th==NULL)
+		return ProcessID::SimulatorProcess; // the main thread will fall into the simulator process
+	return static_cast<ProcessID::ProcessID_t>(reinterpret_cast<size_t>(th->getGroup()));
+}
+void sim::setProcessID(ProcessID::ProcessID_t id) {
+	Thread* th=Thread::getCurrent();
+	ASSERTRET(th!=NULL,"Unable to set process ID for main thread");
+	th->setGroup(reinterpret_cast<void*>(id));
+}
+
+void sim::handle_signal(int sig) {
+	//	sigset_t mask_set;  /* used to set a signal masking set. */
+	//	sigset_t old_set;   /* used to store the old mask set.   */
+		
+	/* reset the signal handler for next time */
+	//	signal(sig, handle_signal);
+	/* mask any further signals while we're inside the handler. */
+	//	sigfillset(&mask_set);
+	//	sigprocmask(SIG_SETMASK, &mask_set, &old_set);
+		
+	char * name=NULL;
+	char defBuf[30];
+	switch(sig) {
+	case SIGINT: name="SIGINT"; break;
+	case SIGQUIT: name="SIGQUIT"; break;
+	case SIGBUS: name="SIGBUS"; break;
+	case SIGSEGV: name="SIGSEGV"; break;
+	case SIGTERM: name="SIGTERM"; break;
+	case SIGABRT: name="SIGABRT"; break;
+	case SIGFPE: name="SIGFPE"; break;
+	case SIGPIPE: name="SIGPIPE"; break;
+	case SIGHUP: name="SIGHUP"; break;
+	default:
+		name=defBuf;
+		snprintf(name,30,"signal %d",sig);
+		break;
+	}
+	cout << "*** ERROR " << Process::getName() << ": Received " << name << endl;
+	
+	static bool firstCall=true;
+	if(!firstCall) {
+		cerr << "Signal handler was recursively called, may be leaked IPC resources :(" << endl;
+		cerr << "The 'ipcs' tool can be used to manually free these, if it becomes a problem. " << endl;
+		cerr << "However, simply re-running will generally reclaim the previous buffers for you." << endl;
+		exit(EXIT_FAILURE);
+		return;
+	}
+	firstCall=false;
+	
+	stacktrace::displayCurrentStackTrace(15);
+	
+	cout << "*** ERROR " << Process::getName() << ": Engaging fault shutdown..." << endl;
+	if(globals!=NULL && !globals->hadFault()) {
+		if(!MessageQueueBase::getSemaphoreManager()->hadFault())
+			globals->lock.lock(ProcessID::getID());
+		if(globals->level_count[SharedGlobals::CREATED]>0)
+			globals->level_count[SharedGlobals::CREATED]--;
+		else
+			cout << "*** ERROR " << Process::getName() << ": level_count[CREATED] underflow" << endl;
+		globals->signalShutdown();
+		if(!MessageQueueBase::getSemaphoreManager()->hadFault())
+			globals->lock.unlock();
+		globals->faultShutdown();
+	}
+	if(MessageQueueBase::getSemaphoreManager()!=NULL && !MessageQueueBase::getSemaphoreManager()->hadFault()) {
+		cout << "*** ERROR " << Process::getName() << ": Dereferencing mutex SemaphoreManager" << endl;
+		MessageQueueBase::setSemaphoreManager(NULL); //reset to preallocated instance
+		MessageQueueBase::getSemaphoreManager()->faultShutdown();
+	}
+	cout << "*** ERROR " << Process::getName() << ": Dereferencing shared memory regions" << endl;
+	RCRegion::faultShutdown();
+	cout << "*** ERROR " << Process::getName() << ": Exiting..." << endl;
+	exit(EXIT_FAILURE);
+}
+	
+void sim::handle_exit() {
+	static bool firstCall=true;
+	if(!firstCall) {
+		cerr << "handle_exit was recursively called" << endl;
+		return;
+	}
+	firstCall=false;
+	cout << Process::getName() << ": Exiting..." << endl;
+#ifndef DISABLE_READLINE
+	rl_reset_terminal(NULL);
+#endif
+	if(RCRegion::NumberOfAttach()==0) {
+		if(original)
+			cout << "Clean shutdown complete.  Have a nice day." << endl;
+		return;
+	}
+	cout << "*** ERROR " << Process::getName() << ": Exit with attached memory regions, engaging fault shutdown..." << endl;
+	if(globals!=NULL && !globals->hadFault()) {
+		if(!MessageQueueBase::getSemaphoreManager()->hadFault())
+			globals->lock.lock(ProcessID::getID());
+		if(globals->level_count[SharedGlobals::CREATED]>0)
+			globals->level_count[SharedGlobals::CREATED]--;
+		else
+			cout << "*** ERROR " << Process::getName() << ": level_count[CREATED] underflow" << endl;
+		globals->signalShutdown();
+		if(!MessageQueueBase::getSemaphoreManager()->hadFault())
+			globals->lock.unlock();
+		globals->faultShutdown();
+	} else {
+		cerr << "*** ERROR " << Process::getName() << ": exit with previous global fault" << endl;
+	}
+	if(MessageQueueBase::getSemaphoreManager()!=NULL && !MessageQueueBase::getSemaphoreManager()->hadFault()) {
+		cout << "*** ERROR " << Process::getName() << ": Dereferencing mutex SemaphoreManager" << endl;
+		MessageQueueBase::setSemaphoreManager(NULL); //reset to preallocated instance
+		MessageQueueBase::getSemaphoreManager()->faultShutdown();
+	} else {
+		cerr << "*** ERROR " << Process::getName() << ": exit with previous mutex fault" << endl;
+	}
+	cout << "*** ERROR " << Process::getName() << ": Dereferencing shared memory regions" << endl;
+	RCRegion::faultShutdown();
+	cout << "*** ERROR " << Process::getName() << ": Exiting..." << endl;
+}
+	
+unsigned int sim::measure_usleep_cost() {
+	usleep(50000); //to hopefully clear out the scheduler for the duration of our test
+	const unsigned int TRIALS=50;
+	TimeET mintime(1.0); //should definitely be less than a second
+	for(unsigned int i=0; i<TRIALS; i++) {
+		//measure usleep (plus overhead)
+		TimeET cur;
+		usleep(1); // at least 1 to avoid being a no-op
+		TimeET elapsed(cur.Age());
+		if(elapsed<mintime)
+			mintime=elapsed;
+	}
+	usleep(50000); //to hopefully clear out the scheduler for the duration of our test
+	TimeET minover(1.0); //should definitely be less than a second
+	for(unsigned int i=0; i<TRIALS; i++) {
+		//measure overhead
+		TimeET cur;
+		TimeET elapsed(cur.Age());
+		if(elapsed<minover)
+			minover=elapsed;
+	}
+	if(mintime<minover) { // something went wrong -- overhead is greater than total
+		mintime=0L;
+		cout << "usleep granularity couldn't be measured, default to 10ms" << endl;
+	} else {
+		//subtract overhead
+		mintime-=minover;
+		cout << "usleep granularity is " << mintime.Value()*1.0e6 << "us";
+		if(mintime<2L) {
+			mintime=2L;
+			cout << ", reset to 2ms";
+		}
+		cout << endl;
+	}
+	return static_cast<unsigned>(mintime.Value()*1.0e6);
+}
+
+sim::ConfigErrorCheck::ConfigErrorCheck() : PrimitiveListener(), holdMPValue(config.multiprocess) {}
+
+sim::ConfigErrorCheck::~ConfigErrorCheck() {
+	sim::config.multiprocess.removePrimitiveListener(this);
+}
+
+void sim::ConfigErrorCheck::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&sim::config.multiprocess) {
+#if TEKKOTSU_SHM_STYLE==NO_SHM
+		if(sim::config.multiprocess) {
+			cerr << "ERROR: TEKKOTSU_SHM_STYLE was set to NO_SHM during compile, Muliprocess cannot be set to 'true'" << endl;
+			sim::config.multiprocess=false;
+		}
+#else
+#  ifdef DEBUG
+		cerr << "sim::config.Multiprocess set to " << sim::config.multiprocess << endl;
+#  endif
+		if(holdMPValue!=sim::config.multiprocess) {
+			cerr << "ERROR: Cannot change sim::config.Multiprocess during execution, must set from command line or load from settings file" << endl;
+			sim::config.multiprocess=holdMPValue;
+		}
+#endif
+	}
+}
+
+void sim::ConfigErrorCheck::holdMultiprocess() {
+	holdMPValue=sim::config.multiprocess;
+	sim::config.multiprocess.addPrimitiveListener(this);
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/tekkotsu/sim.h ./local/tekkotsu/sim.h
--- ../Tekkotsu_3.0/local/tekkotsu/sim.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/tekkotsu/sim.h	2007-10-12 12:55:05.000000000 -0400
@@ -0,0 +1,117 @@
+//-*-c++-*-
+#ifndef INCLUDED_sim_h_
+#define INCLUDED_sim_h_
+
+#include "Events/EventTranslator.h"
+#include "IPC/MessageQueue.h"
+#include "SharedGlobals.h"
+#include "IPC/SharedObject.h"
+#include "IPC/Thread.h"
+#include "Wireless/Wireless.h"
+#include "Shared/ProjectInterface.h"
+#include <vector>
+class SimConfig;
+
+class sim {
+	friend int main(int argc, const char* argv[]);
+public:
+	sim();
+	bool processCommandLine(int argc, const char* argv[]);
+	bool run();
+	~sim();
+	
+	typedef MessageQueue<50> EventQueue_t;
+	typedef MessageQueue<50> MotionCommandQueue_t;
+	typedef MessageQueue<50> SoundPlayQueue_t;
+	typedef MessageQueue<1> CameraQueue_t;
+	typedef MessageQueue<1> SensorQueue_t;
+	typedef MessageQueue<1> TimerWakeup_t;
+	typedef MessageQueue<1> MotionWakeup_t;
+	typedef MessageQueue<ProcessID::NumProcesses+1> StatusRequest_t;
+	typedef MessageQueue<1> MotionOutput_t;
+	
+	static SimConfig config;
+	static IPCEventTranslator * etrans;
+	static std::vector<std::string> cmdlineArgs;
+	
+protected:
+	static unsigned int measure_usleep_cost();
+	static void wait_runlevel(SharedGlobals::runlevel_t level);
+	template<class T> static void manage_process();
+	template<class T> static bool fork_process();
+	
+	static ProcessID::ProcessID_t getProcessID(); //!< ProcessID hook to use the thread group as the process ID
+	static void setProcessID(ProcessID::ProcessID_t id); //!< ProcessID hook to set the thread group as the process ID
+	
+	//! a wrapper for one of the 'major' processes, which would otherwise be forked as its own process if SimConfig::multiprocess was true
+	template<typename T>
+	class PrimaryThread : public Thread {
+	public:
+		PrimaryThread() : Thread() {}
+		virtual void* run() { sim::manage_process<T>(); return NULL; }
+	};
+	static std::vector<Thread*> primaries;
+	
+	//! provides warning regarding configuration settings
+	class ConfigErrorCheck : public plist::PrimitiveListener {
+	public:
+		ConfigErrorCheck();
+		~ConfigErrorCheck();
+		virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+		void holdMultiprocess();
+	protected:
+		bool holdMPValue;
+	};
+	static ConfigErrorCheck cfgCheck;
+
+	static unsigned int sim_get_time() { return globals?globals->get_time():0; }
+	static float sim_getTimeScale() { return globals?globals->getTimeScale():0; }
+	
+	static void handle_signal(int sig);
+	static void handle_exit();
+
+	SharedObject<SemaphoreManager> mutexSemMgr;
+	SharedObject<SharedGlobals> glob;
+	SharedObject<ipc_setup_t> subj;
+	static bool original;
+	static const char * const usage;
+	static pid_t child;
+};
+
+class WirelessThread : public Thread {
+public:
+	//! constructor
+	WirelessThread() : Thread() {}
+	//! destructor -- stop thread
+	virtual ~WirelessThread() {
+		if(isStarted()) {
+			stop();
+			join();
+		}
+	}
+	virtual unsigned int runloop() {
+		// initial setup done by wireless's own constructor
+		wireless->pollTest(NULL); // by passing NULL, we wait indefinitely, so no need to usleep in the Thread code
+		wireless->pollProcess();
+		wireless->pollSetup(); // reinitialize for next test
+		return 0; //no sleep time because pollTest blocks
+	}
+	virtual void stop() {
+		Thread::stop();
+		wireless->wakeup();
+	}
+};
+
+
+/*! @file
+ * @brief 
+ * @author ejt (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.2 $
+ * $State: Exp $
+ * $Date: 2007/10/12 16:55:05 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/DataCache.cc ./local/terk/DataCache.cc
--- ../Tekkotsu_3.0/local/terk/DataCache.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/DataCache.cc	2007-11-20 19:12:01.000000000 -0500
@@ -0,0 +1,124 @@
+#ifdef HAVE_ICE
+
+#include "Shared/RobotInfo.h"
+#include "Shared/ImageUtil.h"
+#include "Shared/debuget.h"
+#include "Shared/LoadSave.h"
+#include "Shared/MarkScope.h"
+#include "DataCache.h"
+#include "QwerkBot.h"
+#include <unistd.h>
+
+using namespace std;
+
+DataCache::DataCache(QwerkBot* qwerk) : number(0), qb(qwerk), state(), states(), cstate(0), frameLock() {
+}
+
+unsigned int DataCache::nextTimestamp() {
+	return 0;
+}
+
+const std::string& DataCache::nextName() {
+	static const std::string noneStr="(none)";
+	return noneStr;
+}
+
+unsigned int DataCache::getData(const char *& payload, unsigned int& size, unsigned int& timestamp, string& name) {
+	::TeRK::QwerkState qstate = qb->requestStateFrame();
+	timestamp = get_time();
+	number++;
+	
+	// TODO: ask ethen about state serialization
+	// clear the state data
+	state.str("");
+	state << "#POS\n";
+	state << "condensed " << RobotInfo::RobotName << "\n";
+	
+	state << "meta-info = ";
+	state << timestamp;
+	state << " ";
+	state << number;
+	state << "\n";
+	
+	state << "outputs =";
+	
+	const int SERVO_MAX=255;
+#ifdef TGT_HAS_WHEELS
+	const int MOTOR_MAX=100000;
+#endif
+	for(unsigned int i=0; i<NumOutputs; ++i) {
+		float v;
+#ifdef TGT_HAS_WHEELS
+		if(i>=WheelOffset && i<WheelOffset+NumWheels) {
+			float scale=outputRanges[i][MaxRange]*3; // assuming symmetric range!
+			v = qstate.motor.motorVelocities[i-WheelOffset]/MOTOR_MAX*scale;
+		} else
+#endif
+#ifdef TGT_HAS_LEDS
+		if(i>=LEDOffset && i<LEDOffset+NumLEDs) {
+			v = qb->ledStatus[i-LEDOffset];
+		} else
+#endif
+		{
+			unsigned int servoIdx=i;
+#ifdef TGT_HAS_WHEELS
+			if(servoIdx>WheelOffset)
+				servoIdx-=NumWheels;
+#endif
+#ifdef TGT_HAS_LEDS
+			if(servoIdx>LEDOffset)
+				servoIdx-=NumLEDs;
+#endif
+			const float range = outputRanges[i][MaxRange]-outputRanges[i][MinRange];
+			v = static_cast<float>(qstate.servo.servoPositions[servoIdx])/SERVO_MAX*range+outputRanges[i][MinRange];
+		}
+		state << " " << v;
+	}		
+	state << "\n";
+	
+	state << "sensors =";
+	state << " " << qstate.battery.batteryVoltage;
+	state << " " << qstate.analogIn.analogInValues[0];
+	state << " " << qstate.analogIn.analogInValues[1];
+	state << " " << qstate.analogIn.analogInValues[2];
+	state << " " << qstate.analogIn.analogInValues[3];
+	state << "\n";
+	
+	/*state << "weights =";
+	for(unsigned int i=0; i<NumOutputs; ++i)
+		state << " 0";
+	state << '\n';*/
+	
+	state << "#END\n";
+	
+	states[cstate] = state.str();
+	
+	size = states[cstate].size();
+	//std::cout << "state\n" << state.str() << std::endl;
+	name = "(none-sensor)";
+	
+	//cout << states[cstate] << endl;
+	payload = const_cast<char *>(states[cstate].c_str());
+	
+	cstate = !cstate;
+	
+	return number;
+}
+
+
+void DataCache::setDataSourceThread(LoadDataThread* p) {
+	if(thread==NULL && p!=NULL) {
+		// just starting to be used, announce what feedback we provide
+		for(unsigned int i=0; i<NumOutputs; i++)
+			providingOutput(i);
+	} else if(thread!=NULL && p==NULL) {
+		// going offline, cancel our announcement
+	  for(unsigned int i=0; i<NumOutputs; i++)
+		  ignoringOutput(i);
+	}
+	DataSource::setDataSourceThread(p);
+	//if(p!=NULL)
+	//  setSource(p->src);
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/DataCache.h ./local/terk/DataCache.h
--- ../Tekkotsu_3.0/local/terk/DataCache.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/DataCache.h	2007-11-20 19:12:01.000000000 -0500
@@ -0,0 +1,43 @@
+#ifndef DATA_CACHE
+#define DATA_CACHE
+
+#include <unistd.h>
+#include <map>
+#include <iostream>
+#include <fstream>
+
+#include "TeRKPeerCommon.h"
+#include "Shared/get_time.h"
+#include "IPC/Thread.h"
+
+#include "local/DataSource.h"
+
+class QwerkBot;
+
+class DataCache:public DataSource{
+ public:
+  DataCache(QwerkBot* qb);
+  virtual ~DataCache() {}
+  virtual unsigned int nextTimestamp();
+  virtual const std::string& nextName();
+  virtual unsigned int getData(const char *& payload, unsigned int& size, unsigned int& timestamp, std::string& name);
+  virtual void setDataSourceThread(LoadDataThread* p);
+
+ protected:
+  unsigned int number;
+  QwerkBot* qb;
+  std::ostringstream state;
+  std::string states[2];
+  int cstate;
+
+  ThreadNS::Lock frameLock;
+
+  virtual void doFreeze() {} //!< user hook for when #frozen is set to true
+  virtual void doUnfreeze() {} //!< user hook for when #frozen is set to false
+
+ private:
+	DataCache(const DataCache&); //!< do not call
+	DataCache& operator=(const DataCache&); //!< do not call
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/ImageCache.cc ./local/terk/ImageCache.cc
--- ../Tekkotsu_3.0/local/terk/ImageCache.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/ImageCache.cc	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,151 @@
+#ifdef HAVE_ICE
+
+#include "Shared/ImageUtil.h"
+#include "Shared/debuget.h"
+#include "Shared/LoadSave.h"
+#include "Shared/MarkScope.h"
+#include "ImageCache.h"
+#include <unistd.h>
+
+using namespace std;
+
+void ImageCache::newImage(::TeRK::ByteArray data){
+	MarkScope l(frameLock);
+	int timeNow = get_time();
+	
+	this->buffers[currentBuffer].setData(data, number);
+	
+	number++;
+	fps = (timeNow - lastTime);
+	lastTime = timeNow;
+}
+
+unsigned int ImageCache::nextTimestamp() {
+	unsigned int diff = get_time() - lastTime;
+	if(diff > fps)
+		return 0;
+	return fps - diff;
+}
+
+const std::string& ImageCache::nextName() {
+	static const std::string noneStr="(none)";
+	return noneStr;
+}
+
+unsigned int ImageCache::getData(const char *& payload, unsigned int& size, unsigned int& timestamp, string& name) {
+	//printf("IMAGECACHE!!!!!!!!!!!!!!!!!!!!!!!!!!!!!\n");
+	while(!(buffers[currentBuffer].unread)){
+		//cout << "Waiting for buffer " << currentBuffer << " to fill." << endl;
+		usleep(10000);
+		//add sleep
+	}
+	MarkScope l(frameLock);
+	Frame& image = buffers[currentBuffer];
+	image.unread = false;
+	
+	//printf("READING: timestamp:%d name:%s size:%d data:%p\n", lastTime, image.filename.c_str(), image.size, image.data);
+	
+	payload=image.data;
+	//cout << "sending width " << *(unsigned int*)(image.data) << endl;
+	size=image.size;
+	//unsigned int reqTime=timestamp;
+	timestamp=lastTime;
+	name="TeRK";
+	
+	currentBuffer = currentBuffer ^ 1;
+	
+	return image.number;
+}
+
+
+void ImageCache::setDataSourceThread(LoadDataThread* p) {
+	DataSource::setDataSourceThread(p);
+	//if(p!=NULL)
+	//  setSource(p->src);
+}
+
+
+
+// ------------------------------------------------
+
+void ImageCache::Frame::setData(::TeRK::ByteArray dataArray, int dataNumber){
+	char* cdata = (char *) &(dataArray[0]);
+	
+	// get the image info
+	size_t nwidth=0, nheight=0, ncomponents=0;
+	
+	// doesn't decompress whole image, just header info (dimensions)
+	image_util::decodeImage(cdata,dataArray.size(),nwidth,nheight,ncomponents);
+	if(nwidth*nheight*ncomponents==0) {
+		cerr << "TeRK returned empty image" << endl;
+		return;
+	}
+	size_t headerSize=getHeaderSize();
+	
+	size_t totalSize = headerSize + nwidth*nheight*ncomponents;
+	
+	if(totalSize > this->size){
+		if(this->data)
+			delete [] this->data;
+		
+		this->data = new char[totalSize];
+	}
+	this->size=totalSize;
+	
+	char* imgbuf = this->data;
+	
+	// decompress the image for real this time:
+	char * img=imgbuf+headerSize;
+	size_t imgSize=totalSize-headerSize;
+	if(!image_util::decodeImage(cdata,dataArray.size(),nwidth,nheight,ncomponents,img,imgSize)) {
+		cerr << "Image decompression failed" << endl;
+		delete [] imgbuf;
+		this->data=NULL;
+		this->size=0;
+		return; // don't fall through to the prepare() below!
+	}
+	
+	if(nwidth*nheight*ncomponents==0) {
+		cerr << "TeRK returned empty image" << endl;
+		delete [] imgbuf;
+		this->data=NULL;
+		this->size=0;
+	}
+	
+	//printf("headerSize:%d width:%d height:%d components:%d totalSize:%d data:%p\n", headerSize, width, height, components, totalSize, imgbuf);
+	
+	this->width = nwidth;
+	this->height = nheight;
+	this->components = ncomponents;
+	
+	if(writeHeader(imgbuf,headerSize)==0) {
+		cerr << "FileSystemImageSource::ImageInfo::prepare(): Ran out of space writing image header" << endl;
+		delete [] imgbuf;
+		this->data=NULL;
+		this->size=0;
+		return;
+	}
+	
+	number = dataNumber;
+	this->unread = true;
+}
+
+size_t ImageCache::Frame::getHeaderSize() const {
+	unsigned int layer=0;
+	return LoadSave::getSerializedSize(layer)
+		+ LoadSave::getSerializedSize(width)
+		+ LoadSave::getSerializedSize(height)
+		+ LoadSave::getSerializedSize(components);
+}
+
+size_t ImageCache::Frame::writeHeader(char* buf, size_t sz) const {
+	unsigned int remain=sz;
+	unsigned int layer=0;
+	if(!LoadSave::encodeInc(layer,buf,remain)) return 0;
+	if(!LoadSave::encodeInc(width,buf,remain)) return 0;
+	if(!LoadSave::encodeInc(height,buf,remain)) return 0;
+	if(!LoadSave::encodeInc(components,buf,remain)) return 0;
+	return sz-remain;
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/ImageCache.h ./local/terk/ImageCache.h
--- ../Tekkotsu_3.0/local/terk/ImageCache.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/ImageCache.h	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,68 @@
+#ifndef INCLUDED_ImageCache_h
+#define INCLUDED_ImageCache_h
+
+#include <unistd.h>
+#include <map>
+#include <iostream>
+#include <fstream>
+
+#include "TeRKPeerCommon.h"
+#include "Shared/get_time.h"
+#include "IPC/Thread.h"
+
+#include "local/DataSource.h"
+
+class ImageCache : public DataSource{
+public:
+	ImageCache() : lastTime(0), fps(0), number(0), currentBuffer(0), frameLock() {}
+	virtual ~ImageCache() {}
+	virtual void newImage(::TeRK::ByteArray data);
+	
+	virtual unsigned int nextTimestamp();
+	virtual const std::string& nextName();
+	virtual unsigned int getData(const char *& payload, unsigned int& size, unsigned int& timestamp, std::string& name);
+	virtual void setDataSourceThread(LoadDataThread* p);
+	
+protected:
+	class Frame {
+	public:
+		Frame() : number(), lifetime(0), data(NULL), size(0), unread(false), width(0), height(0), components(0) {}
+
+		~Frame() {
+			if(this->data)
+				delete [] this->data;
+		}
+		
+		void setData(::TeRK::ByteArray dataArray, int number);
+		
+		int number;
+		
+		float lifetime;
+		char* data;
+		unsigned int size;
+		bool unread;
+		
+		size_t width;
+		size_t height;
+		size_t components;
+		
+		size_t getHeaderSize() const;
+		size_t writeHeader(char* buf, size_t size) const;
+
+	private:
+		Frame(const Frame&); //!< do not call
+		Frame& operator=(const Frame&); //!< do not call
+		
+	};
+	
+	unsigned int lastTime;
+	unsigned int fps;
+	unsigned int number;
+	
+	int currentBuffer;
+	Frame buffers[2];
+	
+	ThreadNS::Lock frameLock;
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/ObjectPingThread.cc ./local/terk/ObjectPingThread.cc
--- ../Tekkotsu_3.0/local/terk/ObjectPingThread.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/ObjectPingThread.cc	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,48 @@
+#ifdef HAVE_ICE
+
+#include "ObjectPingThread.h"
+
+using namespace std;
+
+ObjectPingThread::ObjectPingThread(const Ice::ObjectPrx& objectPrx):
+  _objectPrx(objectPrx),
+  _timeout(IceUtil::Time::seconds(5)),
+  _destroy(false)
+{
+
+}
+
+void ObjectPingThread::run(){
+  cout << "running session run()" << endl;
+  Lock sync(*this);
+  while(!_destroy){
+    timedWait(_timeout);
+    if(_destroy){
+      break;
+    }
+    try{
+      // cout << "Pinging objectPrx" << endl;
+      _objectPrx->ice_ping();
+    }
+    catch(const Ice::Exception&){
+      break;
+    }
+  }
+}
+
+bool ObjectPingThread::destroyed(){
+  return _destroy;
+}
+
+void ObjectPingThread::destroy(){
+  Lock sync(*this);
+  _destroy = true;
+  notify();
+}
+
+void TeRKCallbackI::message(const string& data, const Ice::Current&){
+  cout << data << endl;
+}
+
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/ObjectPingThread.h ./local/terk/ObjectPingThread.h
--- ../Tekkotsu_3.0/local/terk/ObjectPingThread.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/ObjectPingThread.h	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,39 @@
+#ifndef OBJECT_PING_THREAD
+#define OBJECT_PING_THREAD 1
+
+#include <Ice/Application.h>
+#include <Glacier2/Router.h>
+#include "TeRKPeerCommon.h"
+#include "peer/MRPLPeer.h"
+#include "PropertyManagerI.h"
+
+#include <unistd.h>
+#include <map>
+#include <iostream>
+#include <fstream>
+
+class ObjectPingThread : public IceUtil::Thread, public IceUtil::Monitor<IceUtil::Mutex>
+{
+public:
+
+  ObjectPingThread(const Ice::ObjectPrx& objectPrx);
+  virtual void run();
+  
+  void  destroy();
+  bool destroyed();
+
+ private:
+  const Ice::ObjectPrx _objectPrx;
+  const IceUtil::Time _timeout;
+  bool _destroy;
+};
+typedef IceUtil::Handle<ObjectPingThread> ObjectPingThreadPtr;
+
+class TeRKCallbackI 
+{
+public:
+	virtual ~TeRKCallbackI() {}
+	virtual void message(const std::string& data, const Ice::Current&);
+};
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/PropertyManagerI.cc ./local/terk/PropertyManagerI.cc
--- ../Tekkotsu_3.0/local/terk/PropertyManagerI.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/PropertyManagerI.cc	2007-06-03 13:03:24.000000000 -0400
@@ -0,0 +1,34 @@
+#ifdef HAVE_ICE
+
+#include <vector>
+
+#include "TeRKPeerCommon.h"
+#include "PropertyManagerI.h"
+
+using namespace std;
+using namespace TeRK;
+using namespace peer;
+
+string PropertyManagerI::getProperty(const string &key, const Ice::Current&)
+{
+  return properties[key];
+}
+  
+void PropertyManagerI::setProperty(const string &key, const string &value, const Ice::Current&)
+{ 
+  properties[key] = value;
+}
+  
+StringArray PropertyManagerI::getPropertyKeys(const Ice::Current&)
+{ 
+  vector<string> keys;
+  map<string, string>::iterator propiter;
+  
+  for(propiter = properties.begin(); propiter != properties.end(); propiter++) {
+    keys.push_back((*propiter).first);
+  }
+
+  return keys;
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/PropertyManagerI.h ./local/terk/PropertyManagerI.h
--- ../Tekkotsu_3.0/local/terk/PropertyManagerI.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/PropertyManagerI.h	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,23 @@
+#ifndef _PROPERTYMANAGERI_H_
+#define _PROPERTYMANAGERI_H_
+
+#include <vector>
+#include <map>
+
+#include "TeRKPeerCommon.h"
+
+class PropertyManagerI : virtual public ::TeRK::PropertyManager
+{
+ public:
+	PropertyManagerI():PropertyManager(), properties(){};
+
+  std::string getProperty(const std::string &key, const Ice::Current&);
+  void setProperty(const std::string &key, const std::string &value, const Ice::Current&);
+  ::TeRK::StringArray getPropertyKeys(const Ice::Current&);
+
+ private:
+	std::map<std::string, std::string> properties;
+};
+
+#endif /* _PROPERTYMANAGERI_H_ */
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/QwerkBot.cc ./local/terk/QwerkBot.cc
--- ../Tekkotsu_3.0/local/terk/QwerkBot.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/QwerkBot.cc	2007-11-12 14:48:13.000000000 -0500
@@ -0,0 +1,129 @@
+#ifdef HAVE_ICE
+
+#include "Shared/RobotInfo.h"
+#include "QwerkBot.h"
+#include "local/DeviceDrivers/TeRKDriver.h"
+#include "Shared/get_time.h"
+#include <unistd.h>
+
+#include "SerialPort.h"
+
+QwerkBot::QwerkBot(TeRKDriver *cl, ::TeRK::TerkUserPrx peerPrx, ::TeRK::QwerkPrx proxy): 
+	motorControl(NULL), servoControl(NULL), analogControl(NULL), digitalInControl(NULL),
+	digitalOutControl(NULL), ledControl(NULL), serialIO(NULL), video(NULL),
+	ledStatus(), imageCache(0), dataCache(0), serialPort(0), client(cl), peerProxy(), 
+	serviceMap(proxy->getSupportedServices()), qstate(), prx(proxy), terkUserI(), serialConfig() {
+  // not yet implemented
+  //this->terkUserI.bindFrameEvent(this);
+
+  ::TeRK::ProxyTypeIdToIdentityMap::iterator tmp;
+
+  // now attempt to start the services
+  tmp = this->serviceMap.find("::TeRK::MotorController");
+  if(tmp != this->serviceMap.end())
+    this->motorControl = ::TeRK::MotorControllerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+  else
+    this->motorControl = 0;
+  
+  tmp = this->serviceMap.find("::TeRK::ServoController");
+  if(tmp != this->serviceMap.end())
+    this->servoControl = ::TeRK::ServoControllerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+  else
+    this->servoControl = 0;
+
+  tmp = this->serviceMap.find("::TeRK::AnalogInController");
+  if(tmp != this->serviceMap.end())
+    this->analogControl = ::TeRK::AnalogInControllerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+  else
+    this->analogControl = 0;
+  
+  tmp = this->serviceMap.find("::TeRK::DigitalInController");
+  if(tmp != this->serviceMap.end())
+    this->digitalInControl = ::TeRK::DigitalInControllerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+  else
+    this->digitalInControl = 0;
+  
+  tmp = this->serviceMap.find("::TeRK::DigitalOutController");
+  if(tmp != this->serviceMap.end())
+    this->digitalOutControl = ::TeRK::DigitalOutControllerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+  else
+    this->digitalOutControl = 0;
+
+  tmp = this->serviceMap.find("::TeRK::LEDController");
+  if(tmp != this->serviceMap.end())
+    this->ledControl = ::TeRK::LEDControllerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+  else
+    this->ledControl = 0;
+
+  // Setup Video Stream
+  tmp = this->serviceMap.find("::TeRK::VideoStreamerServer");
+  std::cout << "Video? " << (tmp != this->serviceMap.end()) << std::endl;
+  if(tmp != this->serviceMap.end()){
+    this->video = ::TeRK::VideoStreamerServerPrx::uncheckedCast(client->getPeerProxy(tmp->second));
+    this->imageCache = new ImageCache();
+  }
+  else{
+    this->video = 0;
+    this->imageCache = 0;
+  }
+/*
+  for(tmp = this->serviceMap.begin(); tmp != this->serviceMap.end(); tmp++){
+	  cout << tmp->first << endl;
+  }
+*/
+
+	// Setup SerialIO
+	tmp = this->serviceMap.find("::TeRK::SerialIOService");
+	if(tmp != this->serviceMap.end()){
+		this->serialIO = ::TeRK::SerialIOServicePrx::uncheckedCast(client->getPeerProxy(tmp->second));
+
+		// configure serial
+		serialConfig.portName = "/dev/ttyAM1";
+		serialConfig.baud = ::TeRK::BAUD57600;
+		serialConfig.characterSize = ::TeRK::CHARSIZE8;
+		serialConfig.parity = ::TeRK::PARITYNONE;
+		serialConfig.stopBits = ::TeRK::STOPBITS1;
+		serialConfig.flowControl = ::TeRK::FLOWCONTROLNONE;
+		// open the serial port
+		this->serialIO->close(serialConfig.portName);
+		this->serialIO->open(serialConfig);
+		this->serialPort = new QwerkSerialPort(serialConfig.portName, serialIO);
+	} else{
+		this->serialIO = 0;
+		this->serialPort = 0;
+	}
+
+	ledStatus.assign(NumLEDs,::TeRK::LEDOff);
+
+	dataCache = new DataCache(this);
+}
+
+
+bool QwerkBot::setConfig(::TeRK::SerialIOConfig newconfig){
+	if(this->serialIO){
+		this->serialIO->close(newconfig.portName);
+		this->serialIO->open(newconfig);
+		serialConfig = newconfig;
+		return true;
+	}
+	return false;
+}
+
+::TeRK::QwerkState QwerkBot::requestStateFrame(){
+	qstate = prx->getState();
+	return qstate;
+}
+
+QwerkBot::~QwerkBot(){
+  
+}
+
+void QwerkBot::executeLED(::TeRK::LEDCommand ledc){
+	for(unsigned int i = 0; i < NumLEDs; i++){
+		if(ledc.ledMask[i])
+			ledStatus[i] = ledStatus[i];
+	}
+	this->ledControl->execute(ledc);
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/QwerkBot.h ./local/terk/QwerkBot.h
--- ../Tekkotsu_3.0/local/terk/QwerkBot.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/QwerkBot.h	2007-11-11 18:57:30.000000000 -0500
@@ -0,0 +1,67 @@
+#ifndef QWERKBOT
+#define QWERKBOT
+
+#include "Ice/Application.h"
+#include "Ice/IdentityUtil.h"
+#include "IceUtil/UUID.h"
+
+#include <unistd.h>
+#include <map>
+#include <iostream>
+#include <fstream>
+
+#include "TeRKPeerCommon.h"
+#include "peer/MRPLPeer.h"
+#include "SerialIO.h"
+
+#include "PropertyManagerI.h"
+#include "TerkUserI.h"
+#include "ImageCache.h"
+#include "DataCache.h"
+
+#include "SerialPort.h"
+
+class TeRKDriver;
+
+class QwerkBot {
+public:
+	QwerkBot(TeRKDriver *client, ::TeRK::TerkUserPrx peerProxy, ::TeRK::QwerkPrx prx);
+	~QwerkBot();
+	
+	::TeRK::QwerkState requestStateFrame();
+	bool setConfig(::TeRK::SerialIOConfig config);
+	
+	// various controllers
+	::TeRK::MotorControllerPrx motorControl;
+	::TeRK::ServoControllerPrx servoControl;
+	::TeRK::AnalogInControllerPrx analogControl;
+	::TeRK::DigitalInControllerPrx digitalInControl;
+	::TeRK::DigitalOutControllerPrx digitalOutControl;
+	::TeRK::LEDControllerPrx ledControl;
+	::TeRK::SerialIOServicePrx serialIO;
+	::TeRK::VideoStreamerServerPrx video;
+	
+	::TeRK::LEDModeArray ledStatus;
+	void executeLED(::TeRK::LEDCommand ledc);
+	
+	ImageCache* imageCache;
+	DataCache* dataCache;
+
+	QwerkSerialPort* serialPort;
+private:
+	TeRKDriver *client;
+	
+	::TeRK::TerkUserPrx peerProxy;
+	::TeRK::ProxyTypeIdToIdentityMap serviceMap;
+	::TeRK::QwerkState qstate;
+	::TeRK::QwerkPrx prx;
+	TerkUserI terkUserI;
+	
+	::TeRK::SerialIOConfig serialConfig;
+	
+	QwerkBot(const QwerkBot&); //!< do not call
+	QwerkBot& operator=(const QwerkBot&); //!< do not call
+};
+
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/SerialIO.cc ./local/terk/SerialIO.cc
--- ../Tekkotsu_3.0/local/terk/SerialIO.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/SerialIO.cc	2007-06-03 13:03:24.000000000 -0400
@@ -0,0 +1,2331 @@
+#ifdef HAVE_ICE
+
+// **********************************************************************
+//
+// Copyright (c) 2003-2006 ZeroC, Inc. All rights reserved.
+//
+// This copy of Ice is licensed to you under the terms described in the
+// ICE_LICENSE file included in this distribution.
+//
+// **********************************************************************
+
+// Ice version 3.1.1
+// Generated from file `SerialIO.ice'
+
+#include "SerialIO.h"
+#include <Ice/LocalException.h>
+#include <Ice/ObjectFactory.h>
+#include <Ice/BasicStream.h>
+#include <Ice/Object.h>
+#include <IceUtil/Iterator.h>
+
+#ifndef ICE_IGNORE_VERSION
+#   if ICE_INT_VERSION / 100 != 301
+#       error Ice version mismatch!
+#   endif
+#   if ICE_INT_VERSION % 100 < 1
+#       error Ice patch level mismatch!
+#   endif
+#endif
+
+static const ::std::string __TeRK__SerialIOService__open_name = "open";
+
+static const ::std::string __TeRK__SerialIOService__isOpen_name = "isOpen";
+
+static const ::std::string __TeRK__SerialIOService__isDataAvailable_name = "isDataAvailable";
+
+static const ::std::string __TeRK__SerialIOService__read_name = "read";
+
+static const ::std::string __TeRK__SerialIOService__blockingRead_name = "blockingRead";
+
+static const ::std::string __TeRK__SerialIOService__readUntilDelimiter_name = "readUntilDelimiter";
+
+static const ::std::string __TeRK__SerialIOService__blockingReadUntilDelimiter_name = "blockingReadUntilDelimiter";
+
+static const ::std::string __TeRK__SerialIOService__write_name = "write";
+
+static const ::std::string __TeRK__SerialIOService__close_name = "close";
+
+void
+IceInternal::incRef(::TeRK::SerialIOService* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::SerialIOService* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::SerialIOService* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::SerialIOService* p)
+{
+    p->__decRef();
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::SerialIOServicePrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::SerialIOServicePrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::SerialIOService;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::SerialIOServicePtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::SerialIOBaudRate v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::SerialIOBaudRate& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::SerialIOBaudRate>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::SerialIOCharacterSize v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::SerialIOCharacterSize& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::SerialIOCharacterSize>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::SerialIOParity v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::SerialIOParity& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::SerialIOParity>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::SerialIOStopBits v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::SerialIOStopBits& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::SerialIOStopBits>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::SerialIOFlowControl v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::SerialIOFlowControl& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::SerialIOFlowControl>(val);
+}
+
+bool
+TeRK::SerialIOConfig::operator==(const SerialIOConfig& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::SerialIOConfig::operator!=(const SerialIOConfig& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(portName != __rhs.portName)
+    {
+	return true;
+    }
+    if(baud != __rhs.baud)
+    {
+	return true;
+    }
+    if(characterSize != __rhs.characterSize)
+    {
+	return true;
+    }
+    if(parity != __rhs.parity)
+    {
+	return true;
+    }
+    if(stopBits != __rhs.stopBits)
+    {
+	return true;
+    }
+    if(flowControl != __rhs.flowControl)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::SerialIOConfig::operator<(const SerialIOConfig& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(portName < __rhs.portName)
+    {
+	return true;
+    }
+    else if(__rhs.portName < portName)
+    {
+	return false;
+    }
+    if(baud < __rhs.baud)
+    {
+	return true;
+    }
+    else if(__rhs.baud < baud)
+    {
+	return false;
+    }
+    if(characterSize < __rhs.characterSize)
+    {
+	return true;
+    }
+    else if(__rhs.characterSize < characterSize)
+    {
+	return false;
+    }
+    if(parity < __rhs.parity)
+    {
+	return true;
+    }
+    else if(__rhs.parity < parity)
+    {
+	return false;
+    }
+    if(stopBits < __rhs.stopBits)
+    {
+	return true;
+    }
+    else if(__rhs.stopBits < stopBits)
+    {
+	return false;
+    }
+    if(flowControl < __rhs.flowControl)
+    {
+	return true;
+    }
+    else if(__rhs.flowControl < flowControl)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::SerialIOConfig::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(portName);
+    ::TeRK::__write(__os, baud);
+    ::TeRK::__write(__os, characterSize);
+    ::TeRK::__write(__os, parity);
+    ::TeRK::__write(__os, stopBits);
+    ::TeRK::__write(__os, flowControl);
+}
+
+void
+TeRK::SerialIOConfig::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(portName);
+    ::TeRK::__read(__is, baud);
+    ::TeRK::__read(__is, characterSize);
+    ::TeRK::__read(__is, parity);
+    ::TeRK::__read(__is, stopBits);
+    ::TeRK::__read(__is, flowControl);
+}
+
+TeRK::SerialIOException::SerialIOException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException(__ice_reason)
+#else
+    ::TeRK::TeRKException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__SerialIOException_name = "TeRK::SerialIOException";
+
+const ::std::string
+TeRK::SerialIOException::ice_name() const
+{
+    return __TeRK__SerialIOException_name;
+}
+
+::Ice::Exception*
+TeRK::SerialIOException::ice_clone() const
+{
+    return new SerialIOException(*this);
+}
+
+void
+TeRK::SerialIOException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::SerialIOException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::SerialIOException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__write(__os);
+#else
+    ::TeRK::TeRKException::__write(__os);
+#endif
+}
+
+void
+TeRK::SerialIOException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__read(__is, true);
+#else
+    ::TeRK::TeRKException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::SerialIOException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::SerialIOException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::SerialIOException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::SerialIOException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__SerialIOException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::SerialIOException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__SerialIOException__Ptr = new __F__TeRK__SerialIOException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::SerialIOException::ice_factory()
+{
+    return __F__TeRK__SerialIOException__Ptr;
+}
+
+class __F__TeRK__SerialIOException__Init
+{
+public:
+
+    __F__TeRK__SerialIOException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::SerialIOException", ::TeRK::SerialIOException::ice_factory());
+    }
+
+    ~__F__TeRK__SerialIOException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::SerialIOException");
+    }
+};
+
+static __F__TeRK__SerialIOException__Init __F__TeRK__SerialIOException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__SerialIOException__initializer() {} }
+#endif
+
+void
+TeRK::AMI_SerialIOService_open::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::TeRK::SerialIOConfig& config, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__open_name, ::Ice::Normal, __ctx);
+	config.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_open::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_SerialIOService_isOpen::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__isOpen_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_isOpen::__response(bool __ok)
+{
+    bool __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_SerialIOService_isDataAvailable::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__isDataAvailable_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_isDataAvailable::__response(bool __ok)
+{
+    bool __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_SerialIOService_read::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__read_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_read::__response(bool __ok)
+{
+    ::TeRK::ByteArray __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_SerialIOService_blockingRead::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__blockingRead_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->write(timeoutMilliseconds);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_blockingRead::__response(bool __ok)
+{
+    ::TeRK::ByteArray __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_SerialIOService_readUntilDelimiter::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__readUntilDelimiter_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->write(delimiterCharacter);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_readUntilDelimiter::__response(bool __ok)
+{
+    ::TeRK::ByteArray __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_SerialIOService_blockingReadUntilDelimiter::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__blockingReadUntilDelimiter_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->write(delimiterCharacter);
+	__os->write(timeoutMilliseconds);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_blockingReadUntilDelimiter::__response(bool __ok)
+{
+    ::TeRK::ByteArray __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_SerialIOService_write::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, const ::TeRK::ByteArray& data, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__write_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	if(data.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&data[0], &data[0] + data.size());
+	}
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_write::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_SerialIOService_close::__invoke(const ::TeRK::SerialIOServicePrx& __prx, const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__SerialIOService__close_name, ::Ice::Normal, __ctx);
+	__os->write(portName);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_SerialIOService_close::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+IceProxy::TeRK::SerialIOService::open(const ::TeRK::SerialIOConfig& config, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__open_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    __del->open(config, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::open_async(const ::TeRK::AMI_SerialIOService_openPtr& __cb, const ::TeRK::SerialIOConfig& config)
+{
+    open_async(__cb, config, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::open_async(const ::TeRK::AMI_SerialIOService_openPtr& __cb, const ::TeRK::SerialIOConfig& config, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, config, __ctx);
+}
+
+bool
+IceProxy::TeRK::SerialIOService::isOpen(const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__isOpen_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    return __del->isOpen(portName, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::isOpen_async(const ::TeRK::AMI_SerialIOService_isOpenPtr& __cb, const ::std::string& portName)
+{
+    isOpen_async(__cb, portName, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::isOpen_async(const ::TeRK::AMI_SerialIOService_isOpenPtr& __cb, const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, __ctx);
+}
+
+bool
+IceProxy::TeRK::SerialIOService::isDataAvailable(const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__isDataAvailable_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    return __del->isDataAvailable(portName, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::isDataAvailable_async(const ::TeRK::AMI_SerialIOService_isDataAvailablePtr& __cb, const ::std::string& portName)
+{
+    isDataAvailable_async(__cb, portName, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::isDataAvailable_async(const ::TeRK::AMI_SerialIOService_isDataAvailablePtr& __cb, const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, __ctx);
+}
+
+::TeRK::ByteArray
+IceProxy::TeRK::SerialIOService::read(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__read_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    return __del->read(portName, maxNumberOfBytesToRead, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::read_async(const ::TeRK::AMI_SerialIOService_readPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead)
+{
+    read_async(__cb, portName, maxNumberOfBytesToRead, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::read_async(const ::TeRK::AMI_SerialIOService_readPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, maxNumberOfBytesToRead, __ctx);
+}
+
+::TeRK::ByteArray
+IceProxy::TeRK::SerialIOService::blockingRead(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__blockingRead_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    return __del->blockingRead(portName, maxNumberOfBytesToRead, timeoutMilliseconds, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::blockingRead_async(const ::TeRK::AMI_SerialIOService_blockingReadPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds)
+{
+    blockingRead_async(__cb, portName, maxNumberOfBytesToRead, timeoutMilliseconds, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::blockingRead_async(const ::TeRK::AMI_SerialIOService_blockingReadPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, maxNumberOfBytesToRead, timeoutMilliseconds, __ctx);
+}
+
+::TeRK::ByteArray
+IceProxy::TeRK::SerialIOService::readUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__readUntilDelimiter_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    return __del->readUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::readUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_readUntilDelimiterPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter)
+{
+    readUntilDelimiter_async(__cb, portName, maxNumberOfBytesToRead, delimiterCharacter, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::readUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_readUntilDelimiterPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, maxNumberOfBytesToRead, delimiterCharacter, __ctx);
+}
+
+::TeRK::ByteArray
+IceProxy::TeRK::SerialIOService::blockingReadUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__blockingReadUntilDelimiter_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    return __del->blockingReadUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, timeoutMilliseconds, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::blockingReadUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_blockingReadUntilDelimiterPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds)
+{
+    blockingReadUntilDelimiter_async(__cb, portName, maxNumberOfBytesToRead, delimiterCharacter, timeoutMilliseconds, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::blockingReadUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_blockingReadUntilDelimiterPtr& __cb, const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, maxNumberOfBytesToRead, delimiterCharacter, timeoutMilliseconds, __ctx);
+}
+
+void
+IceProxy::TeRK::SerialIOService::write(const ::std::string& portName, const ::TeRK::ByteArray& data, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__SerialIOService__write_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    __del->write(portName, data, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::write_async(const ::TeRK::AMI_SerialIOService_writePtr& __cb, const ::std::string& portName, const ::TeRK::ByteArray& data)
+{
+    write_async(__cb, portName, data, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::write_async(const ::TeRK::AMI_SerialIOService_writePtr& __cb, const ::std::string& portName, const ::TeRK::ByteArray& data, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, data, __ctx);
+}
+
+void
+IceProxy::TeRK::SerialIOService::close(const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::SerialIOService* __del = dynamic_cast< ::IceDelegate::TeRK::SerialIOService*>(__delBase.get());
+	    __del->close(portName, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::SerialIOService::close_async(const ::TeRK::AMI_SerialIOService_closePtr& __cb, const ::std::string& portName)
+{
+    close_async(__cb, portName, __defaultContext());
+}
+
+void
+IceProxy::TeRK::SerialIOService::close_async(const ::TeRK::AMI_SerialIOService_closePtr& __cb, const ::std::string& portName, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, portName, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::SerialIOService::ice_staticId()
+{
+    return ::TeRK::SerialIOService::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::SerialIOService::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::SerialIOService);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::SerialIOService::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::SerialIOService);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::SerialIOService& l, const ::IceProxy::TeRK::SerialIOService& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::SerialIOService& l, const ::IceProxy::TeRK::SerialIOService& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::SerialIOService& l, const ::IceProxy::TeRK::SerialIOService& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::SerialIOService& l, const ::IceProxy::TeRK::SerialIOService& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::SerialIOService& l, const ::IceProxy::TeRK::SerialIOService& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::SerialIOService& l, const ::IceProxy::TeRK::SerialIOService& r)
+{
+    return !(l < r);
+}
+
+void
+IceDelegateM::TeRK::SerialIOService::open(const ::TeRK::SerialIOConfig& config, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__open_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	config.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+bool
+IceDelegateM::TeRK::SerialIOService::isOpen(const ::std::string& portName, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__isOpen_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	bool __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+bool
+IceDelegateM::TeRK::SerialIOService::isDataAvailable(const ::std::string& portName, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__isDataAvailable_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	bool __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateM::TeRK::SerialIOService::read(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__read_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ByteArray __ret;
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateM::TeRK::SerialIOService::blockingRead(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__blockingRead_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->write(timeoutMilliseconds);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ByteArray __ret;
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateM::TeRK::SerialIOService::readUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__readUntilDelimiter_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->write(delimiterCharacter);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ByteArray __ret;
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateM::TeRK::SerialIOService::blockingReadUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__blockingReadUntilDelimiter_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+	__os->write(maxNumberOfBytesToRead);
+	__os->write(delimiterCharacter);
+	__os->write(timeoutMilliseconds);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ByteArray __ret;
+	::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> _____ret;
+	__is->read(_____ret);
+	::std::vector< ::Ice::Byte>(_____ret.first, _____ret.second).swap(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::SerialIOService::write(const ::std::string& portName, const ::TeRK::ByteArray& data, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__write_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+	if(data.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&data[0], &data[0] + data.size());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::SerialIOException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::SerialIOService::close(const ::std::string& portName, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__SerialIOService__close_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(portName);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateD::TeRK::SerialIOService::open(const ::TeRK::SerialIOConfig& config, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__open_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->open(config, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+bool
+IceDelegateD::TeRK::SerialIOService::isOpen(const ::std::string& portName, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__isOpen_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->isOpen(portName, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+bool
+IceDelegateD::TeRK::SerialIOService::isDataAvailable(const ::std::string& portName, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__isDataAvailable_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->isDataAvailable(portName, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateD::TeRK::SerialIOService::read(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__read_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->read(portName, maxNumberOfBytesToRead, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateD::TeRK::SerialIOService::blockingRead(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__blockingRead_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->blockingRead(portName, maxNumberOfBytesToRead, timeoutMilliseconds, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateD::TeRK::SerialIOService::readUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__readUntilDelimiter_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->readUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ByteArray
+IceDelegateD::TeRK::SerialIOService::blockingReadUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__blockingReadUntilDelimiter_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->blockingReadUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, timeoutMilliseconds, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::SerialIOService::write(const ::std::string& portName, const ::TeRK::ByteArray& data, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__write_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->write(portName, data, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::SerialIOService::close(const ::std::string& portName, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__SerialIOService__close_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::SerialIOService* __servant = dynamic_cast< ::TeRK::SerialIOService*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->close(portName, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::ObjectPtr
+TeRK::SerialIOService::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__SerialIOService_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::PropertyManager",
+    "::TeRK::SerialIOService"
+};
+
+bool
+TeRK::SerialIOService::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__SerialIOService_ids, __TeRK__SerialIOService_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::SerialIOService::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__SerialIOService_ids[0], &__TeRK__SerialIOService_ids[4]);
+}
+
+const ::std::string&
+TeRK::SerialIOService::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__SerialIOService_ids[3];
+}
+
+const ::std::string&
+TeRK::SerialIOService::ice_staticId()
+{
+    return __TeRK__SerialIOService_ids[3];
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___open(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::SerialIOConfig config;
+    config.__read(__is);
+    try
+    {
+	open(config, __current);
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___isOpen(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    __is->read(portName);
+    bool __ret = isOpen(portName, __current);
+    __os->write(__ret);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___isDataAvailable(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    __is->read(portName);
+    try
+    {
+	bool __ret = isDataAvailable(portName, __current);
+	__os->write(__ret);
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___read(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    ::Ice::Int maxNumberOfBytesToRead;
+    __is->read(portName);
+    __is->read(maxNumberOfBytesToRead);
+    try
+    {
+	::TeRK::ByteArray __ret = read(portName, maxNumberOfBytesToRead, __current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&__ret[0], &__ret[0] + __ret.size());
+	}
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___blockingRead(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    ::Ice::Int maxNumberOfBytesToRead;
+    ::Ice::Int timeoutMilliseconds;
+    __is->read(portName);
+    __is->read(maxNumberOfBytesToRead);
+    __is->read(timeoutMilliseconds);
+    try
+    {
+	::TeRK::ByteArray __ret = blockingRead(portName, maxNumberOfBytesToRead, timeoutMilliseconds, __current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&__ret[0], &__ret[0] + __ret.size());
+	}
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___readUntilDelimiter(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    ::Ice::Int maxNumberOfBytesToRead;
+    ::Ice::Byte delimiterCharacter;
+    __is->read(portName);
+    __is->read(maxNumberOfBytesToRead);
+    __is->read(delimiterCharacter);
+    try
+    {
+	::TeRK::ByteArray __ret = readUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, __current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&__ret[0], &__ret[0] + __ret.size());
+	}
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___blockingReadUntilDelimiter(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    ::Ice::Int maxNumberOfBytesToRead;
+    ::Ice::Byte delimiterCharacter;
+    ::Ice::Int timeoutMilliseconds;
+    __is->read(portName);
+    __is->read(maxNumberOfBytesToRead);
+    __is->read(delimiterCharacter);
+    __is->read(timeoutMilliseconds);
+    try
+    {
+	::TeRK::ByteArray __ret = blockingReadUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, timeoutMilliseconds, __current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&__ret[0], &__ret[0] + __ret.size());
+	}
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___write(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string portName;
+    ::TeRK::ByteArray data;
+    __is->read(portName);
+    ::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> ___data;
+    __is->read(___data);
+    ::std::vector< ::Ice::Byte>(___data.first, ___data.second).swap(data);
+    try
+    {
+	write(portName, data, __current);
+    }
+    catch(const ::TeRK::SerialIOException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::___close(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::std::string portName;
+    __is->read(portName);
+    close(portName, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__SerialIOService_all[] =
+{
+    "blockingRead",
+    "blockingReadUntilDelimiter",
+    "close",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "isDataAvailable",
+    "isOpen",
+    "open",
+    "read",
+    "readUntilDelimiter",
+    "setProperty",
+    "write"
+};
+
+::IceInternal::DispatchStatus
+TeRK::SerialIOService::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__SerialIOService_all, __TeRK__SerialIOService_all + 17, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__SerialIOService_all)
+    {
+	case 0:
+	{
+	    return ___blockingRead(in, current);
+	}
+	case 1:
+	{
+	    return ___blockingReadUntilDelimiter(in, current);
+	}
+	case 2:
+	{
+	    return ___close(in, current);
+	}
+	case 3:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 4:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 5:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 8:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 9:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 10:
+	{
+	    return ___isDataAvailable(in, current);
+	}
+	case 11:
+	{
+	    return ___isOpen(in, current);
+	}
+	case 12:
+	{
+	    return ___open(in, current);
+	}
+	case 13:
+	{
+	    return ___read(in, current);
+	}
+	case 14:
+	{
+	    return ___readUntilDelimiter(in, current);
+	}
+	case 15:
+	{
+	    return ___setProperty(in, current);
+	}
+	case 16:
+	{
+	    return ___write(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::SerialIOService::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::SerialIOService::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::SerialIOService::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::SerialIOService was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::SerialIOService::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::SerialIOService was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__SerialIOServicePtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::SerialIOServicePtr* p = static_cast< ::TeRK::SerialIOServicePtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::SerialIOServicePtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::SerialIOService::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::SerialIOService& l, const ::TeRK::SerialIOService& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::SerialIOService& l, const ::TeRK::SerialIOService& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::SerialIOService& l, const ::TeRK::SerialIOService& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::SerialIOService& l, const ::TeRK::SerialIOService& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::SerialIOService& l, const ::TeRK::SerialIOService& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::SerialIOService& l, const ::TeRK::SerialIOService& r)
+{
+    return !(l < r);
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/SerialIO.h ./local/terk/SerialIO.h
--- ../Tekkotsu_3.0/local/terk/SerialIO.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/SerialIO.h	2007-04-12 16:07:45.000000000 -0400
@@ -0,0 +1,617 @@
+// **********************************************************************
+//
+// Copyright (c) 2003-2006 ZeroC, Inc. All rights reserved.
+//
+// This copy of Ice is licensed to you under the terms described in the
+// ICE_LICENSE file included in this distribution.
+//
+// **********************************************************************
+
+// Ice version 3.1.1
+// Generated from file `SerialIO.ice'
+
+#ifndef ___IFYRE_terk_source_new_TeRKPeerCommon_code_c____SerialIO_h__
+#define ___IFYRE_terk_source_new_TeRKPeerCommon_code_c____SerialIO_h__
+
+#include <Ice/LocalObjectF.h>
+#include <Ice/ProxyF.h>
+#include <Ice/ObjectF.h>
+#include <Ice/Exception.h>
+#include <Ice/LocalObject.h>
+#include <Ice/Proxy.h>
+#include <Ice/Object.h>
+#include <Ice/Outgoing.h>
+#include <Ice/OutgoingAsync.h>
+#include <Ice/Incoming.h>
+#include <Ice/Direct.h>
+#include <Ice/UserExceptionFactory.h>
+#include <Ice/FactoryTable.h>
+#include <Ice/StreamF.h>
+#include <Ice/UndefSysMacros.h>
+#include "TeRKPeerCommon.h"
+
+#ifndef ICE_IGNORE_VERSION
+#   if ICE_INT_VERSION / 100 != 301
+#       error Ice version mismatch!
+#   endif
+#   if ICE_INT_VERSION % 100 < 1
+#       error Ice patch level mismatch!
+#   endif
+#endif
+
+namespace IceProxy
+{
+
+namespace TeRK
+{
+
+class SerialIOService;
+bool operator==(const SerialIOService&, const SerialIOService&);
+bool operator!=(const SerialIOService&, const SerialIOService&);
+bool operator<(const SerialIOService&, const SerialIOService&);
+bool operator<=(const SerialIOService&, const SerialIOService&);
+bool operator>(const SerialIOService&, const SerialIOService&);
+bool operator>=(const SerialIOService&, const SerialIOService&);
+
+}
+
+}
+
+namespace TeRK
+{
+
+class SerialIOService;
+bool operator==(const SerialIOService&, const SerialIOService&);
+bool operator!=(const SerialIOService&, const SerialIOService&);
+bool operator<(const SerialIOService&, const SerialIOService&);
+bool operator<=(const SerialIOService&, const SerialIOService&);
+bool operator>(const SerialIOService&, const SerialIOService&);
+bool operator>=(const SerialIOService&, const SerialIOService&);
+
+}
+
+namespace IceInternal
+{
+
+void incRef(::TeRK::SerialIOService*);
+void decRef(::TeRK::SerialIOService*);
+
+void incRef(::IceProxy::TeRK::SerialIOService*);
+void decRef(::IceProxy::TeRK::SerialIOService*);
+
+}
+
+namespace TeRK
+{
+
+typedef ::IceInternal::Handle< ::TeRK::SerialIOService> SerialIOServicePtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::SerialIOService> SerialIOServicePrx;
+
+void __write(::IceInternal::BasicStream*, const SerialIOServicePrx&);
+void __read(::IceInternal::BasicStream*, SerialIOServicePrx&);
+void __write(::IceInternal::BasicStream*, const SerialIOServicePtr&);
+void __patch__SerialIOServicePtr(void*, ::Ice::ObjectPtr&);
+
+}
+
+namespace TeRK
+{
+
+enum SerialIOBaudRate
+{
+    BAUD50,
+    BAUD75,
+    BAUD110,
+    BAUD134,
+    BAUD150,
+    BAUD200,
+    BAUD300,
+    BAUD600,
+    BAUD1200,
+    BAUD1800,
+    BAUD2400,
+    BAUD4800,
+    BAUD9600,
+    BAUD19200,
+    BAUD38400,
+    BAUD57600,
+    BAUD115200
+};
+
+void __write(::IceInternal::BasicStream*, SerialIOBaudRate);
+void __read(::IceInternal::BasicStream*, SerialIOBaudRate&);
+
+enum SerialIOCharacterSize
+{
+    CHARSIZE5,
+    CHARSIZE6,
+    CHARSIZE7,
+    CHARSIZE8
+};
+
+void __write(::IceInternal::BasicStream*, SerialIOCharacterSize);
+void __read(::IceInternal::BasicStream*, SerialIOCharacterSize&);
+
+enum SerialIOParity
+{
+    PARITYEVEN,
+    PARITYODD,
+    PARITYNONE
+};
+
+void __write(::IceInternal::BasicStream*, SerialIOParity);
+void __read(::IceInternal::BasicStream*, SerialIOParity&);
+
+enum SerialIOStopBits
+{
+    STOPBITS1,
+    STOPBITS2
+};
+
+void __write(::IceInternal::BasicStream*, SerialIOStopBits);
+void __read(::IceInternal::BasicStream*, SerialIOStopBits&);
+
+enum SerialIOFlowControl
+{
+    FLOWCONTROLHARDWARE,
+    FLOWCONTROLSOFTWARE,
+    FLOWCONTROLNONE
+};
+
+void __write(::IceInternal::BasicStream*, SerialIOFlowControl);
+void __read(::IceInternal::BasicStream*, SerialIOFlowControl&);
+
+struct SerialIOConfig
+{
+    ::std::string portName;
+    ::TeRK::SerialIOBaudRate baud;
+    ::TeRK::SerialIOCharacterSize characterSize;
+    ::TeRK::SerialIOParity parity;
+    ::TeRK::SerialIOStopBits stopBits;
+    ::TeRK::SerialIOFlowControl flowControl;
+
+    bool operator==(const SerialIOConfig&) const;
+    bool operator!=(const SerialIOConfig&) const;
+    bool operator<(const SerialIOConfig&) const;
+    bool operator<=(const SerialIOConfig& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const SerialIOConfig& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const SerialIOConfig& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+class SerialIOException : public ::TeRK::TeRKException
+{
+public:
+
+    SerialIOException() {}
+    explicit SerialIOException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+static SerialIOException __SerialIOException_init;
+
+}
+
+namespace TeRK
+{
+
+class AMI_SerialIOService_open : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::TeRK::SerialIOConfig&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_open> AMI_SerialIOService_openPtr;
+
+class AMI_SerialIOService_isOpen : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(bool) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_isOpen> AMI_SerialIOService_isOpenPtr;
+
+class AMI_SerialIOService_isDataAvailable : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(bool) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_isDataAvailable> AMI_SerialIOService_isDataAvailablePtr;
+
+class AMI_SerialIOService_read : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ByteArray&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, ::Ice::Int, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_read> AMI_SerialIOService_readPtr;
+
+class AMI_SerialIOService_blockingRead : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ByteArray&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_blockingRead> AMI_SerialIOService_blockingReadPtr;
+
+class AMI_SerialIOService_readUntilDelimiter : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ByteArray&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_readUntilDelimiter> AMI_SerialIOService_readUntilDelimiterPtr;
+
+class AMI_SerialIOService_blockingReadUntilDelimiter : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ByteArray&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_blockingReadUntilDelimiter> AMI_SerialIOService_blockingReadUntilDelimiterPtr;
+
+class AMI_SerialIOService_write : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_write> AMI_SerialIOService_writePtr;
+
+class AMI_SerialIOService_close : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::SerialIOServicePrx&, const ::std::string&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_SerialIOService_close> AMI_SerialIOService_closePtr;
+
+}
+
+namespace IceProxy
+{
+
+namespace TeRK
+{
+
+class SerialIOService : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    void open(const ::TeRK::SerialIOConfig& config)
+    {
+	open(config, __defaultContext());
+    }
+    void open(const ::TeRK::SerialIOConfig&, const ::Ice::Context&);
+    void open_async(const ::TeRK::AMI_SerialIOService_openPtr&, const ::TeRK::SerialIOConfig&);
+    void open_async(const ::TeRK::AMI_SerialIOService_openPtr&, const ::TeRK::SerialIOConfig&, const ::Ice::Context&);
+
+    bool isOpen(const ::std::string& portName)
+    {
+	return isOpen(portName, __defaultContext());
+    }
+    bool isOpen(const ::std::string&, const ::Ice::Context&);
+    void isOpen_async(const ::TeRK::AMI_SerialIOService_isOpenPtr&, const ::std::string&);
+    void isOpen_async(const ::TeRK::AMI_SerialIOService_isOpenPtr&, const ::std::string&, const ::Ice::Context&);
+
+    bool isDataAvailable(const ::std::string& portName)
+    {
+	return isDataAvailable(portName, __defaultContext());
+    }
+    bool isDataAvailable(const ::std::string&, const ::Ice::Context&);
+    void isDataAvailable_async(const ::TeRK::AMI_SerialIOService_isDataAvailablePtr&, const ::std::string&);
+    void isDataAvailable_async(const ::TeRK::AMI_SerialIOService_isDataAvailablePtr&, const ::std::string&, const ::Ice::Context&);
+
+    ::TeRK::ByteArray read(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead)
+    {
+	return read(portName, maxNumberOfBytesToRead, __defaultContext());
+    }
+    ::TeRK::ByteArray read(const ::std::string&, ::Ice::Int, const ::Ice::Context&);
+    void read_async(const ::TeRK::AMI_SerialIOService_readPtr&, const ::std::string&, ::Ice::Int);
+    void read_async(const ::TeRK::AMI_SerialIOService_readPtr&, const ::std::string&, ::Ice::Int, const ::Ice::Context&);
+
+    ::TeRK::ByteArray blockingRead(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Int timeoutMilliseconds)
+    {
+	return blockingRead(portName, maxNumberOfBytesToRead, timeoutMilliseconds, __defaultContext());
+    }
+    ::TeRK::ByteArray blockingRead(const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Context&);
+    void blockingRead_async(const ::TeRK::AMI_SerialIOService_blockingReadPtr&, const ::std::string&, ::Ice::Int, ::Ice::Int);
+    void blockingRead_async(const ::TeRK::AMI_SerialIOService_blockingReadPtr&, const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Context&);
+
+    ::TeRK::ByteArray readUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter)
+    {
+	return readUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, __defaultContext());
+    }
+    ::TeRK::ByteArray readUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Context&);
+    void readUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_readUntilDelimiterPtr&, const ::std::string&, ::Ice::Int, ::Ice::Byte);
+    void readUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_readUntilDelimiterPtr&, const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Context&);
+
+    ::TeRK::ByteArray blockingReadUntilDelimiter(const ::std::string& portName, ::Ice::Int maxNumberOfBytesToRead, ::Ice::Byte delimiterCharacter, ::Ice::Int timeoutMilliseconds)
+    {
+	return blockingReadUntilDelimiter(portName, maxNumberOfBytesToRead, delimiterCharacter, timeoutMilliseconds, __defaultContext());
+    }
+    ::TeRK::ByteArray blockingReadUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Context&);
+    void blockingReadUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_blockingReadUntilDelimiterPtr&, const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int);
+    void blockingReadUntilDelimiter_async(const ::TeRK::AMI_SerialIOService_blockingReadUntilDelimiterPtr&, const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Context&);
+
+    void write(const ::std::string& portName, const ::TeRK::ByteArray& data)
+    {
+	write(portName, data, __defaultContext());
+    }
+    void write(const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Context&);
+    void write_async(const ::TeRK::AMI_SerialIOService_writePtr&, const ::std::string&, const ::TeRK::ByteArray&);
+    void write_async(const ::TeRK::AMI_SerialIOService_writePtr&, const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Context&);
+
+    void close(const ::std::string& portName)
+    {
+	close(portName, __defaultContext());
+    }
+    void close(const ::std::string&, const ::Ice::Context&);
+    void close_async(const ::TeRK::AMI_SerialIOService_closePtr&, const ::std::string&);
+    void close_async(const ::TeRK::AMI_SerialIOService_closePtr&, const ::std::string&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+}
+
+}
+
+namespace IceDelegate
+{
+
+namespace TeRK
+{
+
+class SerialIOService : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void open(const ::TeRK::SerialIOConfig&, const ::Ice::Context&) = 0;
+
+    virtual bool isOpen(const ::std::string&, const ::Ice::Context&) = 0;
+
+    virtual bool isDataAvailable(const ::std::string&, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::ByteArray read(const ::std::string&, ::Ice::Int, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::ByteArray blockingRead(const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::ByteArray readUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::ByteArray blockingReadUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Context&) = 0;
+
+    virtual void write(const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Context&) = 0;
+
+    virtual void close(const ::std::string&, const ::Ice::Context&) = 0;
+};
+
+}
+
+}
+
+namespace IceDelegateM
+{
+
+namespace TeRK
+{
+
+class SerialIOService : virtual public ::IceDelegate::TeRK::SerialIOService,
+			virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void open(const ::TeRK::SerialIOConfig&, const ::Ice::Context&);
+
+    virtual bool isOpen(const ::std::string&, const ::Ice::Context&);
+
+    virtual bool isDataAvailable(const ::std::string&, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray read(const ::std::string&, ::Ice::Int, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray blockingRead(const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray readUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray blockingReadUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Context&);
+
+    virtual void write(const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Context&);
+
+    virtual void close(const ::std::string&, const ::Ice::Context&);
+};
+
+}
+
+}
+
+namespace IceDelegateD
+{
+
+namespace TeRK
+{
+
+class SerialIOService : virtual public ::IceDelegate::TeRK::SerialIOService,
+			virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void open(const ::TeRK::SerialIOConfig&, const ::Ice::Context&);
+
+    virtual bool isOpen(const ::std::string&, const ::Ice::Context&);
+
+    virtual bool isDataAvailable(const ::std::string&, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray read(const ::std::string&, ::Ice::Int, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray blockingRead(const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray readUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Context&);
+
+    virtual ::TeRK::ByteArray blockingReadUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Context&);
+
+    virtual void write(const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Context&);
+
+    virtual void close(const ::std::string&, const ::Ice::Context&);
+};
+
+}
+
+}
+
+namespace TeRK
+{
+
+class SerialIOService : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef SerialIOServicePrx ProxyType;
+    typedef SerialIOServicePtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void open(const ::TeRK::SerialIOConfig&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___open(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual bool isOpen(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___isOpen(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual bool isDataAvailable(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___isDataAvailable(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::ByteArray read(const ::std::string&, ::Ice::Int, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___read(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::ByteArray blockingRead(const ::std::string&, ::Ice::Int, ::Ice::Int, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___blockingRead(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::ByteArray readUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___readUntilDelimiter(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::ByteArray blockingReadUntilDelimiter(const ::std::string&, ::Ice::Int, ::Ice::Byte, ::Ice::Int, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___blockingReadUntilDelimiter(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void write(const ::std::string&, const ::TeRK::ByteArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___write(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void close(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___close(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__SerialIOServicePtr(void*, ::Ice::ObjectPtr&);
+
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/SerialPort.cc ./local/terk/SerialPort.cc
--- ../Tekkotsu_3.0/local/terk/SerialPort.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/SerialPort.cc	2007-11-16 15:20:22.000000000 -0500
@@ -0,0 +1,86 @@
+#ifdef HAVE_ICE
+
+#include "SerialPort.h"
+
+const std::string QwerkSerialPort::autoRegisterQwerkSerialPort = "QwerkSerialPort";
+
+const char * QwerkSerialPort::baudNames[] = {
+	"50",
+	"75",
+	"110",
+	"134",
+	"150",
+	"200",
+	"300",
+	"600",
+	"1200",
+	"1800",
+	"2400",
+	"4800",
+	"9600",
+	"19200",
+	"38400",
+	"57600",
+	"115200",
+	""
+};
+const char * QwerkSerialPort::charSizeNames[] = { "5", "6", "7", "8", "" };
+const char * QwerkSerialPort::parityNames[] = { "EVEN", "ODD", "NONE", "" };
+const char * QwerkSerialPort::stopNames[] = { "1", "2", "" };
+const char * QwerkSerialPort::flowNames[] = { "HARDWARE", "SOFTWARE", "NONE", "" };
+INSTANTIATE_NAMEDENUMERATION_STATICS(TeRK::SerialIOBaudRate);
+INSTANTIATE_NAMEDENUMERATION_STATICS(TeRK::SerialIOCharacterSize);
+INSTANTIATE_NAMEDENUMERATION_STATICS(TeRK::SerialIOParity);
+INSTANTIATE_NAMEDENUMERATION_STATICS(TeRK::SerialIOStopBits);
+INSTANTIATE_NAMEDENUMERATION_STATICS(TeRK::SerialIOFlowControl);
+
+bool QwerkSerialPort::open() {
+	if(opened++>0)
+		return true;
+	device.addPrimitiveListener(this);
+	baudRate.addPrimitiveListener(this);
+	charSize.addPrimitiveListener(this);
+	parity.addPrimitiveListener(this);
+	stopBits.addPrimitiveListener(this);
+	flow.addPrimitiveListener(this);
+	return true;
+}
+
+bool QwerkSerialPort::close() {
+	if(opened==0)
+		std::cerr << "Warning: NetworkCommPort close() without open()" << std::endl;
+	if(--opened>0)
+		return false;
+	device.removePrimitiveListener(this);
+	baudRate.removePrimitiveListener(this);
+	charSize.removePrimitiveListener(this);
+	parity.removePrimitiveListener(this);
+	stopBits.removePrimitiveListener(this);
+	flow.removePrimitiveListener(this);
+	return true;
+}
+
+void QwerkSerialPort::plistValueChanged(const plist::PrimitiveBase& pl) {
+	if(&pl==&device) {
+	} else if(&pl==&baudRate) {
+	} else if(&pl==&charSize) {
+	} else if(&pl==&parity) {
+	} else if(&pl==&stopBits) {
+	} else if(&pl==&flow) {
+	} else {
+		std::cerr << "Unknown value in QwerkSerialPort::plistValueChanged!" << std::endl;
+	}
+}
+
+/*! @file
+ * @brief 
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.4 $
+ * $State: Exp $
+ * $Date: 2007/11/16 20:20:22 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/SerialPort.h ./local/terk/SerialPort.h
--- ../Tekkotsu_3.0/local/terk/SerialPort.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/SerialPort.h	2007-11-11 18:57:31.000000000 -0500
@@ -0,0 +1,107 @@
+//-*-c++-*-
+#ifndef INCLUDED_QwerkSerialPort_h_
+#define INCLUDED_QwerkSerialPort_h_
+
+#include "local/CommPort.h"
+#include "Shared/plist.h"
+#include <fstream>
+#include <ios>
+
+#include "TeRKPeerCommon.h"
+#include "peer/MRPLPeer.h"
+#include "SerialIO.h"
+
+#include "SerialStream.h"
+
+//! Provides CommPort interface to file system devices, such as serial ports
+/*! Pass a path to use a file system device, or see NetworkCommPort for a network interface */
+class QwerkSerialPort : public CommPort, public virtual plist::PrimitiveListener {
+public:
+	//! name - name of the serial port to open
+	QwerkSerialPort(const std::string& name, ::TeRK::SerialIOServicePrx serialIO)
+		: CommPort(autoRegisterQwerkSerialPort,name),
+		device("/dev/ttyAM1"), baudRate(TeRK::BAUD115200,baudNames), charSize(TeRK::CHARSIZE8,charSizeNames),
+		parity(TeRK::PARITYNONE,parityNames), stopBits(TeRK::STOPBITS1,stopNames), flow(TeRK::FLOWCONTROLHARDWARE,flowNames),
+		rbuf(serialIO, name), wbuf(serialIO, name), curloc(), curmode(), opened(0)
+	{
+		registerInstance();
+		addEntry("Device",device,"The path to the device on the Qwerk");
+		addEntry("BaudRate",baudRate,"The communication speed (bps)");
+		addEntry("CharSize",charSize,"The number of bits per character");
+		addEntry("Parity",parity);
+		addEntry("StopBits",stopBits);
+		addEntry("Flow",flow);
+	}
+	
+	//! destructor, checks that the file descriptor has already been closed
+	virtual ~QwerkSerialPort() {
+		if(opened>0)
+			connectionError("File descriptor still open in QwerkSerialPort destructor",true);
+	}
+	
+	virtual void setSerialPort(const std::string& name, ::TeRK::SerialIOServicePrx serialIO){
+		rbuf.open(serialIO, name);
+		wbuf.open(serialIO, name);
+	}
+
+	virtual std::string getClassName() const { return autoRegisterQwerkSerialPort; }
+	
+	virtual QwerkSerialBuffer& getReadStreambuf() { return rbuf; }
+	virtual QwerkSerialBuffer& getWriteStreambuf() { return wbuf; }
+	virtual bool isReadable() { return 1; }
+	virtual bool isWriteable() { return 1; }
+	
+	//! tries to have #sbuf open #path in #mode
+	virtual bool open();
+	
+	//! closes #sbuf
+	virtual bool close();
+	
+	//! watches #path, triggers a close() and re-open() if it changes
+	virtual void plistValueChanged(const plist::PrimitiveBase& pl);
+	
+	static const char * baudNames[];
+	static const char * charSizeNames[];
+	static const char * parityNames[];
+	static const char * stopNames[];
+	static const char * flowNames[];
+	
+	plist::Primitive<std::string> device;
+	plist::NamedEnumeration<TeRK::SerialIOBaudRate> baudRate;
+	plist::NamedEnumeration<TeRK::SerialIOCharacterSize> charSize;
+	plist::NamedEnumeration<TeRK::SerialIOParity> parity;
+	plist::NamedEnumeration<TeRK::SerialIOStopBits> stopBits;
+	plist::NamedEnumeration<TeRK::SerialIOFlowControl> flow;
+	
+protected:
+	//! Displays message on stderr and if @a fatal is set, calls closeFD()
+	virtual void connectionError(const std::string& msg, bool fatal) {
+		std::cerr << msg << std::endl;
+		if(fatal){
+			opened=1;
+			close();
+		}
+	}
+	
+	QwerkSerialBuffer rbuf;
+	QwerkSerialBuffer wbuf;
+	std::string curloc;
+	std::ios_base::openmode curmode;
+	unsigned int opened;
+	
+	//! holds the class name, set via registration with the CommPort registry
+	static const std::string autoRegisterQwerkSerialPort;
+};
+
+/*! @file
+ * @brief Describes FileDescriptorMotionHook, which provides a file descriptor interface for hardware "drivers"
+ * @author Ethan Tira-Thompson (ejt) (Creator)
+ *
+ * $Author: ejt $
+ * $Name: tekkotsu-4_0 $
+ * $Revision: 1.3 $
+ * $State: Exp $
+ * $Date: 2007/11/11 23:57:31 $
+ */
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/SerialStream.h ./local/terk/SerialStream.h
--- ../Tekkotsu_3.0/local/terk/SerialStream.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/SerialStream.h	2007-11-18 14:16:11.000000000 -0500
@@ -0,0 +1,241 @@
+#ifndef INCLUDED_qwerkserialstream_h_
+#define INCLUDED_qwerkserialstream_h_
+
+#include <cstdio>
+#include <cstring>
+#include <iostream>
+#include <iosfwd>
+#include <stdio.h>
+#include <stdlib.h>
+#include <ctype.h>
+#include <unistd.h>
+#include <stdexcept>
+
+#include <errno.h>
+#include <signal.h>
+//#include <sys/time.h>
+#include <sys/types.h>
+#include <sys/socket.h>
+#include <netinet/in.h>
+#include <arpa/inet.h>
+#include <netdb.h>
+#include <cstring>
+#include <string>
+#include <poll.h>
+
+#include "TeRKPeerCommon.h"
+#include "peer/MRPLPeer.h"
+#include "SerialIO.h"
+
+template <class charT, class traits=std::char_traits<charT> >
+class basic_QwerkSerialBuffer : public std::basic_streambuf<charT,traits> {
+	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_QwerkSerialBuffer(TeRK::SerialIOServicePrx proxy, std::string port);
+
+	virtual ~basic_QwerkSerialBuffer();
+
+	virtual void open(TeRK::SerialIOServicePrx proxy, std::string port);
+	
+//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<charT,traits>::eback;
+	using std::basic_streambuf<charT,traits>::gptr;
+	using std::basic_streambuf<charT,traits>::egptr;
+	using std::basic_streambuf<charT,traits>::gbump;
+	using std::basic_streambuf<charT,traits>::pbase;
+	using std::basic_streambuf<charT,traits>::pptr;
+	using std::basic_streambuf<charT,traits>::epptr;
+	using std::basic_streambuf<charT,traits>::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<char_type, traits_type>* setbuf(char_type* s, streamsize n);
+	//	virtual pos_type seekoff(off_type off, ios_base::seekdir way, ios_base::openmode which = ios_base::in | ios_base::out);
+	//	virtual pos_type seekpos(pos_type sp, ios_base::openmode which = ios_base::in | ios_base::out);
+	virtual int			sync();
+	//  lib.streambuf.virt.locales Locales:
+	//	virtual void imbue(const locale &loc);
+	
+//Data:
+protected:
+	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;
+
+	TeRK::SerialIOServicePrx prx;
+	std::string terminal;
+	
+private:
+	//basic_QwerkSerialBuffer() = 0;
+	basic_QwerkSerialBuffer(const basic_QwerkSerialBuffer&); // copy constructor, don't call
+	basic_QwerkSerialBuffer& operator=(const basic_QwerkSerialBuffer&); //!< assignment, don't call
+};
+template <class charT, class traits>
+const size_t basic_QwerkSerialBuffer<charT,traits>::def_buf_in_size=(1<<14)-28;
+template <class charT, class traits>
+const size_t basic_QwerkSerialBuffer<charT,traits>::def_buf_out_size=(1<<14)-28;
+
+/*
+template<class T>
+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_QwerkSerialBuffer<char, std::char_traits<char> > QwerkSerialBuffer;
+
+template <class charT, class traits>
+basic_QwerkSerialBuffer<charT,traits>::basic_QwerkSerialBuffer(TeRK::SerialIOServicePrx proxy, std::string port)
+  : std::basic_streambuf<charT,traits>(), buf_in(NULL), buf_out(NULL), using_buf_in(false), using_buf_out(false), prx(proxy), terminal(port) {
+	  buf_in = new charT[def_buf_in_size];
+	  buf_out = new charT[def_buf_out_size];
+	  using_buf_in = using_buf_out = true;
+	  setg(buf_in,buf_in+def_buf_in_size,buf_in+def_buf_in_size);
+	  setp(buf_out,buf_out+def_buf_out_size);
+  }
+
+template <class charT, class traits>
+basic_QwerkSerialBuffer<charT,traits>::~basic_QwerkSerialBuffer() {
+	if(using_buf_in)
+		delete [] buf_in;
+	if(using_buf_out)
+		delete [] buf_out;
+}
+
+template <class charT, class traits>
+void
+basic_QwerkSerialBuffer<charT,traits>::open(TeRK::SerialIOServicePrx proxy, std::string port){
+	prx = proxy;
+	terminal = port;
+}
+
+
+
+template <class charT, class traits>
+void
+basic_QwerkSerialBuffer<charT,traits>::in_sync() {
+	if(gptr()>egptr())
+		gbump( egptr()-gptr() );
+	if(gptr()==eback()) {
+		std::cout << "qwerk serial buffer error: in_sync without room in input buffer" << std::endl;
+		return;
+	}
+
+	unsigned long n = gptr()-eback()-1;
+	
+	//std::cout << "in sync called!" << std::endl;
+	//typedef ::std::vector< ::Ice::Byte> ByteArray;
+	while(!prx->isDataAvailable(terminal)){
+		//std::cout << "waiting for input to be available.." << std::endl;
+		std::cout << "." << std::flush;
+		//usleep(5000);
+		usleep(20000);
+	}
+	::TeRK::ByteArray arr = prx->read(terminal, n);
+	
+	charT * temp_buf = (charT *) &(arr[0]);
+	ssize_t used = arr.size();
+
+	//TODO - what if sizeof(charT)>1?  We might need to worry about getting/storing partial char
+	used/=sizeof(charT);
+
+	size_t remain = egptr()-eback()-used;
+	traits::move(eback(),egptr()-remain,remain);
+	traits::copy(egptr()-used,temp_buf,used);
+	gbump( -used );
+}
+
+template <class charT, class traits>
+void
+basic_QwerkSerialBuffer<charT,traits>::out_flush() {
+	::TeRK::ByteArray arr(pbase(), pptr());
+	prx->write(terminal, arr);
+	pbump( -((pptr()-pbase())*sizeof(charT)) );
+}
+
+
+template <class charT, class traits>
+inline std::streamsize
+basic_QwerkSerialBuffer<charT, traits>::showmanyc() {
+	return 1;//(is_open() && canRead) ? 1 : 0;
+}
+
+template <class charT, class traits>
+inline typename basic_QwerkSerialBuffer<charT, traits>::int_type
+basic_QwerkSerialBuffer<charT, traits>::underflow() {
+	in_sync();
+	if(gptr()<egptr())
+		return traits::to_int_type(*gptr());
+//	cout << "UNDERFLOW" << endl;
+	return traits::eof();
+}
+
+template <class charT, class traits>
+inline typename basic_QwerkSerialBuffer<charT, traits>::int_type
+basic_QwerkSerialBuffer<charT, traits>::uflow() {
+	in_sync();
+	if(gptr()<egptr()) {
+		int_type ans = traits::to_int_type(*gptr());
+		gbump(1);
+		return ans;
+	}
+//	cout << "UNDERFLOW" << endl;
+	return traits::eof();
+}
+
+template <class charT, class traits>
+inline typename basic_QwerkSerialBuffer<charT, traits>::int_type
+basic_QwerkSerialBuffer<charT, traits>::overflow(int_type c) { 
+	out_flush();
+	if(!traits::eq_int_type(c, traits::eof())) {
+		*pptr() = c;
+		pbump(1);
+	}
+	return traits::not_eof(c);
+}
+
+template <class charT, class traits>
+inline int
+basic_QwerkSerialBuffer<charT, traits>::sync() {
+	out_flush();
+	//in_sync();
+	return 0;
+}
+
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/TeRKPeerCommon.cc ./local/terk/TeRKPeerCommon.cc
--- ../Tekkotsu_3.0/local/terk/TeRKPeerCommon.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/TeRKPeerCommon.cc	2007-06-03 13:03:23.000000000 -0400
@@ -0,0 +1,13291 @@
+#ifdef HAVE_ICE
+
+// **********************************************************************
+//
+// Copyright (c) 2003-2006 ZeroC, Inc. All rights reserved.
+//
+// This copy of Ice is licensed to you under the terms described in the
+// ICE_LICENSE file included in this distribution.
+//
+// **********************************************************************
+
+// Ice version 3.1.1
+// Generated from file `TeRKPeerCommon.ice'
+
+#include "TeRKPeerCommon.h"
+#include <Ice/LocalException.h>
+#include <Ice/ObjectFactory.h>
+#include <Ice/BasicStream.h>
+#include <Ice/Object.h>
+#include <IceUtil/Iterator.h>
+
+#ifndef ICE_IGNORE_VERSION
+#   if ICE_INT_VERSION / 100 != 301
+#       error Ice version mismatch!
+#   endif
+#   if ICE_INT_VERSION % 100 < 1
+#       error Ice patch level mismatch!
+#   endif
+#endif
+
+static const ::std::string __TeRK__PropertyManager__getProperty_name = "getProperty";
+
+static const ::std::string __TeRK__PropertyManager__getProperties_name = "getProperties";
+
+static const ::std::string __TeRK__PropertyManager__getPropertyKeys_name = "getPropertyKeys";
+
+static const ::std::string __TeRK__PropertyManager__setProperty_name = "setProperty";
+
+static const ::std::string __TeRK__AnalogInController__getState_name = "getState";
+
+static const ::std::string __TeRK__AudioController__execute_name = "execute";
+
+static const ::std::string __TeRK__DigitalInController__getState_name = "getState";
+
+static const ::std::string __TeRK__DigitalOutController__execute_name = "execute";
+
+static const ::std::string __TeRK__LEDController__execute_name = "execute";
+
+static const ::std::string __TeRK__MotorController__execute_name = "execute";
+
+static const ::std::string __TeRK__MotorController__getFrequency_name = "getFrequency";
+
+static const ::std::string __TeRK__MotorController__startMotorBufferRecord_name = "startMotorBufferRecord";
+
+static const ::std::string __TeRK__MotorController__stopMotorBufferRecord_name = "stopMotorBufferRecord";
+
+static const ::std::string __TeRK__MotorController__getMotorBuffers_name = "getMotorBuffers";
+
+static const ::std::string __TeRK__MotorController__setMotorBuffer_name = "setMotorBuffer";
+
+static const ::std::string __TeRK__MotorController__playMotorBuffer_name = "playMotorBuffer";
+
+static const ::std::string __TeRK__MotorController__driveForward_name = "driveForward";
+
+static const ::std::string __TeRK__MotorController__driveBack_name = "driveBack";
+
+static const ::std::string __TeRK__MotorController__spinLeft_name = "spinLeft";
+
+static const ::std::string __TeRK__MotorController__spinRight_name = "spinRight";
+
+static const ::std::string __TeRK__MotorController__setMotorVelocities_name = "setMotorVelocities";
+
+static const ::std::string __TeRK__MotorController__stopMotors_name = "stopMotors";
+
+static const ::std::string __TeRK__ServoController__execute_name = "execute";
+
+static const ::std::string __TeRK__ServoController__cameraTiltUp_name = "cameraTiltUp";
+
+static const ::std::string __TeRK__ServoController__cameraTiltDown_name = "cameraTiltDown";
+
+static const ::std::string __TeRK__ServoController__cameraPanLeft_name = "cameraPanLeft";
+
+static const ::std::string __TeRK__ServoController__cameraPanRight_name = "cameraPanRight";
+
+static const ::std::string __TeRK__ServoController__setServoPositions_name = "setServoPositions";
+
+static const ::std::string __TeRK__ServoController__setServoVelocities_name = "setServoVelocities";
+
+static const ::std::string __TeRK__ServoController__stopServos_name = "stopServos";
+
+static const ::std::string __TeRK__VideoStreamerClient__newFrame_name = "newFrame";
+
+static const ::std::string __TeRK__VideoStreamerServer__startVideoStream_name = "startVideoStream";
+
+static const ::std::string __TeRK__VideoStreamerServer__stopVideoStream_name = "stopVideoStream";
+
+static const ::std::string __TeRK__VideoStreamerServer__startCamera_name = "startCamera";
+
+static const ::std::string __TeRK__VideoStreamerServer__stopCamera_name = "stopCamera";
+
+static const ::std::string __TeRK__VideoStreamerServer__getFrame_name = "getFrame";
+
+static const ::std::string __TeRK__TerkUser__getSupportedServices_name = "getSupportedServices";
+
+static const ::std::string __TeRK__Qwerk__getState_name = "getState";
+
+static const ::std::string __TeRK__Qwerk__execute_name = "execute";
+
+static const ::std::string __TeRK__Qwerk__emergencyStop_name = "emergencyStop";
+
+static const ::std::string __TeRK__Qwerk__getCommandControllerTypeToProxyIdentityMap_name = "getCommandControllerTypeToProxyIdentityMap";
+
+void
+IceInternal::incRef(::TeRK::PropertyManager* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::PropertyManager* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::PropertyManager* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::PropertyManager* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::AbstractCommandController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::AbstractCommandController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::AbstractCommandController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::AbstractCommandController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::AnalogInController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::AnalogInController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::AnalogInController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::AnalogInController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::AudioController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::AudioController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::AudioController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::AudioController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::DigitalInController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::DigitalInController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::DigitalInController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::DigitalInController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::DigitalOutController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::DigitalOutController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::DigitalOutController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::DigitalOutController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::LEDController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::LEDController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::LEDController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::LEDController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::MotorController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::MotorController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::MotorController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::MotorController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::ServoController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::ServoController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::ServoController* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::ServoController* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::VideoStreamerClient* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::VideoStreamerClient* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::VideoStreamerClient* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::VideoStreamerClient* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::VideoStreamerServer* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::VideoStreamerServer* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::VideoStreamerServer* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::VideoStreamerServer* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::TerkUser* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::TerkUser* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::TerkUser* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::TerkUser* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::Qwerk* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::Qwerk* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::Qwerk* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::Qwerk* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::TeRK::TerkClient* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::TeRK::TerkClient* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::TeRK::TerkClient* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::TeRK::TerkClient* p)
+{
+    p->__decRef();
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::PropertyManagerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::PropertyManagerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::PropertyManager;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::PropertyManagerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AbstractCommandControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::AbstractCommandControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::AbstractCommandController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AbstractCommandControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AnalogInControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::AnalogInControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::AnalogInController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AnalogInControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AudioControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::AudioControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::AudioController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AudioControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::DigitalInControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::DigitalInControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::DigitalInController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::DigitalInControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::DigitalOutControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::DigitalOutControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::DigitalOutController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::DigitalOutControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::LEDControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::LEDControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::LEDController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::LEDControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::MotorControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::MotorControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::MotorController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::MotorControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::ServoControllerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::ServoControllerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::ServoController;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::ServoControllerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::VideoStreamerClientPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::VideoStreamerClientPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::VideoStreamerClient;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::VideoStreamerClientPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::VideoStreamerServerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::VideoStreamerServerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::VideoStreamerServer;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::VideoStreamerServerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::TerkUserPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::TerkUserPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::TerkUser;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::TerkUserPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::QwerkPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::QwerkPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::Qwerk;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::QwerkPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::TerkClientPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::TerkClientPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::TeRK::TerkClient;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::TerkClientPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::ImageFormat v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::ImageFormat& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::ImageFormat>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::AudioMode v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::AudioMode& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::AudioMode>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::LEDMode v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::LEDMode& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::LEDMode>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::MotorMode v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::MotorMode& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::MotorMode>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, ::TeRK::ServoMode v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::ServoMode& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::TeRK::ServoMode>(val);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::LEDMode* begin, const ::TeRK::LEDMode* end, ::TeRK::__U__LEDModeArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	::TeRK::__write(__os, begin[i]);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::LEDModeArray& v, ::TeRK::__U__LEDModeArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->checkFixedSeq(sz, 1);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	::TeRK::__read(__is, v[i]);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::MotorMode* begin, const ::TeRK::MotorMode* end, ::TeRK::__U__MotorModeArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	::TeRK::__write(__os, begin[i]);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::MotorModeArray& v, ::TeRK::__U__MotorModeArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->checkFixedSeq(sz, 1);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	::TeRK::__read(__is, v[i]);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::ServoMode* begin, const ::TeRK::ServoMode* end, ::TeRK::__U__ServoModeArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	::TeRK::__write(__os, begin[i]);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::ServoModeArray& v, ::TeRK::__U__ServoModeArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->checkFixedSeq(sz, 1);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	::TeRK::__read(__is, v[i]);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::ProxyTypeIdToIdentityMap& v, ::TeRK::__U__ProxyTypeIdToIdentityMap)
+{
+    __os->writeSize(::Ice::Int(v.size()));
+    ::TeRK::ProxyTypeIdToIdentityMap::const_iterator p;
+    for(p = v.begin(); p != v.end(); ++p)
+    {
+	__os->write(p->first);
+	p->second.__write(__os);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::ProxyTypeIdToIdentityMap& v, ::TeRK::__U__ProxyTypeIdToIdentityMap)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    while(sz--)
+    {
+	::std::pair<const  ::std::string, ::Ice::Identity> pair;
+	__is->read(const_cast< ::std::string&>(pair.first));
+	::TeRK::ProxyTypeIdToIdentityMap::iterator __i = v.insert(v.end(), pair);
+	__i->second.__read(__is);
+    }
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::PropertyMap& v, ::TeRK::__U__PropertyMap)
+{
+    __os->writeSize(::Ice::Int(v.size()));
+    ::TeRK::PropertyMap::const_iterator p;
+    for(p = v.begin(); p != v.end(); ++p)
+    {
+	__os->write(p->first);
+	__os->write(p->second);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::PropertyMap& v, ::TeRK::__U__PropertyMap)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    while(sz--)
+    {
+	::std::pair<const  ::std::string, ::std::string> pair;
+	__is->read(const_cast< ::std::string&>(pair.first));
+	::TeRK::PropertyMap::iterator __i = v.insert(v.end(), pair);
+	__is->read(__i->second);
+    }
+}
+
+TeRK::GenericError::GenericError(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    UserException(),
+#else
+    ::Ice::UserException(),
+#endif
+    reason(__ice_reason)
+{
+}
+
+static const char* __TeRK__GenericError_name = "TeRK::GenericError";
+
+const ::std::string
+TeRK::GenericError::ice_name() const
+{
+    return __TeRK__GenericError_name;
+}
+
+::Ice::Exception*
+TeRK::GenericError::ice_clone() const
+{
+    return new GenericError(*this);
+}
+
+void
+TeRK::GenericError::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::GenericError::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::GenericError"), false);
+    __os->startWriteSlice();
+    __os->write(reason);
+    __os->endWriteSlice();
+}
+
+void
+TeRK::GenericError::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->read(reason);
+    __is->endReadSlice();
+}
+
+void
+TeRK::GenericError::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::GenericError was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::GenericError::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::GenericError was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__GenericError : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::GenericError();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__GenericError__Ptr = new __F__TeRK__GenericError;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::GenericError::ice_factory()
+{
+    return __F__TeRK__GenericError__Ptr;
+}
+
+class __F__TeRK__GenericError__Init
+{
+public:
+
+    __F__TeRK__GenericError__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::GenericError", ::TeRK::GenericError::ice_factory());
+    }
+
+    ~__F__TeRK__GenericError__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::GenericError");
+    }
+};
+
+static __F__TeRK__GenericError__Init __F__TeRK__GenericError__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__GenericError__initializer() {} }
+#endif
+
+TeRK::TeRKException::TeRKException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    UserException(),
+#else
+    ::Ice::UserException(),
+#endif
+    reason(__ice_reason)
+{
+}
+
+static const char* __TeRK__TeRKException_name = "TeRK::TeRKException";
+
+const ::std::string
+TeRK::TeRKException::ice_name() const
+{
+    return __TeRK__TeRKException_name;
+}
+
+::Ice::Exception*
+TeRK::TeRKException::ice_clone() const
+{
+    return new TeRKException(*this);
+}
+
+void
+TeRK::TeRKException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::TeRKException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::TeRKException"), false);
+    __os->startWriteSlice();
+    __os->write(reason);
+    __os->endWriteSlice();
+}
+
+void
+TeRK::TeRKException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->read(reason);
+    __is->endReadSlice();
+}
+
+void
+TeRK::TeRKException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::TeRKException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::TeRKException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::TeRKException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__TeRKException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::TeRKException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__TeRKException__Ptr = new __F__TeRK__TeRKException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::TeRKException::ice_factory()
+{
+    return __F__TeRK__TeRKException__Ptr;
+}
+
+class __F__TeRK__TeRKException__Init
+{
+public:
+
+    __F__TeRK__TeRKException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::TeRKException", ::TeRK::TeRKException::ice_factory());
+    }
+
+    ~__F__TeRK__TeRKException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::TeRKException");
+    }
+};
+
+static __F__TeRK__TeRKException__Init __F__TeRK__TeRKException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__TeRKException__initializer() {} }
+#endif
+
+TeRK::MotorException::MotorException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException(__ice_reason)
+#else
+    ::TeRK::TeRKException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__MotorException_name = "TeRK::MotorException";
+
+const ::std::string
+TeRK::MotorException::ice_name() const
+{
+    return __TeRK__MotorException_name;
+}
+
+::Ice::Exception*
+TeRK::MotorException::ice_clone() const
+{
+    return new MotorException(*this);
+}
+
+void
+TeRK::MotorException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::MotorException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::MotorException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__write(__os);
+#else
+    ::TeRK::TeRKException::__write(__os);
+#endif
+}
+
+void
+TeRK::MotorException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__read(__is, true);
+#else
+    ::TeRK::TeRKException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::MotorException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::MotorException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::MotorException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::MotorException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__MotorException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::MotorException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__MotorException__Ptr = new __F__TeRK__MotorException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::MotorException::ice_factory()
+{
+    return __F__TeRK__MotorException__Ptr;
+}
+
+class __F__TeRK__MotorException__Init
+{
+public:
+
+    __F__TeRK__MotorException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::MotorException", ::TeRK::MotorException::ice_factory());
+    }
+
+    ~__F__TeRK__MotorException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::MotorException");
+    }
+};
+
+static __F__TeRK__MotorException__Init __F__TeRK__MotorException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__MotorException__initializer() {} }
+#endif
+
+TeRK::VideoException::VideoException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException(__ice_reason)
+#else
+    ::TeRK::TeRKException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__VideoException_name = "TeRK::VideoException";
+
+const ::std::string
+TeRK::VideoException::ice_name() const
+{
+    return __TeRK__VideoException_name;
+}
+
+::Ice::Exception*
+TeRK::VideoException::ice_clone() const
+{
+    return new VideoException(*this);
+}
+
+void
+TeRK::VideoException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::VideoException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::VideoException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__write(__os);
+#else
+    ::TeRK::TeRKException::__write(__os);
+#endif
+}
+
+void
+TeRK::VideoException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__read(__is, true);
+#else
+    ::TeRK::TeRKException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::VideoException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::VideoException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::VideoException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::VideoException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__VideoException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::VideoException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__VideoException__Ptr = new __F__TeRK__VideoException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::VideoException::ice_factory()
+{
+    return __F__TeRK__VideoException__Ptr;
+}
+
+class __F__TeRK__VideoException__Init
+{
+public:
+
+    __F__TeRK__VideoException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::VideoException", ::TeRK::VideoException::ice_factory());
+    }
+
+    ~__F__TeRK__VideoException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::VideoException");
+    }
+};
+
+static __F__TeRK__VideoException__Init __F__TeRK__VideoException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__VideoException__initializer() {} }
+#endif
+
+TeRK::ReadOnlyPropertyException::ReadOnlyPropertyException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException(__ice_reason)
+#else
+    ::TeRK::TeRKException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__ReadOnlyPropertyException_name = "TeRK::ReadOnlyPropertyException";
+
+const ::std::string
+TeRK::ReadOnlyPropertyException::ice_name() const
+{
+    return __TeRK__ReadOnlyPropertyException_name;
+}
+
+::Ice::Exception*
+TeRK::ReadOnlyPropertyException::ice_clone() const
+{
+    return new ReadOnlyPropertyException(*this);
+}
+
+void
+TeRK::ReadOnlyPropertyException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::ReadOnlyPropertyException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::ReadOnlyPropertyException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__write(__os);
+#else
+    ::TeRK::TeRKException::__write(__os);
+#endif
+}
+
+void
+TeRK::ReadOnlyPropertyException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__read(__is, true);
+#else
+    ::TeRK::TeRKException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::ReadOnlyPropertyException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::ReadOnlyPropertyException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::ReadOnlyPropertyException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::ReadOnlyPropertyException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__ReadOnlyPropertyException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::ReadOnlyPropertyException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__ReadOnlyPropertyException__Ptr = new __F__TeRK__ReadOnlyPropertyException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::ReadOnlyPropertyException::ice_factory()
+{
+    return __F__TeRK__ReadOnlyPropertyException__Ptr;
+}
+
+class __F__TeRK__ReadOnlyPropertyException__Init
+{
+public:
+
+    __F__TeRK__ReadOnlyPropertyException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::ReadOnlyPropertyException", ::TeRK::ReadOnlyPropertyException::ice_factory());
+    }
+
+    ~__F__TeRK__ReadOnlyPropertyException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::ReadOnlyPropertyException");
+    }
+};
+
+static __F__TeRK__ReadOnlyPropertyException__Init __F__TeRK__ReadOnlyPropertyException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__ReadOnlyPropertyException__initializer() {} }
+#endif
+
+TeRK::CommandException::CommandException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException(__ice_reason)
+#else
+    ::TeRK::TeRKException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__CommandException_name = "TeRK::CommandException";
+
+const ::std::string
+TeRK::CommandException::ice_name() const
+{
+    return __TeRK__CommandException_name;
+}
+
+::Ice::Exception*
+TeRK::CommandException::ice_clone() const
+{
+    return new CommandException(*this);
+}
+
+void
+TeRK::CommandException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::CommandException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::CommandException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__write(__os);
+#else
+    ::TeRK::TeRKException::__write(__os);
+#endif
+}
+
+void
+TeRK::CommandException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    TeRKException::__read(__is, true);
+#else
+    ::TeRK::TeRKException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::CommandException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::CommandException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::CommandException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::CommandException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__CommandException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::CommandException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__CommandException__Ptr = new __F__TeRK__CommandException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::CommandException::ice_factory()
+{
+    return __F__TeRK__CommandException__Ptr;
+}
+
+class __F__TeRK__CommandException__Init
+{
+public:
+
+    __F__TeRK__CommandException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::CommandException", ::TeRK::CommandException::ice_factory());
+    }
+
+    ~__F__TeRK__CommandException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::CommandException");
+    }
+};
+
+static __F__TeRK__CommandException__Init __F__TeRK__CommandException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__CommandException__initializer() {} }
+#endif
+
+TeRK::AudioCommandException::AudioCommandException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException(__ice_reason)
+#else
+    ::TeRK::CommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__AudioCommandException_name = "TeRK::AudioCommandException";
+
+const ::std::string
+TeRK::AudioCommandException::ice_name() const
+{
+    return __TeRK__AudioCommandException_name;
+}
+
+::Ice::Exception*
+TeRK::AudioCommandException::ice_clone() const
+{
+    return new AudioCommandException(*this);
+}
+
+void
+TeRK::AudioCommandException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::AudioCommandException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::AudioCommandException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__write(__os);
+#else
+    ::TeRK::CommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::AudioCommandException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__read(__is, true);
+#else
+    ::TeRK::CommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::AudioCommandException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::AudioCommandException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::AudioCommandException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::AudioCommandException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__AudioCommandException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::AudioCommandException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__AudioCommandException__Ptr = new __F__TeRK__AudioCommandException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::AudioCommandException::ice_factory()
+{
+    return __F__TeRK__AudioCommandException__Ptr;
+}
+
+class __F__TeRK__AudioCommandException__Init
+{
+public:
+
+    __F__TeRK__AudioCommandException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::AudioCommandException", ::TeRK::AudioCommandException::ice_factory());
+    }
+
+    ~__F__TeRK__AudioCommandException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::AudioCommandException");
+    }
+};
+
+static __F__TeRK__AudioCommandException__Init __F__TeRK__AudioCommandException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__AudioCommandException__initializer() {} }
+#endif
+
+TeRK::AudioCommandQueueFullException::AudioCommandQueueFullException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    AudioCommandException(__ice_reason)
+#else
+    ::TeRK::AudioCommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__AudioCommandQueueFullException_name = "TeRK::AudioCommandQueueFullException";
+
+const ::std::string
+TeRK::AudioCommandQueueFullException::ice_name() const
+{
+    return __TeRK__AudioCommandQueueFullException_name;
+}
+
+::Ice::Exception*
+TeRK::AudioCommandQueueFullException::ice_clone() const
+{
+    return new AudioCommandQueueFullException(*this);
+}
+
+void
+TeRK::AudioCommandQueueFullException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::AudioCommandQueueFullException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::AudioCommandQueueFullException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    AudioCommandException::__write(__os);
+#else
+    ::TeRK::AudioCommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::AudioCommandQueueFullException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    AudioCommandException::__read(__is, true);
+#else
+    ::TeRK::AudioCommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::AudioCommandQueueFullException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::AudioCommandQueueFullException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::AudioCommandQueueFullException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::AudioCommandQueueFullException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__AudioCommandQueueFullException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::AudioCommandQueueFullException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__AudioCommandQueueFullException__Ptr = new __F__TeRK__AudioCommandQueueFullException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::AudioCommandQueueFullException::ice_factory()
+{
+    return __F__TeRK__AudioCommandQueueFullException__Ptr;
+}
+
+class __F__TeRK__AudioCommandQueueFullException__Init
+{
+public:
+
+    __F__TeRK__AudioCommandQueueFullException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::AudioCommandQueueFullException", ::TeRK::AudioCommandQueueFullException::ice_factory());
+    }
+
+    ~__F__TeRK__AudioCommandQueueFullException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::AudioCommandQueueFullException");
+    }
+};
+
+static __F__TeRK__AudioCommandQueueFullException__Init __F__TeRK__AudioCommandQueueFullException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__AudioCommandQueueFullException__initializer() {} }
+#endif
+
+TeRK::AudioFileTooLargeException::AudioFileTooLargeException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    AudioCommandException(__ice_reason)
+#else
+    ::TeRK::AudioCommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__AudioFileTooLargeException_name = "TeRK::AudioFileTooLargeException";
+
+const ::std::string
+TeRK::AudioFileTooLargeException::ice_name() const
+{
+    return __TeRK__AudioFileTooLargeException_name;
+}
+
+::Ice::Exception*
+TeRK::AudioFileTooLargeException::ice_clone() const
+{
+    return new AudioFileTooLargeException(*this);
+}
+
+void
+TeRK::AudioFileTooLargeException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::AudioFileTooLargeException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::AudioFileTooLargeException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    AudioCommandException::__write(__os);
+#else
+    ::TeRK::AudioCommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::AudioFileTooLargeException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    AudioCommandException::__read(__is, true);
+#else
+    ::TeRK::AudioCommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::AudioFileTooLargeException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::AudioFileTooLargeException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::AudioFileTooLargeException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::AudioFileTooLargeException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__AudioFileTooLargeException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::AudioFileTooLargeException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__AudioFileTooLargeException__Ptr = new __F__TeRK__AudioFileTooLargeException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::AudioFileTooLargeException::ice_factory()
+{
+    return __F__TeRK__AudioFileTooLargeException__Ptr;
+}
+
+class __F__TeRK__AudioFileTooLargeException__Init
+{
+public:
+
+    __F__TeRK__AudioFileTooLargeException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::AudioFileTooLargeException", ::TeRK::AudioFileTooLargeException::ice_factory());
+    }
+
+    ~__F__TeRK__AudioFileTooLargeException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::AudioFileTooLargeException");
+    }
+};
+
+static __F__TeRK__AudioFileTooLargeException__Init __F__TeRK__AudioFileTooLargeException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__AudioFileTooLargeException__initializer() {} }
+#endif
+
+TeRK::DigitalOutCommandException::DigitalOutCommandException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException(__ice_reason)
+#else
+    ::TeRK::CommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__DigitalOutCommandException_name = "TeRK::DigitalOutCommandException";
+
+const ::std::string
+TeRK::DigitalOutCommandException::ice_name() const
+{
+    return __TeRK__DigitalOutCommandException_name;
+}
+
+::Ice::Exception*
+TeRK::DigitalOutCommandException::ice_clone() const
+{
+    return new DigitalOutCommandException(*this);
+}
+
+void
+TeRK::DigitalOutCommandException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::DigitalOutCommandException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::DigitalOutCommandException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__write(__os);
+#else
+    ::TeRK::CommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::DigitalOutCommandException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__read(__is, true);
+#else
+    ::TeRK::CommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::DigitalOutCommandException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::DigitalOutCommandException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::DigitalOutCommandException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::DigitalOutCommandException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__DigitalOutCommandException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::DigitalOutCommandException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__DigitalOutCommandException__Ptr = new __F__TeRK__DigitalOutCommandException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::DigitalOutCommandException::ice_factory()
+{
+    return __F__TeRK__DigitalOutCommandException__Ptr;
+}
+
+class __F__TeRK__DigitalOutCommandException__Init
+{
+public:
+
+    __F__TeRK__DigitalOutCommandException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::DigitalOutCommandException", ::TeRK::DigitalOutCommandException::ice_factory());
+    }
+
+    ~__F__TeRK__DigitalOutCommandException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::DigitalOutCommandException");
+    }
+};
+
+static __F__TeRK__DigitalOutCommandException__Init __F__TeRK__DigitalOutCommandException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__DigitalOutCommandException__initializer() {} }
+#endif
+
+TeRK::LEDCommandException::LEDCommandException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException(__ice_reason)
+#else
+    ::TeRK::CommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__LEDCommandException_name = "TeRK::LEDCommandException";
+
+const ::std::string
+TeRK::LEDCommandException::ice_name() const
+{
+    return __TeRK__LEDCommandException_name;
+}
+
+::Ice::Exception*
+TeRK::LEDCommandException::ice_clone() const
+{
+    return new LEDCommandException(*this);
+}
+
+void
+TeRK::LEDCommandException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::LEDCommandException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::LEDCommandException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__write(__os);
+#else
+    ::TeRK::CommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::LEDCommandException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__read(__is, true);
+#else
+    ::TeRK::CommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::LEDCommandException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::LEDCommandException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::LEDCommandException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::LEDCommandException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__LEDCommandException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::LEDCommandException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__LEDCommandException__Ptr = new __F__TeRK__LEDCommandException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::LEDCommandException::ice_factory()
+{
+    return __F__TeRK__LEDCommandException__Ptr;
+}
+
+class __F__TeRK__LEDCommandException__Init
+{
+public:
+
+    __F__TeRK__LEDCommandException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::LEDCommandException", ::TeRK::LEDCommandException::ice_factory());
+    }
+
+    ~__F__TeRK__LEDCommandException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::LEDCommandException");
+    }
+};
+
+static __F__TeRK__LEDCommandException__Init __F__TeRK__LEDCommandException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__LEDCommandException__initializer() {} }
+#endif
+
+TeRK::MotorCommandException::MotorCommandException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException(__ice_reason)
+#else
+    ::TeRK::CommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__MotorCommandException_name = "TeRK::MotorCommandException";
+
+const ::std::string
+TeRK::MotorCommandException::ice_name() const
+{
+    return __TeRK__MotorCommandException_name;
+}
+
+::Ice::Exception*
+TeRK::MotorCommandException::ice_clone() const
+{
+    return new MotorCommandException(*this);
+}
+
+void
+TeRK::MotorCommandException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::MotorCommandException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::MotorCommandException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__write(__os);
+#else
+    ::TeRK::CommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::MotorCommandException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__read(__is, true);
+#else
+    ::TeRK::CommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::MotorCommandException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::MotorCommandException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::MotorCommandException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::MotorCommandException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__MotorCommandException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::MotorCommandException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__MotorCommandException__Ptr = new __F__TeRK__MotorCommandException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::MotorCommandException::ice_factory()
+{
+    return __F__TeRK__MotorCommandException__Ptr;
+}
+
+class __F__TeRK__MotorCommandException__Init
+{
+public:
+
+    __F__TeRK__MotorCommandException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::MotorCommandException", ::TeRK::MotorCommandException::ice_factory());
+    }
+
+    ~__F__TeRK__MotorCommandException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::MotorCommandException");
+    }
+};
+
+static __F__TeRK__MotorCommandException__Init __F__TeRK__MotorCommandException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__MotorCommandException__initializer() {} }
+#endif
+
+TeRK::ServoCommandException::ServoCommandException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException(__ice_reason)
+#else
+    ::TeRK::CommandException(__ice_reason)
+#endif
+{
+}
+
+static const char* __TeRK__ServoCommandException_name = "TeRK::ServoCommandException";
+
+const ::std::string
+TeRK::ServoCommandException::ice_name() const
+{
+    return __TeRK__ServoCommandException_name;
+}
+
+::Ice::Exception*
+TeRK::ServoCommandException::ice_clone() const
+{
+    return new ServoCommandException(*this);
+}
+
+void
+TeRK::ServoCommandException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+TeRK::ServoCommandException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::TeRK::ServoCommandException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__write(__os);
+#else
+    ::TeRK::CommandException::__write(__os);
+#endif
+}
+
+void
+TeRK::ServoCommandException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    CommandException::__read(__is, true);
+#else
+    ::TeRK::CommandException::__read(__is, true);
+#endif
+}
+
+void
+TeRK::ServoCommandException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::ServoCommandException was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::ServoCommandException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception TeRK::ServoCommandException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__TeRK__ServoCommandException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::TeRK::ServoCommandException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__TeRK__ServoCommandException__Ptr = new __F__TeRK__ServoCommandException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+TeRK::ServoCommandException::ice_factory()
+{
+    return __F__TeRK__ServoCommandException__Ptr;
+}
+
+class __F__TeRK__ServoCommandException__Init
+{
+public:
+
+    __F__TeRK__ServoCommandException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::TeRK::ServoCommandException", ::TeRK::ServoCommandException::ice_factory());
+    }
+
+    ~__F__TeRK__ServoCommandException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::TeRK::ServoCommandException");
+    }
+};
+
+static __F__TeRK__ServoCommandException__Init __F__TeRK__ServoCommandException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__TeRK__ServoCommandException__initializer() {} }
+#endif
+
+bool
+TeRK::MotorBuffer::operator==(const MotorBuffer& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::MotorBuffer::operator!=(const MotorBuffer& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(values != __rhs.values)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::MotorBuffer::operator<(const MotorBuffer& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(values < __rhs.values)
+    {
+	return true;
+    }
+    else if(__rhs.values < values)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::MotorBuffer::__write(::IceInternal::BasicStream* __os) const
+{
+    if(values.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&values[0], &values[0] + values.size());
+    }
+}
+
+void
+TeRK::MotorBuffer::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(values);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::MotorBuffer* begin, const ::TeRK::MotorBuffer* end, ::TeRK::__U__MotorBufferArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	begin[i].__write(__os);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::MotorBufferArray& v, ::TeRK::__U__MotorBufferArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->startSeq(sz, 1);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	v[i].__read(__is);
+	__is->checkSeq();
+	__is->endElement();
+    }
+    __is->endSeq(sz);
+}
+
+bool
+TeRK::Image::operator==(const Image& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::Image::operator!=(const Image& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(height != __rhs.height)
+    {
+	return true;
+    }
+    if(width != __rhs.width)
+    {
+	return true;
+    }
+    if(frameNum != __rhs.frameNum)
+    {
+	return true;
+    }
+    if(format != __rhs.format)
+    {
+	return true;
+    }
+    if(data != __rhs.data)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::Image::operator<(const Image& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(height < __rhs.height)
+    {
+	return true;
+    }
+    else if(__rhs.height < height)
+    {
+	return false;
+    }
+    if(width < __rhs.width)
+    {
+	return true;
+    }
+    else if(__rhs.width < width)
+    {
+	return false;
+    }
+    if(frameNum < __rhs.frameNum)
+    {
+	return true;
+    }
+    else if(__rhs.frameNum < frameNum)
+    {
+	return false;
+    }
+    if(format < __rhs.format)
+    {
+	return true;
+    }
+    else if(__rhs.format < format)
+    {
+	return false;
+    }
+    if(data < __rhs.data)
+    {
+	return true;
+    }
+    else if(__rhs.data < data)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::Image::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(height);
+    __os->write(width);
+    __os->write(frameNum);
+    ::TeRK::__write(__os, format);
+    if(data.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&data[0], &data[0] + data.size());
+    }
+}
+
+void
+TeRK::Image::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(height);
+    __is->read(width);
+    __is->read(frameNum);
+    ::TeRK::__read(__is, format);
+    ::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> ___data;
+    __is->read(___data);
+    ::std::vector< ::Ice::Byte>(___data.first, ___data.second).swap(data);
+}
+
+bool
+TeRK::AnalogInState::operator==(const AnalogInState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::AnalogInState::operator!=(const AnalogInState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(analogInValues != __rhs.analogInValues)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::AnalogInState::operator<(const AnalogInState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(analogInValues < __rhs.analogInValues)
+    {
+	return true;
+    }
+    else if(__rhs.analogInValues < analogInValues)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::AnalogInState::__write(::IceInternal::BasicStream* __os) const
+{
+    if(analogInValues.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&analogInValues[0], &analogInValues[0] + analogInValues.size());
+    }
+}
+
+void
+TeRK::AnalogInState::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(analogInValues);
+}
+
+bool
+TeRK::BatteryState::operator==(const BatteryState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::BatteryState::operator!=(const BatteryState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(batteryVoltage != __rhs.batteryVoltage)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::BatteryState::operator<(const BatteryState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(batteryVoltage < __rhs.batteryVoltage)
+    {
+	return true;
+    }
+    else if(__rhs.batteryVoltage < batteryVoltage)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::BatteryState::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(batteryVoltage);
+}
+
+void
+TeRK::BatteryState::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(batteryVoltage);
+}
+
+bool
+TeRK::ButtonState::operator==(const ButtonState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::ButtonState::operator!=(const ButtonState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(buttonStates != __rhs.buttonStates)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::ButtonState::operator<(const ButtonState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(buttonStates < __rhs.buttonStates)
+    {
+	return true;
+    }
+    else if(__rhs.buttonStates < buttonStates)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::ButtonState::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(buttonStates);
+}
+
+void
+TeRK::ButtonState::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(buttonStates);
+}
+
+bool
+TeRK::DigitalInState::operator==(const DigitalInState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::DigitalInState::operator!=(const DigitalInState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(digitalInStates != __rhs.digitalInStates)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::DigitalInState::operator<(const DigitalInState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(digitalInStates < __rhs.digitalInStates)
+    {
+	return true;
+    }
+    else if(__rhs.digitalInStates < digitalInStates)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::DigitalInState::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(digitalInStates);
+}
+
+void
+TeRK::DigitalInState::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(digitalInStates);
+}
+
+bool
+TeRK::MotorState::operator==(const MotorState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::MotorState::operator!=(const MotorState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(motorVelocities != __rhs.motorVelocities)
+    {
+	return true;
+    }
+    if(motorPositions != __rhs.motorPositions)
+    {
+	return true;
+    }
+    if(motorCurrents != __rhs.motorCurrents)
+    {
+	return true;
+    }
+    if(motorDutyCycles != __rhs.motorDutyCycles)
+    {
+	return true;
+    }
+    if(motorDone != __rhs.motorDone)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::MotorState::operator<(const MotorState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(motorVelocities < __rhs.motorVelocities)
+    {
+	return true;
+    }
+    else if(__rhs.motorVelocities < motorVelocities)
+    {
+	return false;
+    }
+    if(motorPositions < __rhs.motorPositions)
+    {
+	return true;
+    }
+    else if(__rhs.motorPositions < motorPositions)
+    {
+	return false;
+    }
+    if(motorCurrents < __rhs.motorCurrents)
+    {
+	return true;
+    }
+    else if(__rhs.motorCurrents < motorCurrents)
+    {
+	return false;
+    }
+    if(motorDutyCycles < __rhs.motorDutyCycles)
+    {
+	return true;
+    }
+    else if(__rhs.motorDutyCycles < motorDutyCycles)
+    {
+	return false;
+    }
+    if(motorDone < __rhs.motorDone)
+    {
+	return true;
+    }
+    else if(__rhs.motorDone < motorDone)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::MotorState::__write(::IceInternal::BasicStream* __os) const
+{
+    if(motorVelocities.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorVelocities[0], &motorVelocities[0] + motorVelocities.size());
+    }
+    if(motorPositions.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorPositions[0], &motorPositions[0] + motorPositions.size());
+    }
+    if(motorCurrents.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorCurrents[0], &motorCurrents[0] + motorCurrents.size());
+    }
+    if(motorDutyCycles.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorDutyCycles[0], &motorDutyCycles[0] + motorDutyCycles.size());
+    }
+    __os->write(motorDone);
+}
+
+void
+TeRK::MotorState::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(motorVelocities);
+    __is->read(motorPositions);
+    __is->read(motorCurrents);
+    __is->read(motorDutyCycles);
+    __is->read(motorDone);
+}
+
+bool
+TeRK::ServoState::operator==(const ServoState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::ServoState::operator!=(const ServoState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(servoPositions != __rhs.servoPositions)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::ServoState::operator<(const ServoState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(servoPositions < __rhs.servoPositions)
+    {
+	return true;
+    }
+    else if(__rhs.servoPositions < servoPositions)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::ServoState::__write(::IceInternal::BasicStream* __os) const
+{
+    if(servoPositions.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&servoPositions[0], &servoPositions[0] + servoPositions.size());
+    }
+}
+
+void
+TeRK::ServoState::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(servoPositions);
+}
+
+bool
+TeRK::QwerkState::operator==(const QwerkState& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::QwerkState::operator!=(const QwerkState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(analogIn != __rhs.analogIn)
+    {
+	return true;
+    }
+    if(battery != __rhs.battery)
+    {
+	return true;
+    }
+    if(button != __rhs.button)
+    {
+	return true;
+    }
+    if(digitalIn != __rhs.digitalIn)
+    {
+	return true;
+    }
+    if(motor != __rhs.motor)
+    {
+	return true;
+    }
+    if(servo != __rhs.servo)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::QwerkState::operator<(const QwerkState& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(analogIn < __rhs.analogIn)
+    {
+	return true;
+    }
+    else if(__rhs.analogIn < analogIn)
+    {
+	return false;
+    }
+    if(battery < __rhs.battery)
+    {
+	return true;
+    }
+    else if(__rhs.battery < battery)
+    {
+	return false;
+    }
+    if(button < __rhs.button)
+    {
+	return true;
+    }
+    else if(__rhs.button < button)
+    {
+	return false;
+    }
+    if(digitalIn < __rhs.digitalIn)
+    {
+	return true;
+    }
+    else if(__rhs.digitalIn < digitalIn)
+    {
+	return false;
+    }
+    if(motor < __rhs.motor)
+    {
+	return true;
+    }
+    else if(__rhs.motor < motor)
+    {
+	return false;
+    }
+    if(servo < __rhs.servo)
+    {
+	return true;
+    }
+    else if(__rhs.servo < servo)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::QwerkState::__write(::IceInternal::BasicStream* __os) const
+{
+    analogIn.__write(__os);
+    battery.__write(__os);
+    button.__write(__os);
+    digitalIn.__write(__os);
+    motor.__write(__os);
+    servo.__write(__os);
+}
+
+void
+TeRK::QwerkState::__read(::IceInternal::BasicStream* __is)
+{
+    analogIn.__read(__is);
+    battery.__read(__is);
+    button.__read(__is);
+    digitalIn.__read(__is);
+    motor.__read(__is);
+    servo.__read(__is);
+}
+
+bool
+TeRK::AudioCommand::operator==(const AudioCommand& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::AudioCommand::operator!=(const AudioCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(mode != __rhs.mode)
+    {
+	return true;
+    }
+    if(frequency != __rhs.frequency)
+    {
+	return true;
+    }
+    if(amplitude != __rhs.amplitude)
+    {
+	return true;
+    }
+    if(duration != __rhs.duration)
+    {
+	return true;
+    }
+    if(sound != __rhs.sound)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::AudioCommand::operator<(const AudioCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(mode < __rhs.mode)
+    {
+	return true;
+    }
+    else if(__rhs.mode < mode)
+    {
+	return false;
+    }
+    if(frequency < __rhs.frequency)
+    {
+	return true;
+    }
+    else if(__rhs.frequency < frequency)
+    {
+	return false;
+    }
+    if(amplitude < __rhs.amplitude)
+    {
+	return true;
+    }
+    else if(__rhs.amplitude < amplitude)
+    {
+	return false;
+    }
+    if(duration < __rhs.duration)
+    {
+	return true;
+    }
+    else if(__rhs.duration < duration)
+    {
+	return false;
+    }
+    if(sound < __rhs.sound)
+    {
+	return true;
+    }
+    else if(__rhs.sound < sound)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::AudioCommand::__write(::IceInternal::BasicStream* __os) const
+{
+    ::TeRK::__write(__os, mode);
+    __os->write(frequency);
+    __os->write(amplitude);
+    __os->write(duration);
+    if(sound.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&sound[0], &sound[0] + sound.size());
+    }
+}
+
+void
+TeRK::AudioCommand::__read(::IceInternal::BasicStream* __is)
+{
+    ::TeRK::__read(__is, mode);
+    __is->read(frequency);
+    __is->read(amplitude);
+    __is->read(duration);
+    ::std::pair<const ::Ice::Byte*, const ::Ice::Byte*> ___sound;
+    __is->read(___sound);
+    ::std::vector< ::Ice::Byte>(___sound.first, ___sound.second).swap(sound);
+}
+
+bool
+TeRK::DigitalOutCommand::operator==(const DigitalOutCommand& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::DigitalOutCommand::operator!=(const DigitalOutCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(digitalOutMask != __rhs.digitalOutMask)
+    {
+	return true;
+    }
+    if(digitalOutValues != __rhs.digitalOutValues)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::DigitalOutCommand::operator<(const DigitalOutCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(digitalOutMask < __rhs.digitalOutMask)
+    {
+	return true;
+    }
+    else if(__rhs.digitalOutMask < digitalOutMask)
+    {
+	return false;
+    }
+    if(digitalOutValues < __rhs.digitalOutValues)
+    {
+	return true;
+    }
+    else if(__rhs.digitalOutValues < digitalOutValues)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::DigitalOutCommand::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(digitalOutMask);
+    __os->write(digitalOutValues);
+}
+
+void
+TeRK::DigitalOutCommand::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(digitalOutMask);
+    __is->read(digitalOutValues);
+}
+
+bool
+TeRK::LEDCommand::operator==(const LEDCommand& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::LEDCommand::operator!=(const LEDCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(ledMask != __rhs.ledMask)
+    {
+	return true;
+    }
+    if(ledModes != __rhs.ledModes)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::LEDCommand::operator<(const LEDCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(ledMask < __rhs.ledMask)
+    {
+	return true;
+    }
+    else if(__rhs.ledMask < ledMask)
+    {
+	return false;
+    }
+    if(ledModes < __rhs.ledModes)
+    {
+	return true;
+    }
+    else if(__rhs.ledModes < ledModes)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::LEDCommand::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(ledMask);
+    if(ledModes.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	::TeRK::__write(__os, &ledModes[0], &ledModes[0] + ledModes.size(), ::TeRK::__U__LEDModeArray());
+    }
+}
+
+void
+TeRK::LEDCommand::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(ledMask);
+    ::TeRK::__read(__is, ledModes, ::TeRK::__U__LEDModeArray());
+}
+
+bool
+TeRK::MotorCommand::operator==(const MotorCommand& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::MotorCommand::operator!=(const MotorCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(motorMask != __rhs.motorMask)
+    {
+	return true;
+    }
+    if(motorModes != __rhs.motorModes)
+    {
+	return true;
+    }
+    if(motorPositions != __rhs.motorPositions)
+    {
+	return true;
+    }
+    if(motorVelocities != __rhs.motorVelocities)
+    {
+	return true;
+    }
+    if(motorAccelerations != __rhs.motorAccelerations)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::MotorCommand::operator<(const MotorCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(motorMask < __rhs.motorMask)
+    {
+	return true;
+    }
+    else if(__rhs.motorMask < motorMask)
+    {
+	return false;
+    }
+    if(motorModes < __rhs.motorModes)
+    {
+	return true;
+    }
+    else if(__rhs.motorModes < motorModes)
+    {
+	return false;
+    }
+    if(motorPositions < __rhs.motorPositions)
+    {
+	return true;
+    }
+    else if(__rhs.motorPositions < motorPositions)
+    {
+	return false;
+    }
+    if(motorVelocities < __rhs.motorVelocities)
+    {
+	return true;
+    }
+    else if(__rhs.motorVelocities < motorVelocities)
+    {
+	return false;
+    }
+    if(motorAccelerations < __rhs.motorAccelerations)
+    {
+	return true;
+    }
+    else if(__rhs.motorAccelerations < motorAccelerations)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::MotorCommand::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(motorMask);
+    if(motorModes.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	::TeRK::__write(__os, &motorModes[0], &motorModes[0] + motorModes.size(), ::TeRK::__U__MotorModeArray());
+    }
+    if(motorPositions.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorPositions[0], &motorPositions[0] + motorPositions.size());
+    }
+    if(motorVelocities.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorVelocities[0], &motorVelocities[0] + motorVelocities.size());
+    }
+    if(motorAccelerations.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&motorAccelerations[0], &motorAccelerations[0] + motorAccelerations.size());
+    }
+}
+
+void
+TeRK::MotorCommand::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(motorMask);
+    ::TeRK::__read(__is, motorModes, ::TeRK::__U__MotorModeArray());
+    __is->read(motorPositions);
+    __is->read(motorVelocities);
+    __is->read(motorAccelerations);
+}
+
+bool
+TeRK::ServoCommand::operator==(const ServoCommand& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::ServoCommand::operator!=(const ServoCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(servoMask != __rhs.servoMask)
+    {
+	return true;
+    }
+    if(servoModes != __rhs.servoModes)
+    {
+	return true;
+    }
+    if(servoPositions != __rhs.servoPositions)
+    {
+	return true;
+    }
+    if(servoSpeeds != __rhs.servoSpeeds)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::ServoCommand::operator<(const ServoCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(servoMask < __rhs.servoMask)
+    {
+	return true;
+    }
+    else if(__rhs.servoMask < servoMask)
+    {
+	return false;
+    }
+    if(servoModes < __rhs.servoModes)
+    {
+	return true;
+    }
+    else if(__rhs.servoModes < servoModes)
+    {
+	return false;
+    }
+    if(servoPositions < __rhs.servoPositions)
+    {
+	return true;
+    }
+    else if(__rhs.servoPositions < servoPositions)
+    {
+	return false;
+    }
+    if(servoSpeeds < __rhs.servoSpeeds)
+    {
+	return true;
+    }
+    else if(__rhs.servoSpeeds < servoSpeeds)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::ServoCommand::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(servoMask);
+    if(servoModes.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	::TeRK::__write(__os, &servoModes[0], &servoModes[0] + servoModes.size(), ::TeRK::__U__ServoModeArray());
+    }
+    if(servoPositions.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&servoPositions[0], &servoPositions[0] + servoPositions.size());
+    }
+    if(servoSpeeds.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&servoSpeeds[0], &servoSpeeds[0] + servoSpeeds.size());
+    }
+}
+
+void
+TeRK::ServoCommand::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(servoMask);
+    ::TeRK::__read(__is, servoModes, ::TeRK::__U__ServoModeArray());
+    __is->read(servoPositions);
+    __is->read(servoSpeeds);
+}
+
+bool
+TeRK::QwerkCommand::operator==(const QwerkCommand& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+TeRK::QwerkCommand::operator!=(const QwerkCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(audioCmd != __rhs.audioCmd)
+    {
+	return true;
+    }
+    if(digitalOutCmd != __rhs.digitalOutCmd)
+    {
+	return true;
+    }
+    if(ledCmd != __rhs.ledCmd)
+    {
+	return true;
+    }
+    if(motorCmd != __rhs.motorCmd)
+    {
+	return true;
+    }
+    if(servoCmd != __rhs.servoCmd)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+TeRK::QwerkCommand::operator<(const QwerkCommand& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(audioCmd < __rhs.audioCmd)
+    {
+	return true;
+    }
+    else if(__rhs.audioCmd < audioCmd)
+    {
+	return false;
+    }
+    if(digitalOutCmd < __rhs.digitalOutCmd)
+    {
+	return true;
+    }
+    else if(__rhs.digitalOutCmd < digitalOutCmd)
+    {
+	return false;
+    }
+    if(ledCmd < __rhs.ledCmd)
+    {
+	return true;
+    }
+    else if(__rhs.ledCmd < ledCmd)
+    {
+	return false;
+    }
+    if(motorCmd < __rhs.motorCmd)
+    {
+	return true;
+    }
+    else if(__rhs.motorCmd < motorCmd)
+    {
+	return false;
+    }
+    if(servoCmd < __rhs.servoCmd)
+    {
+	return true;
+    }
+    else if(__rhs.servoCmd < servoCmd)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+TeRK::QwerkCommand::__write(::IceInternal::BasicStream* __os) const
+{
+    audioCmd.__write(__os);
+    digitalOutCmd.__write(__os);
+    ledCmd.__write(__os);
+    motorCmd.__write(__os);
+    servoCmd.__write(__os);
+}
+
+void
+TeRK::QwerkCommand::__read(::IceInternal::BasicStream* __is)
+{
+    audioCmd.__read(__is);
+    digitalOutCmd.__read(__is);
+    ledCmd.__read(__is);
+    motorCmd.__read(__is);
+    servoCmd.__read(__is);
+}
+
+void
+TeRK::__write(::IceInternal::BasicStream* __os, const ::TeRK::AbstractCommandControllerPrx* begin, const ::TeRK::AbstractCommandControllerPrx* end, ::TeRK::__U__AbstractCommandControllerProxyArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	::TeRK::__write(__os, begin[i]);
+    }
+}
+
+void
+TeRK::__read(::IceInternal::BasicStream* __is, ::TeRK::AbstractCommandControllerProxyArray& v, ::TeRK::__U__AbstractCommandControllerProxyArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->startSeq(sz, 2);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	::TeRK::__read(__is, v[i]);
+	__is->checkSeq();
+	__is->endElement();
+    }
+    __is->endSeq(sz);
+}
+
+void
+TeRK::AMI_PropertyManager_getProperty::__invoke(const ::TeRK::PropertyManagerPrx& __prx, const ::std::string& key, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__PropertyManager__getProperty_name, ::Ice::Normal, __ctx);
+	__os->write(key);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_PropertyManager_getProperty::__response(bool __ok)
+{
+    ::std::string __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_PropertyManager_getProperties::__invoke(const ::TeRK::PropertyManagerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__PropertyManager__getProperties_name, ::Ice::Normal, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_PropertyManager_getProperties::__response(bool __ok)
+{
+    ::TeRK::PropertyMap __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::__read(__is, __ret, ::TeRK::__U__PropertyMap());
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_PropertyManager_getPropertyKeys::__invoke(const ::TeRK::PropertyManagerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__PropertyManager__getPropertyKeys_name, ::Ice::Normal, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_PropertyManager_getPropertyKeys::__response(bool __ok)
+{
+    ::TeRK::StringArray __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_PropertyManager_setProperty::__invoke(const ::TeRK::PropertyManagerPrx& __prx, const ::std::string& key, const ::std::string& value, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__PropertyManager__setProperty_name, ::Ice::Normal, __ctx);
+	__os->write(key);
+	__os->write(value);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_PropertyManager_setProperty::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::ReadOnlyPropertyException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_AnalogInController_getState::__invoke(const ::TeRK::AnalogInControllerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__AnalogInController__getState_name, ::Ice::Normal, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_AnalogInController_getState::__response(bool __ok)
+{
+    ::TeRK::AnalogInState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_AudioController_execute::__invoke(const ::TeRK::AudioControllerPrx& __prx, const ::TeRK::AudioCommand& command, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__AudioController__execute_name, ::Ice::Normal, __ctx);
+	command.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_AudioController_execute::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::AudioCommandException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_DigitalInController_getState::__invoke(const ::TeRK::DigitalInControllerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__DigitalInController__getState_name, ::Ice::Normal, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_DigitalInController_getState::__response(bool __ok)
+{
+    ::TeRK::DigitalInState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_DigitalOutController_execute::__invoke(const ::TeRK::DigitalOutControllerPrx& __prx, const ::TeRK::DigitalOutCommand& command, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__DigitalOutController__execute_name, ::Ice::Normal, __ctx);
+	command.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_DigitalOutController_execute::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::DigitalOutCommandException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_LEDController_execute::__invoke(const ::TeRK::LEDControllerPrx& __prx, const ::TeRK::LEDCommand& command, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__LEDController__execute_name, ::Ice::Normal, __ctx);
+	command.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_LEDController_execute::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::LEDCommandException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_MotorController_execute::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::TeRK::MotorCommand& command, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__execute_name, ::Ice::Normal, __ctx);
+	command.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_execute::__response(bool __ok)
+{
+    ::TeRK::MotorState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorCommandException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_MotorController_getFrequency::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__getFrequency_name, ::Ice::Normal, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_getFrequency::__response(bool __ok)
+{
+    ::Ice::Int __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_MotorController_startMotorBufferRecord::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__startMotorBufferRecord_name, ::Ice::Normal, __ctx);
+	__os->write(motorMask);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_startMotorBufferRecord::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_MotorController_stopMotorBufferRecord::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__stopMotorBufferRecord_name, ::Ice::Idempotent, __ctx);
+	__os->write(motorMask);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_stopMotorBufferRecord::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_MotorController_getMotorBuffers::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__getMotorBuffers_name, ::Ice::Nonmutating, __ctx);
+	__os->write(motorMask);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_getMotorBuffers::__response(bool __ok)
+{
+    ::TeRK::MotorBufferArray __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::__read(__is, __ret, ::TeRK::__U__MotorBufferArray());
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_MotorController_setMotorBuffer::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__setMotorBuffer_name, ::Ice::Idempotent, __ctx);
+	__os->write(motorMask);
+	if(motorBuffers.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::TeRK::__write(__os, &motorBuffers[0], &motorBuffers[0] + motorBuffers.size(), ::TeRK::__U__MotorBufferArray());
+	}
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_setMotorBuffer::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_MotorController_playMotorBuffer::__invoke(const ::TeRK::MotorControllerPrx& __prx, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__MotorController__playMotorBuffer_name, ::Ice::Normal, __ctx);
+	__os->write(motorMask);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_MotorController_playMotorBuffer::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_ServoController_execute::__invoke(const ::TeRK::ServoControllerPrx& __prx, const ::TeRK::ServoCommand& command, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__ServoController__execute_name, ::Ice::Normal, __ctx);
+	command.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_ServoController_execute::__response(bool __ok)
+{
+    ::TeRK::ServoState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::ServoCommandException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_VideoStreamerServer_startVideoStream::__invoke(const ::TeRK::VideoStreamerServerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__VideoStreamerServer__startVideoStream_name, ::Ice::Idempotent, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_startVideoStream::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_stopVideoStream::__invoke(const ::TeRK::VideoStreamerServerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__VideoStreamerServer__stopVideoStream_name, ::Ice::Idempotent, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_stopVideoStream::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_startCamera::__invoke(const ::TeRK::VideoStreamerServerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__VideoStreamerServer__startCamera_name, ::Ice::Idempotent, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_startCamera::__response(bool __ok)
+{
+    ::Ice::Int __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_VideoStreamerServer_stopCamera::__invoke(const ::TeRK::VideoStreamerServerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__VideoStreamerServer__stopCamera_name, ::Ice::Idempotent, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_stopCamera::__response(bool __ok)
+{
+    ::Ice::Int __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__is->read(__ret);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_VideoStreamerServer_getFrame::__invoke(const ::TeRK::VideoStreamerServerPrx& __prx, ::Ice::Int frameNumber, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__VideoStreamerServer__getFrame_name, ::Ice::Normal, __ctx);
+	__os->write(frameNumber);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_VideoStreamerServer_getFrame::__response(bool __ok)
+{
+    ::TeRK::Image __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_TerkUser_getSupportedServices::__invoke(const ::TeRK::TerkUserPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__TerkUser__getSupportedServices_name, ::Ice::Nonmutating, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_TerkUser_getSupportedServices::__response(bool __ok)
+{
+    ::TeRK::ProxyTypeIdToIdentityMap __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::__read(__is, __ret, ::TeRK::__U__ProxyTypeIdToIdentityMap());
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_Qwerk_getState::__invoke(const ::TeRK::QwerkPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__Qwerk__getState_name, ::Ice::Nonmutating, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_Qwerk_getState::__response(bool __ok)
+{
+    ::TeRK::QwerkState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_Qwerk_execute::__invoke(const ::TeRK::QwerkPrx& __prx, const ::TeRK::QwerkCommand& command, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__Qwerk__execute_name, ::Ice::Normal, __ctx);
+	command.__write(__os);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_Qwerk_execute::__response(bool __ok)
+{
+    ::TeRK::QwerkState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::CommandException& __ex)
+	    {
+		ice_exception(__ex);
+		return;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_Qwerk_emergencyStop::__invoke(const ::TeRK::QwerkPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__Qwerk__emergencyStop_name, ::Ice::Idempotent, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_Qwerk_emergencyStop::__response(bool __ok)
+{
+    ::TeRK::QwerkState __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	__ret.__read(__is);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+void
+TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMap::__invoke(const ::TeRK::QwerkPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __TeRK__Qwerk__getCommandControllerTypeToProxyIdentityMap_name, ::Ice::Nonmutating, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMap::__response(bool __ok)
+{
+    ::TeRK::ProxyTypeIdToIdentityMap __ret;
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::__read(__is, __ret, ::TeRK::__U__ProxyTypeIdToIdentityMap());
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response(__ret);
+}
+
+::std::string
+IceProxy::TeRK::PropertyManager::getProperty(const ::std::string& key, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__PropertyManager__getProperty_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::PropertyManager* __del = dynamic_cast< ::IceDelegate::TeRK::PropertyManager*>(__delBase.get());
+	    return __del->getProperty(key, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::PropertyManager::getProperty_async(const ::TeRK::AMI_PropertyManager_getPropertyPtr& __cb, const ::std::string& key)
+{
+    getProperty_async(__cb, key, __defaultContext());
+}
+
+void
+IceProxy::TeRK::PropertyManager::getProperty_async(const ::TeRK::AMI_PropertyManager_getPropertyPtr& __cb, const ::std::string& key, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, key, __ctx);
+}
+
+::TeRK::PropertyMap
+IceProxy::TeRK::PropertyManager::getProperties(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__PropertyManager__getProperties_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::PropertyManager* __del = dynamic_cast< ::IceDelegate::TeRK::PropertyManager*>(__delBase.get());
+	    return __del->getProperties(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::PropertyManager::getProperties_async(const ::TeRK::AMI_PropertyManager_getPropertiesPtr& __cb)
+{
+    getProperties_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::PropertyManager::getProperties_async(const ::TeRK::AMI_PropertyManager_getPropertiesPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+::TeRK::StringArray
+IceProxy::TeRK::PropertyManager::getPropertyKeys(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__PropertyManager__getPropertyKeys_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::PropertyManager* __del = dynamic_cast< ::IceDelegate::TeRK::PropertyManager*>(__delBase.get());
+	    return __del->getPropertyKeys(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::PropertyManager::getPropertyKeys_async(const ::TeRK::AMI_PropertyManager_getPropertyKeysPtr& __cb)
+{
+    getPropertyKeys_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::PropertyManager::getPropertyKeys_async(const ::TeRK::AMI_PropertyManager_getPropertyKeysPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+void
+IceProxy::TeRK::PropertyManager::setProperty(const ::std::string& key, const ::std::string& value, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__PropertyManager__setProperty_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::PropertyManager* __del = dynamic_cast< ::IceDelegate::TeRK::PropertyManager*>(__delBase.get());
+	    __del->setProperty(key, value, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::PropertyManager::setProperty_async(const ::TeRK::AMI_PropertyManager_setPropertyPtr& __cb, const ::std::string& key, const ::std::string& value)
+{
+    setProperty_async(__cb, key, value, __defaultContext());
+}
+
+void
+IceProxy::TeRK::PropertyManager::setProperty_async(const ::TeRK::AMI_PropertyManager_setPropertyPtr& __cb, const ::std::string& key, const ::std::string& value, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, key, value, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::PropertyManager::ice_staticId()
+{
+    return ::TeRK::PropertyManager::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::PropertyManager::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::PropertyManager);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::PropertyManager::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::PropertyManager);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::PropertyManager& l, const ::IceProxy::TeRK::PropertyManager& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::PropertyManager& l, const ::IceProxy::TeRK::PropertyManager& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::PropertyManager& l, const ::IceProxy::TeRK::PropertyManager& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::PropertyManager& l, const ::IceProxy::TeRK::PropertyManager& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::PropertyManager& l, const ::IceProxy::TeRK::PropertyManager& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::PropertyManager& l, const ::IceProxy::TeRK::PropertyManager& r)
+{
+    return !(l < r);
+}
+
+const ::std::string&
+IceProxy::TeRK::AbstractCommandController::ice_staticId()
+{
+    return ::TeRK::AbstractCommandController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::AbstractCommandController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::AbstractCommandController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::AbstractCommandController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::AbstractCommandController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::AbstractCommandController& l, const ::IceProxy::TeRK::AbstractCommandController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::AbstractCommandController& l, const ::IceProxy::TeRK::AbstractCommandController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::AbstractCommandController& l, const ::IceProxy::TeRK::AbstractCommandController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::AbstractCommandController& l, const ::IceProxy::TeRK::AbstractCommandController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::AbstractCommandController& l, const ::IceProxy::TeRK::AbstractCommandController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::AbstractCommandController& l, const ::IceProxy::TeRK::AbstractCommandController& r)
+{
+    return !(l < r);
+}
+
+::TeRK::AnalogInState
+IceProxy::TeRK::AnalogInController::getState(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__AnalogInController__getState_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::AnalogInController* __del = dynamic_cast< ::IceDelegate::TeRK::AnalogInController*>(__delBase.get());
+	    return __del->getState(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::AnalogInController::getState_async(const ::TeRK::AMI_AnalogInController_getStatePtr& __cb)
+{
+    getState_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::AnalogInController::getState_async(const ::TeRK::AMI_AnalogInController_getStatePtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::AnalogInController::ice_staticId()
+{
+    return ::TeRK::AnalogInController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::AnalogInController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::AnalogInController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::AnalogInController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::AnalogInController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::AnalogInController& l, const ::IceProxy::TeRK::AnalogInController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::AnalogInController& l, const ::IceProxy::TeRK::AnalogInController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::AnalogInController& l, const ::IceProxy::TeRK::AnalogInController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::AnalogInController& l, const ::IceProxy::TeRK::AnalogInController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::AnalogInController& l, const ::IceProxy::TeRK::AnalogInController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::AnalogInController& l, const ::IceProxy::TeRK::AnalogInController& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::TeRK::AudioController::execute(const ::TeRK::AudioCommand& command, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__AudioController__execute_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::AudioController* __del = dynamic_cast< ::IceDelegate::TeRK::AudioController*>(__delBase.get());
+	    __del->execute(command, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::AudioController::execute_async(const ::TeRK::AMI_AudioController_executePtr& __cb, const ::TeRK::AudioCommand& command)
+{
+    execute_async(__cb, command, __defaultContext());
+}
+
+void
+IceProxy::TeRK::AudioController::execute_async(const ::TeRK::AMI_AudioController_executePtr& __cb, const ::TeRK::AudioCommand& command, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, command, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::AudioController::ice_staticId()
+{
+    return ::TeRK::AudioController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::AudioController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::AudioController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::AudioController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::AudioController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::AudioController& l, const ::IceProxy::TeRK::AudioController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::AudioController& l, const ::IceProxy::TeRK::AudioController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::AudioController& l, const ::IceProxy::TeRK::AudioController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::AudioController& l, const ::IceProxy::TeRK::AudioController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::AudioController& l, const ::IceProxy::TeRK::AudioController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::AudioController& l, const ::IceProxy::TeRK::AudioController& r)
+{
+    return !(l < r);
+}
+
+::TeRK::DigitalInState
+IceProxy::TeRK::DigitalInController::getState(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__DigitalInController__getState_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::DigitalInController* __del = dynamic_cast< ::IceDelegate::TeRK::DigitalInController*>(__delBase.get());
+	    return __del->getState(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::DigitalInController::getState_async(const ::TeRK::AMI_DigitalInController_getStatePtr& __cb)
+{
+    getState_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::DigitalInController::getState_async(const ::TeRK::AMI_DigitalInController_getStatePtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::DigitalInController::ice_staticId()
+{
+    return ::TeRK::DigitalInController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::DigitalInController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::DigitalInController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::DigitalInController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::DigitalInController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::DigitalInController& l, const ::IceProxy::TeRK::DigitalInController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::DigitalInController& l, const ::IceProxy::TeRK::DigitalInController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::DigitalInController& l, const ::IceProxy::TeRK::DigitalInController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::DigitalInController& l, const ::IceProxy::TeRK::DigitalInController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::DigitalInController& l, const ::IceProxy::TeRK::DigitalInController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::DigitalInController& l, const ::IceProxy::TeRK::DigitalInController& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::TeRK::DigitalOutController::execute(const ::TeRK::DigitalOutCommand& command, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__DigitalOutController__execute_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::DigitalOutController* __del = dynamic_cast< ::IceDelegate::TeRK::DigitalOutController*>(__delBase.get());
+	    __del->execute(command, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::DigitalOutController::execute_async(const ::TeRK::AMI_DigitalOutController_executePtr& __cb, const ::TeRK::DigitalOutCommand& command)
+{
+    execute_async(__cb, command, __defaultContext());
+}
+
+void
+IceProxy::TeRK::DigitalOutController::execute_async(const ::TeRK::AMI_DigitalOutController_executePtr& __cb, const ::TeRK::DigitalOutCommand& command, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, command, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::DigitalOutController::ice_staticId()
+{
+    return ::TeRK::DigitalOutController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::DigitalOutController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::DigitalOutController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::DigitalOutController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::DigitalOutController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::DigitalOutController& l, const ::IceProxy::TeRK::DigitalOutController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::DigitalOutController& l, const ::IceProxy::TeRK::DigitalOutController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::DigitalOutController& l, const ::IceProxy::TeRK::DigitalOutController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::DigitalOutController& l, const ::IceProxy::TeRK::DigitalOutController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::DigitalOutController& l, const ::IceProxy::TeRK::DigitalOutController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::DigitalOutController& l, const ::IceProxy::TeRK::DigitalOutController& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::TeRK::LEDController::execute(const ::TeRK::LEDCommand& command, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__LEDController__execute_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::LEDController* __del = dynamic_cast< ::IceDelegate::TeRK::LEDController*>(__delBase.get());
+	    __del->execute(command, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::LEDController::execute_async(const ::TeRK::AMI_LEDController_executePtr& __cb, const ::TeRK::LEDCommand& command)
+{
+    execute_async(__cb, command, __defaultContext());
+}
+
+void
+IceProxy::TeRK::LEDController::execute_async(const ::TeRK::AMI_LEDController_executePtr& __cb, const ::TeRK::LEDCommand& command, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, command, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::LEDController::ice_staticId()
+{
+    return ::TeRK::LEDController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::LEDController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::LEDController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::LEDController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::LEDController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::LEDController& l, const ::IceProxy::TeRK::LEDController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::LEDController& l, const ::IceProxy::TeRK::LEDController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::LEDController& l, const ::IceProxy::TeRK::LEDController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::LEDController& l, const ::IceProxy::TeRK::LEDController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::LEDController& l, const ::IceProxy::TeRK::LEDController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::LEDController& l, const ::IceProxy::TeRK::LEDController& r)
+{
+    return !(l < r);
+}
+
+::TeRK::MotorState
+IceProxy::TeRK::MotorController::execute(const ::TeRK::MotorCommand& command, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__execute_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    return __del->execute(command, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::execute_async(const ::TeRK::AMI_MotorController_executePtr& __cb, const ::TeRK::MotorCommand& command)
+{
+    execute_async(__cb, command, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::execute_async(const ::TeRK::AMI_MotorController_executePtr& __cb, const ::TeRK::MotorCommand& command, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, command, __ctx);
+}
+
+::Ice::Int
+IceProxy::TeRK::MotorController::getFrequency(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__getFrequency_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    return __del->getFrequency(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::getFrequency_async(const ::TeRK::AMI_MotorController_getFrequencyPtr& __cb)
+{
+    getFrequency_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::getFrequency_async(const ::TeRK::AMI_MotorController_getFrequencyPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+void
+IceProxy::TeRK::MotorController::startMotorBufferRecord(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__startMotorBufferRecord_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->startMotorBufferRecord(motorMask, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::startMotorBufferRecord_async(const ::TeRK::AMI_MotorController_startMotorBufferRecordPtr& __cb, const ::TeRK::BooleanArray& motorMask)
+{
+    startMotorBufferRecord_async(__cb, motorMask, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::startMotorBufferRecord_async(const ::TeRK::AMI_MotorController_startMotorBufferRecordPtr& __cb, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, motorMask, __ctx);
+}
+
+void
+IceProxy::TeRK::MotorController::stopMotorBufferRecord(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__stopMotorBufferRecord_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->stopMotorBufferRecord(motorMask, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::stopMotorBufferRecord_async(const ::TeRK::AMI_MotorController_stopMotorBufferRecordPtr& __cb, const ::TeRK::BooleanArray& motorMask)
+{
+    stopMotorBufferRecord_async(__cb, motorMask, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::stopMotorBufferRecord_async(const ::TeRK::AMI_MotorController_stopMotorBufferRecordPtr& __cb, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, motorMask, __ctx);
+}
+
+::TeRK::MotorBufferArray
+IceProxy::TeRK::MotorController::getMotorBuffers(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__getMotorBuffers_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    return __del->getMotorBuffers(motorMask, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::getMotorBuffers_async(const ::TeRK::AMI_MotorController_getMotorBuffersPtr& __cb, const ::TeRK::BooleanArray& motorMask)
+{
+    getMotorBuffers_async(__cb, motorMask, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::getMotorBuffers_async(const ::TeRK::AMI_MotorController_getMotorBuffersPtr& __cb, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, motorMask, __ctx);
+}
+
+void
+IceProxy::TeRK::MotorController::setMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__setMotorBuffer_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->setMotorBuffer(motorMask, motorBuffers, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::setMotorBuffer_async(const ::TeRK::AMI_MotorController_setMotorBufferPtr& __cb, const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers)
+{
+    setMotorBuffer_async(__cb, motorMask, motorBuffers, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::setMotorBuffer_async(const ::TeRK::AMI_MotorController_setMotorBufferPtr& __cb, const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, motorMask, motorBuffers, __ctx);
+}
+
+void
+IceProxy::TeRK::MotorController::playMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__playMotorBuffer_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->playMotorBuffer(motorMask, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::playMotorBuffer_async(const ::TeRK::AMI_MotorController_playMotorBufferPtr& __cb, const ::TeRK::BooleanArray& motorMask)
+{
+    playMotorBuffer_async(__cb, motorMask, __defaultContext());
+}
+
+void
+IceProxy::TeRK::MotorController::playMotorBuffer_async(const ::TeRK::AMI_MotorController_playMotorBufferPtr& __cb, const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, motorMask, __ctx);
+}
+
+void
+IceProxy::TeRK::MotorController::driveForward(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->driveForward(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::driveBack(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->driveBack(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::spinLeft(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->spinLeft(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::spinRight(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->spinRight(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::setMotorVelocities(const ::TeRK::IntArray& motorValues, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__MotorController__setMotorVelocities_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->setMotorVelocities(motorValues, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::MotorController::stopMotors(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::MotorController* __del = dynamic_cast< ::IceDelegate::TeRK::MotorController*>(__delBase.get());
+	    __del->stopMotors(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+const ::std::string&
+IceProxy::TeRK::MotorController::ice_staticId()
+{
+    return ::TeRK::MotorController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::MotorController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::MotorController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::MotorController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::MotorController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::MotorController& l, const ::IceProxy::TeRK::MotorController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::MotorController& l, const ::IceProxy::TeRK::MotorController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::MotorController& l, const ::IceProxy::TeRK::MotorController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::MotorController& l, const ::IceProxy::TeRK::MotorController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::MotorController& l, const ::IceProxy::TeRK::MotorController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::MotorController& l, const ::IceProxy::TeRK::MotorController& r)
+{
+    return !(l < r);
+}
+
+::TeRK::ServoState
+IceProxy::TeRK::ServoController::execute(const ::TeRK::ServoCommand& command, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__ServoController__execute_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    return __del->execute(command, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::execute_async(const ::TeRK::AMI_ServoController_executePtr& __cb, const ::TeRK::ServoCommand& command)
+{
+    execute_async(__cb, command, __defaultContext());
+}
+
+void
+IceProxy::TeRK::ServoController::execute_async(const ::TeRK::AMI_ServoController_executePtr& __cb, const ::TeRK::ServoCommand& command, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, command, __ctx);
+}
+
+void
+IceProxy::TeRK::ServoController::cameraTiltUp(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->cameraTiltUp(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::cameraTiltDown(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->cameraTiltDown(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::cameraPanLeft(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->cameraPanLeft(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::cameraPanRight(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->cameraPanRight(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::setServoPositions(const ::TeRK::IntArray& servoPositions, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->setServoPositions(servoPositions, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::setServoVelocities(const ::TeRK::IntArray& servoVelocities, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->setServoVelocities(servoVelocities, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::ServoController::stopServos(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::ServoController* __del = dynamic_cast< ::IceDelegate::TeRK::ServoController*>(__delBase.get());
+	    __del->stopServos(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+const ::std::string&
+IceProxy::TeRK::ServoController::ice_staticId()
+{
+    return ::TeRK::ServoController::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::ServoController::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::ServoController);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::ServoController::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::ServoController);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::ServoController& l, const ::IceProxy::TeRK::ServoController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::ServoController& l, const ::IceProxy::TeRK::ServoController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::ServoController& l, const ::IceProxy::TeRK::ServoController& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::ServoController& l, const ::IceProxy::TeRK::ServoController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::ServoController& l, const ::IceProxy::TeRK::ServoController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::ServoController& l, const ::IceProxy::TeRK::ServoController& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::TeRK::VideoStreamerClient::newFrame(const ::TeRK::Image& frame, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::VideoStreamerClient* __del = dynamic_cast< ::IceDelegate::TeRK::VideoStreamerClient*>(__delBase.get());
+	    __del->newFrame(frame, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+const ::std::string&
+IceProxy::TeRK::VideoStreamerClient::ice_staticId()
+{
+    return ::TeRK::VideoStreamerClient::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::VideoStreamerClient::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::VideoStreamerClient);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::VideoStreamerClient::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::VideoStreamerClient);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::VideoStreamerClient& l, const ::IceProxy::TeRK::VideoStreamerClient& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::VideoStreamerClient& l, const ::IceProxy::TeRK::VideoStreamerClient& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::VideoStreamerClient& l, const ::IceProxy::TeRK::VideoStreamerClient& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::VideoStreamerClient& l, const ::IceProxy::TeRK::VideoStreamerClient& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::VideoStreamerClient& l, const ::IceProxy::TeRK::VideoStreamerClient& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::VideoStreamerClient& l, const ::IceProxy::TeRK::VideoStreamerClient& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::startVideoStream(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__VideoStreamerServer__startVideoStream_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::VideoStreamerServer* __del = dynamic_cast< ::IceDelegate::TeRK::VideoStreamerServer*>(__delBase.get());
+	    __del->startVideoStream(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::startVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_startVideoStreamPtr& __cb)
+{
+    startVideoStream_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::startVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_startVideoStreamPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::stopVideoStream(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__VideoStreamerServer__stopVideoStream_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::VideoStreamerServer* __del = dynamic_cast< ::IceDelegate::TeRK::VideoStreamerServer*>(__delBase.get());
+	    __del->stopVideoStream(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::stopVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_stopVideoStreamPtr& __cb)
+{
+    stopVideoStream_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::stopVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_stopVideoStreamPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+::Ice::Int
+IceProxy::TeRK::VideoStreamerServer::startCamera(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__VideoStreamerServer__startCamera_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::VideoStreamerServer* __del = dynamic_cast< ::IceDelegate::TeRK::VideoStreamerServer*>(__delBase.get());
+	    return __del->startCamera(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::startCamera_async(const ::TeRK::AMI_VideoStreamerServer_startCameraPtr& __cb)
+{
+    startCamera_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::startCamera_async(const ::TeRK::AMI_VideoStreamerServer_startCameraPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+::Ice::Int
+IceProxy::TeRK::VideoStreamerServer::stopCamera(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__VideoStreamerServer__stopCamera_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::VideoStreamerServer* __del = dynamic_cast< ::IceDelegate::TeRK::VideoStreamerServer*>(__delBase.get());
+	    return __del->stopCamera(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::stopCamera_async(const ::TeRK::AMI_VideoStreamerServer_stopCameraPtr& __cb)
+{
+    stopCamera_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::stopCamera_async(const ::TeRK::AMI_VideoStreamerServer_stopCameraPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+::TeRK::Image
+IceProxy::TeRK::VideoStreamerServer::getFrame(::Ice::Int frameNumber, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__VideoStreamerServer__getFrame_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::VideoStreamerServer* __del = dynamic_cast< ::IceDelegate::TeRK::VideoStreamerServer*>(__delBase.get());
+	    return __del->getFrame(frameNumber, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::getFrame_async(const ::TeRK::AMI_VideoStreamerServer_getFramePtr& __cb, ::Ice::Int frameNumber)
+{
+    getFrame_async(__cb, frameNumber, __defaultContext());
+}
+
+void
+IceProxy::TeRK::VideoStreamerServer::getFrame_async(const ::TeRK::AMI_VideoStreamerServer_getFramePtr& __cb, ::Ice::Int frameNumber, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, frameNumber, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::VideoStreamerServer::ice_staticId()
+{
+    return ::TeRK::VideoStreamerServer::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::VideoStreamerServer::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::VideoStreamerServer);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::VideoStreamerServer::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::VideoStreamerServer);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::VideoStreamerServer& l, const ::IceProxy::TeRK::VideoStreamerServer& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::VideoStreamerServer& l, const ::IceProxy::TeRK::VideoStreamerServer& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::VideoStreamerServer& l, const ::IceProxy::TeRK::VideoStreamerServer& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::VideoStreamerServer& l, const ::IceProxy::TeRK::VideoStreamerServer& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::VideoStreamerServer& l, const ::IceProxy::TeRK::VideoStreamerServer& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::VideoStreamerServer& l, const ::IceProxy::TeRK::VideoStreamerServer& r)
+{
+    return !(l < r);
+}
+
+::TeRK::ProxyTypeIdToIdentityMap
+IceProxy::TeRK::TerkUser::getSupportedServices(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__TerkUser__getSupportedServices_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::TerkUser* __del = dynamic_cast< ::IceDelegate::TeRK::TerkUser*>(__delBase.get());
+	    return __del->getSupportedServices(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::TerkUser::getSupportedServices_async(const ::TeRK::AMI_TerkUser_getSupportedServicesPtr& __cb)
+{
+    getSupportedServices_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::TerkUser::getSupportedServices_async(const ::TeRK::AMI_TerkUser_getSupportedServicesPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::TerkUser::ice_staticId()
+{
+    return ::TeRK::TerkUser::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::TerkUser::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::TerkUser);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::TerkUser::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::TerkUser);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::TerkUser& l, const ::IceProxy::TeRK::TerkUser& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::TerkUser& l, const ::IceProxy::TeRK::TerkUser& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::TerkUser& l, const ::IceProxy::TeRK::TerkUser& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::TerkUser& l, const ::IceProxy::TeRK::TerkUser& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::TerkUser& l, const ::IceProxy::TeRK::TerkUser& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::TerkUser& l, const ::IceProxy::TeRK::TerkUser& r)
+{
+    return !(l < r);
+}
+
+::TeRK::QwerkState
+IceProxy::TeRK::Qwerk::getState(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__Qwerk__getState_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::Qwerk* __del = dynamic_cast< ::IceDelegate::TeRK::Qwerk*>(__delBase.get());
+	    return __del->getState(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::Qwerk::getState_async(const ::TeRK::AMI_Qwerk_getStatePtr& __cb)
+{
+    getState_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::Qwerk::getState_async(const ::TeRK::AMI_Qwerk_getStatePtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+::TeRK::QwerkState
+IceProxy::TeRK::Qwerk::execute(const ::TeRK::QwerkCommand& command, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__Qwerk__execute_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::Qwerk* __del = dynamic_cast< ::IceDelegate::TeRK::Qwerk*>(__delBase.get());
+	    return __del->execute(command, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::Qwerk::execute_async(const ::TeRK::AMI_Qwerk_executePtr& __cb, const ::TeRK::QwerkCommand& command)
+{
+    execute_async(__cb, command, __defaultContext());
+}
+
+void
+IceProxy::TeRK::Qwerk::execute_async(const ::TeRK::AMI_Qwerk_executePtr& __cb, const ::TeRK::QwerkCommand& command, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, command, __ctx);
+}
+
+::TeRK::QwerkState
+IceProxy::TeRK::Qwerk::emergencyStop(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__Qwerk__emergencyStop_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::Qwerk* __del = dynamic_cast< ::IceDelegate::TeRK::Qwerk*>(__delBase.get());
+	    return __del->emergencyStop(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::Qwerk::emergencyStop_async(const ::TeRK::AMI_Qwerk_emergencyStopPtr& __cb)
+{
+    emergencyStop_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::Qwerk::emergencyStop_async(const ::TeRK::AMI_Qwerk_emergencyStopPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+::TeRK::ProxyTypeIdToIdentityMap
+IceProxy::TeRK::Qwerk::getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__TeRK__Qwerk__getCommandControllerTypeToProxyIdentityMap_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::TeRK::Qwerk* __del = dynamic_cast< ::IceDelegate::TeRK::Qwerk*>(__delBase.get());
+	    return __del->getCommandControllerTypeToProxyIdentityMap(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapperRelaxed(__ex, __cnt);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::TeRK::Qwerk::getCommandControllerTypeToProxyIdentityMap_async(const ::TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMapPtr& __cb)
+{
+    getCommandControllerTypeToProxyIdentityMap_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::TeRK::Qwerk::getCommandControllerTypeToProxyIdentityMap_async(const ::TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMapPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+const ::std::string&
+IceProxy::TeRK::Qwerk::ice_staticId()
+{
+    return ::TeRK::Qwerk::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::Qwerk::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::Qwerk);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::Qwerk::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::Qwerk);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::Qwerk& l, const ::IceProxy::TeRK::Qwerk& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::Qwerk& l, const ::IceProxy::TeRK::Qwerk& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::Qwerk& l, const ::IceProxy::TeRK::Qwerk& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::Qwerk& l, const ::IceProxy::TeRK::Qwerk& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::Qwerk& l, const ::IceProxy::TeRK::Qwerk& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::Qwerk& l, const ::IceProxy::TeRK::Qwerk& r)
+{
+    return !(l < r);
+}
+
+const ::std::string&
+IceProxy::TeRK::TerkClient::ice_staticId()
+{
+    return ::TeRK::TerkClient::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::TeRK::TerkClient::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::TeRK::TerkClient);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::TeRK::TerkClient::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::TeRK::TerkClient);
+}
+
+bool
+IceProxy::TeRK::operator==(const ::IceProxy::TeRK::TerkClient& l, const ::IceProxy::TeRK::TerkClient& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator!=(const ::IceProxy::TeRK::TerkClient& l, const ::IceProxy::TeRK::TerkClient& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<(const ::IceProxy::TeRK::TerkClient& l, const ::IceProxy::TeRK::TerkClient& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::TeRK::operator<=(const ::IceProxy::TeRK::TerkClient& l, const ::IceProxy::TeRK::TerkClient& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::TeRK::operator>(const ::IceProxy::TeRK::TerkClient& l, const ::IceProxy::TeRK::TerkClient& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::TeRK::operator>=(const ::IceProxy::TeRK::TerkClient& l, const ::IceProxy::TeRK::TerkClient& r)
+{
+    return !(l < r);
+}
+
+::std::string
+IceDelegateM::TeRK::PropertyManager::getProperty(const ::std::string& key, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__PropertyManager__getProperty_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(key);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::std::string __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::PropertyMap
+IceDelegateM::TeRK::PropertyManager::getProperties(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__PropertyManager__getProperties_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::PropertyMap __ret;
+	::TeRK::__read(__is, __ret, ::TeRK::__U__PropertyMap());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::StringArray
+IceDelegateM::TeRK::PropertyManager::getPropertyKeys(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__PropertyManager__getPropertyKeys_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::StringArray __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::PropertyManager::setProperty(const ::std::string& key, const ::std::string& value, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__PropertyManager__setProperty_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(key);
+	__os->write(value);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::ReadOnlyPropertyException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::AnalogInState
+IceDelegateM::TeRK::AnalogInController::getState(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__AnalogInController__getState_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::AnalogInState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::AudioController::execute(const ::TeRK::AudioCommand& command, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__AudioController__execute_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	command.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::AudioCommandException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::DigitalInState
+IceDelegateM::TeRK::DigitalInController::getState(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__DigitalInController__getState_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::DigitalInState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::DigitalOutController::execute(const ::TeRK::DigitalOutCommand& command, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__DigitalOutController__execute_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	command.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::DigitalOutCommandException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::LEDController::execute(const ::TeRK::LEDCommand& command, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__LEDController__execute_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	command.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::LEDCommandException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::MotorState
+IceDelegateM::TeRK::MotorController::execute(const ::TeRK::MotorCommand& command, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__execute_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	command.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorCommandException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::MotorState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::Ice::Int
+IceDelegateM::TeRK::MotorController::getFrequency(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__getFrequency_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::Ice::Int __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::startMotorBufferRecord(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__startMotorBufferRecord_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(motorMask);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::stopMotorBufferRecord(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__stopMotorBufferRecord_name, ::Ice::Idempotent, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(motorMask);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::MotorBufferArray
+IceDelegateM::TeRK::MotorController::getMotorBuffers(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__getMotorBuffers_name, ::Ice::Nonmutating, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(motorMask);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::MotorBufferArray __ret;
+	::TeRK::__read(__is, __ret, ::TeRK::__U__MotorBufferArray());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::setMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__setMotorBuffer_name, ::Ice::Idempotent, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(motorMask);
+	if(motorBuffers.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::TeRK::__write(__os, &motorBuffers[0], &motorBuffers[0] + motorBuffers.size(), ::TeRK::__U__MotorBufferArray());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::playMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__playMotorBuffer_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(motorMask);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::MotorException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::driveForward(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__driveForward_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::driveBack(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__driveBack_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::spinLeft(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__spinLeft_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::spinRight(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__spinRight_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::setMotorVelocities(const ::TeRK::IntArray& motorValues, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__setMotorVelocities_name, ::Ice::Idempotent, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	if(motorValues.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&motorValues[0], &motorValues[0] + motorValues.size());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::GenericError&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::MotorController::stopMotors(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__MotorController__stopMotors_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ServoState
+IceDelegateM::TeRK::ServoController::execute(const ::TeRK::ServoCommand& command, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__execute_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	command.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::ServoCommandException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ServoState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::cameraTiltUp(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__cameraTiltUp_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::cameraTiltDown(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__cameraTiltDown_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::cameraPanLeft(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__cameraPanLeft_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::cameraPanRight(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__cameraPanRight_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::setServoPositions(const ::TeRK::IntArray& servoPositions, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__setServoPositions_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	if(servoPositions.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&servoPositions[0], &servoPositions[0] + servoPositions.size());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::setServoVelocities(const ::TeRK::IntArray& servoVelocities, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__setServoVelocities_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	if(servoVelocities.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    __os->write(&servoVelocities[0], &servoVelocities[0] + servoVelocities.size());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::ServoController::stopServos(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__ServoController__stopServos_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::VideoStreamerClient::newFrame(const ::TeRK::Image& frame, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__VideoStreamerClient__newFrame_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	frame.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::VideoStreamerServer::startVideoStream(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__VideoStreamerServer__startVideoStream_name, ::Ice::Idempotent, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::TeRK::VideoStreamerServer::stopVideoStream(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__VideoStreamerServer__stopVideoStream_name, ::Ice::Idempotent, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::Ice::Int
+IceDelegateM::TeRK::VideoStreamerServer::startCamera(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__VideoStreamerServer__startCamera_name, ::Ice::Idempotent, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::Ice::Int __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::Ice::Int
+IceDelegateM::TeRK::VideoStreamerServer::stopCamera(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__VideoStreamerServer__stopCamera_name, ::Ice::Idempotent, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::Ice::Int __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::Image
+IceDelegateM::TeRK::VideoStreamerServer::getFrame(::Ice::Int frameNumber, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__VideoStreamerServer__getFrame_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(frameNumber);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::VideoException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::Image __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ProxyTypeIdToIdentityMap
+IceDelegateM::TeRK::TerkUser::getSupportedServices(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__TerkUser__getSupportedServices_name, ::Ice::Nonmutating, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ProxyTypeIdToIdentityMap __ret;
+	::TeRK::__read(__is, __ret, ::TeRK::__U__ProxyTypeIdToIdentityMap());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::QwerkState
+IceDelegateM::TeRK::Qwerk::getState(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__Qwerk__getState_name, ::Ice::Nonmutating, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::QwerkState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::QwerkState
+IceDelegateM::TeRK::Qwerk::execute(const ::TeRK::QwerkCommand& command, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__Qwerk__execute_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	command.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::TeRK::CommandException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::QwerkState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::QwerkState
+IceDelegateM::TeRK::Qwerk::emergencyStop(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__Qwerk__emergencyStop_name, ::Ice::Idempotent, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::QwerkState __ret;
+	__ret.__read(__is);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::TeRK::ProxyTypeIdToIdentityMap
+IceDelegateM::TeRK::Qwerk::getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __TeRK__Qwerk__getCommandControllerTypeToProxyIdentityMap_name, ::Ice::Nonmutating, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::TeRK::ProxyTypeIdToIdentityMap __ret;
+	::TeRK::__read(__is, __ret, ::TeRK::__U__ProxyTypeIdToIdentityMap());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::std::string
+IceDelegateD::TeRK::PropertyManager::getProperty(const ::std::string& key, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__PropertyManager__getProperty_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::PropertyManager* __servant = dynamic_cast< ::TeRK::PropertyManager*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getProperty(key, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::PropertyMap
+IceDelegateD::TeRK::PropertyManager::getProperties(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__PropertyManager__getProperties_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::PropertyManager* __servant = dynamic_cast< ::TeRK::PropertyManager*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getProperties(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::StringArray
+IceDelegateD::TeRK::PropertyManager::getPropertyKeys(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__PropertyManager__getPropertyKeys_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::PropertyManager* __servant = dynamic_cast< ::TeRK::PropertyManager*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getPropertyKeys(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::PropertyManager::setProperty(const ::std::string& key, const ::std::string& value, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__PropertyManager__setProperty_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::PropertyManager* __servant = dynamic_cast< ::TeRK::PropertyManager*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->setProperty(key, value, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::AnalogInState
+IceDelegateD::TeRK::AnalogInController::getState(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__AnalogInController__getState_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::AnalogInController* __servant = dynamic_cast< ::TeRK::AnalogInController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getState(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::AudioController::execute(const ::TeRK::AudioCommand& command, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__AudioController__execute_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::AudioController* __servant = dynamic_cast< ::TeRK::AudioController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->execute(command, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::DigitalInState
+IceDelegateD::TeRK::DigitalInController::getState(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__DigitalInController__getState_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::DigitalInController* __servant = dynamic_cast< ::TeRK::DigitalInController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getState(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::DigitalOutController::execute(const ::TeRK::DigitalOutCommand& command, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__DigitalOutController__execute_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::DigitalOutController* __servant = dynamic_cast< ::TeRK::DigitalOutController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->execute(command, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::LEDController::execute(const ::TeRK::LEDCommand& command, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__LEDController__execute_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::LEDController* __servant = dynamic_cast< ::TeRK::LEDController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->execute(command, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::MotorState
+IceDelegateD::TeRK::MotorController::execute(const ::TeRK::MotorCommand& command, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__execute_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->execute(command, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::Int
+IceDelegateD::TeRK::MotorController::getFrequency(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__getFrequency_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getFrequency(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::startMotorBufferRecord(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__startMotorBufferRecord_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->startMotorBufferRecord(motorMask, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::stopMotorBufferRecord(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__stopMotorBufferRecord_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->stopMotorBufferRecord(motorMask, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::MotorBufferArray
+IceDelegateD::TeRK::MotorController::getMotorBuffers(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__getMotorBuffers_name, ::Ice::Nonmutating, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getMotorBuffers(motorMask, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::setMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__setMotorBuffer_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->setMotorBuffer(motorMask, motorBuffers, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::playMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__playMotorBuffer_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->playMotorBuffer(motorMask, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::driveForward(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__driveForward_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->driveForward(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::driveBack(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__driveBack_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->driveBack(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::spinLeft(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__spinLeft_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->spinLeft(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::spinRight(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__spinRight_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->spinRight(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::setMotorVelocities(const ::TeRK::IntArray& motorValues, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__setMotorVelocities_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->setMotorVelocities(motorValues, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::MotorController::stopMotors(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__MotorController__stopMotors_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::MotorController* __servant = dynamic_cast< ::TeRK::MotorController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->stopMotors(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ServoState
+IceDelegateD::TeRK::ServoController::execute(const ::TeRK::ServoCommand& command, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__execute_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->execute(command, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::cameraTiltUp(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__cameraTiltUp_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->cameraTiltUp(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::cameraTiltDown(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__cameraTiltDown_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->cameraTiltDown(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::cameraPanLeft(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__cameraPanLeft_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->cameraPanLeft(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::cameraPanRight(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__cameraPanRight_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->cameraPanRight(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::setServoPositions(const ::TeRK::IntArray& servoPositions, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__setServoPositions_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->setServoPositions(servoPositions, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::setServoVelocities(const ::TeRK::IntArray& servoVelocities, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__setServoVelocities_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->setServoVelocities(servoVelocities, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::ServoController::stopServos(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__ServoController__stopServos_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::ServoController* __servant = dynamic_cast< ::TeRK::ServoController*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->stopServos(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::VideoStreamerClient::newFrame(const ::TeRK::Image& frame, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__VideoStreamerClient__newFrame_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::VideoStreamerClient* __servant = dynamic_cast< ::TeRK::VideoStreamerClient*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->newFrame(frame, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::VideoStreamerServer::startVideoStream(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__VideoStreamerServer__startVideoStream_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::VideoStreamerServer* __servant = dynamic_cast< ::TeRK::VideoStreamerServer*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->startVideoStream(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::TeRK::VideoStreamerServer::stopVideoStream(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__VideoStreamerServer__stopVideoStream_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::VideoStreamerServer* __servant = dynamic_cast< ::TeRK::VideoStreamerServer*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->stopVideoStream(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::Int
+IceDelegateD::TeRK::VideoStreamerServer::startCamera(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__VideoStreamerServer__startCamera_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::VideoStreamerServer* __servant = dynamic_cast< ::TeRK::VideoStreamerServer*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->startCamera(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::Int
+IceDelegateD::TeRK::VideoStreamerServer::stopCamera(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__VideoStreamerServer__stopCamera_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::VideoStreamerServer* __servant = dynamic_cast< ::TeRK::VideoStreamerServer*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->stopCamera(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::Image
+IceDelegateD::TeRK::VideoStreamerServer::getFrame(::Ice::Int frameNumber, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__VideoStreamerServer__getFrame_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::VideoStreamerServer* __servant = dynamic_cast< ::TeRK::VideoStreamerServer*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getFrame(frameNumber, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ProxyTypeIdToIdentityMap
+IceDelegateD::TeRK::TerkUser::getSupportedServices(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__TerkUser__getSupportedServices_name, ::Ice::Nonmutating, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::TerkUser* __servant = dynamic_cast< ::TeRK::TerkUser*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getSupportedServices(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::QwerkState
+IceDelegateD::TeRK::Qwerk::getState(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__Qwerk__getState_name, ::Ice::Nonmutating, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::Qwerk* __servant = dynamic_cast< ::TeRK::Qwerk*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getState(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::QwerkState
+IceDelegateD::TeRK::Qwerk::execute(const ::TeRK::QwerkCommand& command, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__Qwerk__execute_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::Qwerk* __servant = dynamic_cast< ::TeRK::Qwerk*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->execute(command, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::QwerkState
+IceDelegateD::TeRK::Qwerk::emergencyStop(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__Qwerk__emergencyStop_name, ::Ice::Idempotent, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::Qwerk* __servant = dynamic_cast< ::TeRK::Qwerk*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->emergencyStop(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::TeRK::ProxyTypeIdToIdentityMap
+IceDelegateD::TeRK::Qwerk::getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __TeRK__Qwerk__getCommandControllerTypeToProxyIdentityMap_name, ::Ice::Nonmutating, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::TeRK::Qwerk* __servant = dynamic_cast< ::TeRK::Qwerk*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getCommandControllerTypeToProxyIdentityMap(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::ObjectPtr
+TeRK::PropertyManager::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__PropertyManager_ids[2] =
+{
+    "::Ice::Object",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::PropertyManager::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__PropertyManager_ids, __TeRK__PropertyManager_ids + 2, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::PropertyManager::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__PropertyManager_ids[0], &__TeRK__PropertyManager_ids[2]);
+}
+
+const ::std::string&
+TeRK::PropertyManager::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__PropertyManager_ids[1];
+}
+
+const ::std::string&
+TeRK::PropertyManager::ice_staticId()
+{
+    return __TeRK__PropertyManager_ids[1];
+}
+
+::IceInternal::DispatchStatus
+TeRK::PropertyManager::___getProperty(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string key;
+    __is->read(key);
+    ::std::string __ret = getProperty(key, __current);
+    __os->write(__ret);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::PropertyManager::___getProperties(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::PropertyMap __ret = getProperties(__current);
+    ::TeRK::__write(__os, __ret, ::TeRK::__U__PropertyMap());
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::PropertyManager::___getPropertyKeys(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::StringArray __ret = getPropertyKeys(__current);
+    if(__ret.size() == 0)
+    {
+	__os->writeSize(0);
+    }
+    else
+    {
+	__os->write(&__ret[0], &__ret[0] + __ret.size());
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::PropertyManager::___setProperty(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string key;
+    ::std::string value;
+    __is->read(key);
+    __is->read(value);
+    try
+    {
+	setProperty(key, value, __current);
+    }
+    catch(const ::TeRK::ReadOnlyPropertyException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__PropertyManager_all[] =
+{
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::PropertyManager::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__PropertyManager_all, __TeRK__PropertyManager_all + 8, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__PropertyManager_all)
+    {
+	case 0:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 2:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 7:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::PropertyManager::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::PropertyManager::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::PropertyManager::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::PropertyManager was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::PropertyManager::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::PropertyManager was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__PropertyManagerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::PropertyManagerPtr* p = static_cast< ::TeRK::PropertyManagerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::PropertyManagerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::PropertyManager::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::PropertyManager& l, const ::TeRK::PropertyManager& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::PropertyManager& l, const ::TeRK::PropertyManager& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::PropertyManager& l, const ::TeRK::PropertyManager& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::PropertyManager& l, const ::TeRK::PropertyManager& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::PropertyManager& l, const ::TeRK::PropertyManager& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::PropertyManager& l, const ::TeRK::PropertyManager& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::AbstractCommandController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__AbstractCommandController_ids[3] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::AbstractCommandController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__AbstractCommandController_ids, __TeRK__AbstractCommandController_ids + 3, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::AbstractCommandController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__AbstractCommandController_ids[0], &__TeRK__AbstractCommandController_ids[3]);
+}
+
+const ::std::string&
+TeRK::AbstractCommandController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__AbstractCommandController_ids[1];
+}
+
+const ::std::string&
+TeRK::AbstractCommandController::ice_staticId()
+{
+    return __TeRK__AbstractCommandController_ids[1];
+}
+
+static ::std::string __TeRK__AbstractCommandController_all[] =
+{
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::AbstractCommandController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__AbstractCommandController_all, __TeRK__AbstractCommandController_all + 8, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__AbstractCommandController_all)
+    {
+	case 0:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 2:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 7:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::AbstractCommandController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::AbstractCommandController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::AbstractCommandController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::AbstractCommandController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::AbstractCommandController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::AbstractCommandController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__AbstractCommandControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::AbstractCommandControllerPtr* p = static_cast< ::TeRK::AbstractCommandControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::AbstractCommandControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::AbstractCommandController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::AbstractCommandController& l, const ::TeRK::AbstractCommandController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::AbstractCommandController& l, const ::TeRK::AbstractCommandController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::AbstractCommandController& l, const ::TeRK::AbstractCommandController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::AbstractCommandController& l, const ::TeRK::AbstractCommandController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::AbstractCommandController& l, const ::TeRK::AbstractCommandController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::AbstractCommandController& l, const ::TeRK::AbstractCommandController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::AnalogInController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__AnalogInController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::AnalogInController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::AnalogInController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__AnalogInController_ids, __TeRK__AnalogInController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::AnalogInController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__AnalogInController_ids[0], &__TeRK__AnalogInController_ids[4]);
+}
+
+const ::std::string&
+TeRK::AnalogInController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__AnalogInController_ids[2];
+}
+
+const ::std::string&
+TeRK::AnalogInController::ice_staticId()
+{
+    return __TeRK__AnalogInController_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::AnalogInController::___getState(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::AnalogInState __ret = getState(__current);
+    __ret.__write(__os);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__AnalogInController_all[] =
+{
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "getState",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::AnalogInController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__AnalogInController_all, __TeRK__AnalogInController_all + 9, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__AnalogInController_all)
+    {
+	case 0:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 2:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 3:
+	{
+	    return ___getState(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 8:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::AnalogInController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::AnalogInController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::AnalogInController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::AnalogInController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::AnalogInController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::AnalogInController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__AnalogInControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::AnalogInControllerPtr* p = static_cast< ::TeRK::AnalogInControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::AnalogInControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::AnalogInController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::AnalogInController& l, const ::TeRK::AnalogInController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::AnalogInController& l, const ::TeRK::AnalogInController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::AnalogInController& l, const ::TeRK::AnalogInController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::AnalogInController& l, const ::TeRK::AnalogInController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::AnalogInController& l, const ::TeRK::AnalogInController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::AnalogInController& l, const ::TeRK::AnalogInController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::AudioController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__AudioController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::AudioController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::AudioController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__AudioController_ids, __TeRK__AudioController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::AudioController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__AudioController_ids[0], &__TeRK__AudioController_ids[4]);
+}
+
+const ::std::string&
+TeRK::AudioController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__AudioController_ids[2];
+}
+
+const ::std::string&
+TeRK::AudioController::ice_staticId()
+{
+    return __TeRK__AudioController_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::AudioController::___execute(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::AudioCommand command;
+    command.__read(__is);
+    try
+    {
+	execute(command, __current);
+    }
+    catch(const ::TeRK::AudioCommandException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__AudioController_all[] =
+{
+    "execute",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::AudioController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__AudioController_all, __TeRK__AudioController_all + 9, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__AudioController_all)
+    {
+	case 0:
+	{
+	    return ___execute(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 2:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 3:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 8:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::AudioController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::AudioController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::AudioController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::AudioController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::AudioController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::AudioController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__AudioControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::AudioControllerPtr* p = static_cast< ::TeRK::AudioControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::AudioControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::AudioController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::AudioController& l, const ::TeRK::AudioController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::AudioController& l, const ::TeRK::AudioController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::AudioController& l, const ::TeRK::AudioController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::AudioController& l, const ::TeRK::AudioController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::AudioController& l, const ::TeRK::AudioController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::AudioController& l, const ::TeRK::AudioController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::DigitalInController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__DigitalInController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::DigitalInController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::DigitalInController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__DigitalInController_ids, __TeRK__DigitalInController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::DigitalInController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__DigitalInController_ids[0], &__TeRK__DigitalInController_ids[4]);
+}
+
+const ::std::string&
+TeRK::DigitalInController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__DigitalInController_ids[2];
+}
+
+const ::std::string&
+TeRK::DigitalInController::ice_staticId()
+{
+    return __TeRK__DigitalInController_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::DigitalInController::___getState(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::DigitalInState __ret = getState(__current);
+    __ret.__write(__os);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__DigitalInController_all[] =
+{
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "getState",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::DigitalInController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__DigitalInController_all, __TeRK__DigitalInController_all + 9, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__DigitalInController_all)
+    {
+	case 0:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 2:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 3:
+	{
+	    return ___getState(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 8:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::DigitalInController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::DigitalInController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::DigitalInController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::DigitalInController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::DigitalInController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::DigitalInController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__DigitalInControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::DigitalInControllerPtr* p = static_cast< ::TeRK::DigitalInControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::DigitalInControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::DigitalInController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::DigitalInController& l, const ::TeRK::DigitalInController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::DigitalInController& l, const ::TeRK::DigitalInController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::DigitalInController& l, const ::TeRK::DigitalInController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::DigitalInController& l, const ::TeRK::DigitalInController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::DigitalInController& l, const ::TeRK::DigitalInController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::DigitalInController& l, const ::TeRK::DigitalInController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::DigitalOutController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__DigitalOutController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::DigitalOutController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::DigitalOutController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__DigitalOutController_ids, __TeRK__DigitalOutController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::DigitalOutController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__DigitalOutController_ids[0], &__TeRK__DigitalOutController_ids[4]);
+}
+
+const ::std::string&
+TeRK::DigitalOutController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__DigitalOutController_ids[2];
+}
+
+const ::std::string&
+TeRK::DigitalOutController::ice_staticId()
+{
+    return __TeRK__DigitalOutController_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::DigitalOutController::___execute(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::DigitalOutCommand command;
+    command.__read(__is);
+    try
+    {
+	execute(command, __current);
+    }
+    catch(const ::TeRK::DigitalOutCommandException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__DigitalOutController_all[] =
+{
+    "execute",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::DigitalOutController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__DigitalOutController_all, __TeRK__DigitalOutController_all + 9, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__DigitalOutController_all)
+    {
+	case 0:
+	{
+	    return ___execute(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 2:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 3:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 8:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::DigitalOutController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::DigitalOutController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::DigitalOutController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::DigitalOutController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::DigitalOutController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::DigitalOutController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__DigitalOutControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::DigitalOutControllerPtr* p = static_cast< ::TeRK::DigitalOutControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::DigitalOutControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::DigitalOutController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::DigitalOutController& l, const ::TeRK::DigitalOutController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::DigitalOutController& l, const ::TeRK::DigitalOutController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::DigitalOutController& l, const ::TeRK::DigitalOutController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::DigitalOutController& l, const ::TeRK::DigitalOutController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::DigitalOutController& l, const ::TeRK::DigitalOutController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::DigitalOutController& l, const ::TeRK::DigitalOutController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::LEDController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__LEDController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::LEDController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::LEDController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__LEDController_ids, __TeRK__LEDController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::LEDController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__LEDController_ids[0], &__TeRK__LEDController_ids[4]);
+}
+
+const ::std::string&
+TeRK::LEDController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__LEDController_ids[2];
+}
+
+const ::std::string&
+TeRK::LEDController::ice_staticId()
+{
+    return __TeRK__LEDController_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::LEDController::___execute(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::LEDCommand command;
+    command.__read(__is);
+    try
+    {
+	execute(command, __current);
+    }
+    catch(const ::TeRK::LEDCommandException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__LEDController_all[] =
+{
+    "execute",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::LEDController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__LEDController_all, __TeRK__LEDController_all + 9, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__LEDController_all)
+    {
+	case 0:
+	{
+	    return ___execute(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 2:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 3:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 8:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::LEDController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::LEDController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::LEDController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::LEDController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::LEDController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::LEDController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__LEDControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::LEDControllerPtr* p = static_cast< ::TeRK::LEDControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::LEDControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::LEDController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::LEDController& l, const ::TeRK::LEDController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::LEDController& l, const ::TeRK::LEDController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::LEDController& l, const ::TeRK::LEDController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::LEDController& l, const ::TeRK::LEDController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::LEDController& l, const ::TeRK::LEDController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::LEDController& l, const ::TeRK::LEDController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::MotorController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__MotorController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::MotorController",
+    "::TeRK::PropertyManager"
+};
+
+bool
+TeRK::MotorController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__MotorController_ids, __TeRK__MotorController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::MotorController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__MotorController_ids[0], &__TeRK__MotorController_ids[4]);
+}
+
+const ::std::string&
+TeRK::MotorController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__MotorController_ids[2];
+}
+
+const ::std::string&
+TeRK::MotorController::ice_staticId()
+{
+    return __TeRK__MotorController_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___execute(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::MotorCommand command;
+    command.__read(__is);
+    try
+    {
+	::TeRK::MotorState __ret = execute(command, __current);
+	__ret.__write(__os);
+    }
+    catch(const ::TeRK::MotorCommandException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___getFrequency(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::Ice::Int __ret = getFrequency(__current);
+    __os->write(__ret);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___startMotorBufferRecord(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::BooleanArray motorMask;
+    __is->read(motorMask);
+    try
+    {
+	startMotorBufferRecord(motorMask, __current);
+    }
+    catch(const ::TeRK::MotorException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___stopMotorBufferRecord(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::BooleanArray motorMask;
+    __is->read(motorMask);
+    try
+    {
+	stopMotorBufferRecord(motorMask, __current);
+    }
+    catch(const ::TeRK::MotorException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___getMotorBuffers(::IceInternal::Incoming&__inS, const ::Ice::Current& __current) const
+{
+    __checkMode(::Ice::Nonmutating, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::BooleanArray motorMask;
+    __is->read(motorMask);
+    try
+    {
+	::TeRK::MotorBufferArray __ret = getMotorBuffers(motorMask, __current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::TeRK::__write(__os, &__ret[0], &__ret[0] + __ret.size(), ::TeRK::__U__MotorBufferArray());
+	}
+    }
+    catch(const ::TeRK::MotorException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___setMotorBuffer(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::BooleanArray motorMask;
+    ::TeRK::MotorBufferArray motorBuffers;
+    __is->read(motorMask);
+    ::TeRK::__read(__is, motorBuffers, ::TeRK::__U__MotorBufferArray());
+    try
+    {
+	setMotorBuffer(motorMask, motorBuffers, __current);
+    }
+    catch(const ::TeRK::MotorException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___playMotorBuffer(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::BooleanArray motorMask;
+    __is->read(motorMask);
+    try
+    {
+	playMotorBuffer(motorMask, __current);
+    }
+    catch(const ::TeRK::MotorException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___driveForward(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    driveForward(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___driveBack(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    driveBack(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___spinLeft(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    spinLeft(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___spinRight(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    spinRight(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___setMotorVelocities(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::IntArray motorValues;
+    __is->read(motorValues);
+    try
+    {
+	setMotorVelocities(motorValues, __current);
+    }
+    catch(const ::TeRK::GenericError& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::___stopMotors(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    stopMotors(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__MotorController_all[] =
+{
+    "driveBack",
+    "driveForward",
+    "execute",
+    "getFrequency",
+    "getMotorBuffers",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "playMotorBuffer",
+    "setMotorBuffer",
+    "setMotorVelocities",
+    "setProperty",
+    "spinLeft",
+    "spinRight",
+    "startMotorBufferRecord",
+    "stopMotorBufferRecord",
+    "stopMotors"
+};
+
+::IceInternal::DispatchStatus
+TeRK::MotorController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__MotorController_all, __TeRK__MotorController_all + 21, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__MotorController_all)
+    {
+	case 0:
+	{
+	    return ___driveBack(in, current);
+	}
+	case 1:
+	{
+	    return ___driveForward(in, current);
+	}
+	case 2:
+	{
+	    return ___execute(in, current);
+	}
+	case 3:
+	{
+	    return ___getFrequency(in, current);
+	}
+	case 4:
+	{
+	    return ___getMotorBuffers(in, current);
+	}
+	case 5:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 6:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 7:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 8:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 9:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 10:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 11:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 12:
+	{
+	    return ___playMotorBuffer(in, current);
+	}
+	case 13:
+	{
+	    return ___setMotorBuffer(in, current);
+	}
+	case 14:
+	{
+	    return ___setMotorVelocities(in, current);
+	}
+	case 15:
+	{
+	    return ___setProperty(in, current);
+	}
+	case 16:
+	{
+	    return ___spinLeft(in, current);
+	}
+	case 17:
+	{
+	    return ___spinRight(in, current);
+	}
+	case 18:
+	{
+	    return ___startMotorBufferRecord(in, current);
+	}
+	case 19:
+	{
+	    return ___stopMotorBufferRecord(in, current);
+	}
+	case 20:
+	{
+	    return ___stopMotors(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::MotorController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::MotorController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::MotorController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::MotorController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::MotorController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::MotorController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__MotorControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::MotorControllerPtr* p = static_cast< ::TeRK::MotorControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::MotorControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::MotorController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::MotorController& l, const ::TeRK::MotorController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::MotorController& l, const ::TeRK::MotorController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::MotorController& l, const ::TeRK::MotorController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::MotorController& l, const ::TeRK::MotorController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::MotorController& l, const ::TeRK::MotorController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::MotorController& l, const ::TeRK::MotorController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::ServoController::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__ServoController_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::PropertyManager",
+    "::TeRK::ServoController"
+};
+
+bool
+TeRK::ServoController::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__ServoController_ids, __TeRK__ServoController_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::ServoController::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__ServoController_ids[0], &__TeRK__ServoController_ids[4]);
+}
+
+const ::std::string&
+TeRK::ServoController::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__ServoController_ids[3];
+}
+
+const ::std::string&
+TeRK::ServoController::ice_staticId()
+{
+    return __TeRK__ServoController_ids[3];
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___execute(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::ServoCommand command;
+    command.__read(__is);
+    try
+    {
+	::TeRK::ServoState __ret = execute(command, __current);
+	__ret.__write(__os);
+    }
+    catch(const ::TeRK::ServoCommandException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___cameraTiltUp(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    cameraTiltUp(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___cameraTiltDown(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    cameraTiltDown(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___cameraPanLeft(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    cameraPanLeft(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___cameraPanRight(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    cameraPanRight(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___setServoPositions(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::TeRK::IntArray servoPositions;
+    __is->read(servoPositions);
+    setServoPositions(servoPositions, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___setServoVelocities(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::TeRK::IntArray servoVelocities;
+    __is->read(servoVelocities);
+    setServoVelocities(servoVelocities, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::___stopServos(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    stopServos(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__ServoController_all[] =
+{
+    "cameraPanLeft",
+    "cameraPanRight",
+    "cameraTiltDown",
+    "cameraTiltUp",
+    "execute",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty",
+    "setServoPositions",
+    "setServoVelocities",
+    "stopServos"
+};
+
+::IceInternal::DispatchStatus
+TeRK::ServoController::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__ServoController_all, __TeRK__ServoController_all + 16, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__ServoController_all)
+    {
+	case 0:
+	{
+	    return ___cameraPanLeft(in, current);
+	}
+	case 1:
+	{
+	    return ___cameraPanRight(in, current);
+	}
+	case 2:
+	{
+	    return ___cameraTiltDown(in, current);
+	}
+	case 3:
+	{
+	    return ___cameraTiltUp(in, current);
+	}
+	case 4:
+	{
+	    return ___execute(in, current);
+	}
+	case 5:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 6:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 7:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 8:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 9:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 10:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 11:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 12:
+	{
+	    return ___setProperty(in, current);
+	}
+	case 13:
+	{
+	    return ___setServoPositions(in, current);
+	}
+	case 14:
+	{
+	    return ___setServoVelocities(in, current);
+	}
+	case 15:
+	{
+	    return ___stopServos(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::ServoController::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::ServoController::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::ServoController::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::ServoController was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::ServoController::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::ServoController was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__ServoControllerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::ServoControllerPtr* p = static_cast< ::TeRK::ServoControllerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::ServoControllerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::ServoController::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::ServoController& l, const ::TeRK::ServoController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::ServoController& l, const ::TeRK::ServoController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::ServoController& l, const ::TeRK::ServoController& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::ServoController& l, const ::TeRK::ServoController& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::ServoController& l, const ::TeRK::ServoController& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::ServoController& l, const ::TeRK::ServoController& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::VideoStreamerClient::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__VideoStreamerClient_ids[2] =
+{
+    "::Ice::Object",
+    "::TeRK::VideoStreamerClient"
+};
+
+bool
+TeRK::VideoStreamerClient::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__VideoStreamerClient_ids, __TeRK__VideoStreamerClient_ids + 2, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::VideoStreamerClient::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__VideoStreamerClient_ids[0], &__TeRK__VideoStreamerClient_ids[2]);
+}
+
+const ::std::string&
+TeRK::VideoStreamerClient::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__VideoStreamerClient_ids[1];
+}
+
+const ::std::string&
+TeRK::VideoStreamerClient::ice_staticId()
+{
+    return __TeRK__VideoStreamerClient_ids[1];
+}
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerClient::___newFrame(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::TeRK::Image frame;
+    frame.__read(__is);
+    newFrame(frame, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__VideoStreamerClient_all[] =
+{
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "newFrame"
+};
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerClient::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__VideoStreamerClient_all, __TeRK__VideoStreamerClient_all + 5, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__VideoStreamerClient_all)
+    {
+	case 0:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 1:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 2:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 4:
+	{
+	    return ___newFrame(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::VideoStreamerClient::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::VideoStreamerClient::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::VideoStreamerClient::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::VideoStreamerClient was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::VideoStreamerClient::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::VideoStreamerClient was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__VideoStreamerClientPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::VideoStreamerClientPtr* p = static_cast< ::TeRK::VideoStreamerClientPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::VideoStreamerClientPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::VideoStreamerClient::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::VideoStreamerClient& l, const ::TeRK::VideoStreamerClient& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::VideoStreamerClient& l, const ::TeRK::VideoStreamerClient& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::VideoStreamerClient& l, const ::TeRK::VideoStreamerClient& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::VideoStreamerClient& l, const ::TeRK::VideoStreamerClient& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::VideoStreamerClient& l, const ::TeRK::VideoStreamerClient& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::VideoStreamerClient& l, const ::TeRK::VideoStreamerClient& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::VideoStreamerServer::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__VideoStreamerServer_ids[4] =
+{
+    "::Ice::Object",
+    "::TeRK::AbstractCommandController",
+    "::TeRK::PropertyManager",
+    "::TeRK::VideoStreamerServer"
+};
+
+bool
+TeRK::VideoStreamerServer::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__VideoStreamerServer_ids, __TeRK__VideoStreamerServer_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::VideoStreamerServer::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__VideoStreamerServer_ids[0], &__TeRK__VideoStreamerServer_ids[4]);
+}
+
+const ::std::string&
+TeRK::VideoStreamerServer::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__VideoStreamerServer_ids[3];
+}
+
+const ::std::string&
+TeRK::VideoStreamerServer::ice_staticId()
+{
+    return __TeRK__VideoStreamerServer_ids[3];
+}
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerServer::___startVideoStream(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    try
+    {
+	startVideoStream(__current);
+    }
+    catch(const ::TeRK::VideoException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerServer::___stopVideoStream(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    try
+    {
+	stopVideoStream(__current);
+    }
+    catch(const ::TeRK::VideoException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerServer::___startCamera(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    try
+    {
+	::Ice::Int __ret = startCamera(__current);
+	__os->write(__ret);
+    }
+    catch(const ::TeRK::VideoException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerServer::___stopCamera(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    try
+    {
+	::Ice::Int __ret = stopCamera(__current);
+	__os->write(__ret);
+    }
+    catch(const ::TeRK::VideoException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerServer::___getFrame(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::Ice::Int frameNumber;
+    __is->read(frameNumber);
+    try
+    {
+	::TeRK::Image __ret = getFrame(frameNumber, __current);
+	__ret.__write(__os);
+    }
+    catch(const ::TeRK::VideoException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__VideoStreamerServer_all[] =
+{
+    "getFrame",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "setProperty",
+    "startCamera",
+    "startVideoStream",
+    "stopCamera",
+    "stopVideoStream"
+};
+
+::IceInternal::DispatchStatus
+TeRK::VideoStreamerServer::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__VideoStreamerServer_all, __TeRK__VideoStreamerServer_all + 13, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__VideoStreamerServer_all)
+    {
+	case 0:
+	{
+	    return ___getFrame(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 2:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 3:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 8:
+	{
+	    return ___setProperty(in, current);
+	}
+	case 9:
+	{
+	    return ___startCamera(in, current);
+	}
+	case 10:
+	{
+	    return ___startVideoStream(in, current);
+	}
+	case 11:
+	{
+	    return ___stopCamera(in, current);
+	}
+	case 12:
+	{
+	    return ___stopVideoStream(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::VideoStreamerServer::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::VideoStreamerServer::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::VideoStreamerServer::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::VideoStreamerServer was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::VideoStreamerServer::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::VideoStreamerServer was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__VideoStreamerServerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::VideoStreamerServerPtr* p = static_cast< ::TeRK::VideoStreamerServerPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::VideoStreamerServerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::VideoStreamerServer::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::VideoStreamerServer& l, const ::TeRK::VideoStreamerServer& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::VideoStreamerServer& l, const ::TeRK::VideoStreamerServer& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::VideoStreamerServer& l, const ::TeRK::VideoStreamerServer& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::VideoStreamerServer& l, const ::TeRK::VideoStreamerServer& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::VideoStreamerServer& l, const ::TeRK::VideoStreamerServer& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::VideoStreamerServer& l, const ::TeRK::VideoStreamerServer& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::TerkUser::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__TerkUser_ids[6] =
+{
+    "::Ice::Object",
+    "::TeRK::PropertyManager",
+    "::TeRK::TerkUser",
+    "::peer::ConnectionEventHandler",
+    "::peer::PeerConnectionEventHandler",
+    "::peer::UserConnectionEventHandler"
+};
+
+bool
+TeRK::TerkUser::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__TerkUser_ids, __TeRK__TerkUser_ids + 6, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::TerkUser::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__TerkUser_ids[0], &__TeRK__TerkUser_ids[6]);
+}
+
+const ::std::string&
+TeRK::TerkUser::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__TerkUser_ids[2];
+}
+
+const ::std::string&
+TeRK::TerkUser::ice_staticId()
+{
+    return __TeRK__TerkUser_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::TerkUser::___getSupportedServices(::IceInternal::Incoming&__inS, const ::Ice::Current& __current) const
+{
+    __checkMode(::Ice::Nonmutating, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::ProxyTypeIdToIdentityMap __ret = getSupportedServices(__current);
+    ::TeRK::__write(__os, __ret, ::TeRK::__U__ProxyTypeIdToIdentityMap());
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__TerkUser_all[] =
+{
+    "forcedLogoutNotification",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "getSupportedServices",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "peerConnected",
+    "peerConnectedNoProxy",
+    "peerDisconnected",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::TerkUser::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__TerkUser_all, __TeRK__TerkUser_all + 13, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__TerkUser_all)
+    {
+	case 0:
+	{
+	    return ___forcedLogoutNotification(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 2:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 3:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 4:
+	{
+	    return ___getSupportedServices(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 8:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 9:
+	{
+	    return ___peerConnected(in, current);
+	}
+	case 10:
+	{
+	    return ___peerConnectedNoProxy(in, current);
+	}
+	case 11:
+	{
+	    return ___peerDisconnected(in, current);
+	}
+	case 12:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::TerkUser::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::TerkUser::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::TerkUser::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::TerkUser was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::TerkUser::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::TerkUser was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__TerkUserPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::TerkUserPtr* p = static_cast< ::TeRK::TerkUserPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::TerkUserPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::TerkUser::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::TerkUser& l, const ::TeRK::TerkUser& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::TerkUser& l, const ::TeRK::TerkUser& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::TerkUser& l, const ::TeRK::TerkUser& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::TerkUser& l, const ::TeRK::TerkUser& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::TerkUser& l, const ::TeRK::TerkUser& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::TerkUser& l, const ::TeRK::TerkUser& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::Qwerk::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__Qwerk_ids[7] =
+{
+    "::Ice::Object",
+    "::TeRK::PropertyManager",
+    "::TeRK::Qwerk",
+    "::TeRK::TerkUser",
+    "::peer::ConnectionEventHandler",
+    "::peer::PeerConnectionEventHandler",
+    "::peer::UserConnectionEventHandler"
+};
+
+bool
+TeRK::Qwerk::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__Qwerk_ids, __TeRK__Qwerk_ids + 7, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::Qwerk::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__Qwerk_ids[0], &__TeRK__Qwerk_ids[7]);
+}
+
+const ::std::string&
+TeRK::Qwerk::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__Qwerk_ids[2];
+}
+
+const ::std::string&
+TeRK::Qwerk::ice_staticId()
+{
+    return __TeRK__Qwerk_ids[2];
+}
+
+::IceInternal::DispatchStatus
+TeRK::Qwerk::___getState(::IceInternal::Incoming&__inS, const ::Ice::Current& __current) const
+{
+    __checkMode(::Ice::Nonmutating, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::QwerkState __ret = getState(__current);
+    __ret.__write(__os);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::Qwerk::___execute(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::QwerkCommand command;
+    command.__read(__is);
+    try
+    {
+	::TeRK::QwerkState __ret = execute(command, __current);
+	__ret.__write(__os);
+    }
+    catch(const ::TeRK::CommandException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::Qwerk::___emergencyStop(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Idempotent, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::QwerkState __ret = emergencyStop(__current);
+    __ret.__write(__os);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+TeRK::Qwerk::___getCommandControllerTypeToProxyIdentityMap(::IceInternal::Incoming&__inS, const ::Ice::Current& __current) const
+{
+    __checkMode(::Ice::Nonmutating, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::TeRK::ProxyTypeIdToIdentityMap __ret = getCommandControllerTypeToProxyIdentityMap(__current);
+    ::TeRK::__write(__os, __ret, ::TeRK::__U__ProxyTypeIdToIdentityMap());
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __TeRK__Qwerk_all[] =
+{
+    "emergencyStop",
+    "execute",
+    "forcedLogoutNotification",
+    "getCommandControllerTypeToProxyIdentityMap",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "getState",
+    "getSupportedServices",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "peerConnected",
+    "peerConnectedNoProxy",
+    "peerDisconnected",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::Qwerk::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__Qwerk_all, __TeRK__Qwerk_all + 17, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__Qwerk_all)
+    {
+	case 0:
+	{
+	    return ___emergencyStop(in, current);
+	}
+	case 1:
+	{
+	    return ___execute(in, current);
+	}
+	case 2:
+	{
+	    return ___forcedLogoutNotification(in, current);
+	}
+	case 3:
+	{
+	    return ___getCommandControllerTypeToProxyIdentityMap(in, current);
+	}
+	case 4:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 5:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 6:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 7:
+	{
+	    return ___getState(in, current);
+	}
+	case 8:
+	{
+	    return ___getSupportedServices(in, current);
+	}
+	case 9:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 10:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 11:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 12:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 13:
+	{
+	    return ___peerConnected(in, current);
+	}
+	case 14:
+	{
+	    return ___peerConnectedNoProxy(in, current);
+	}
+	case 15:
+	{
+	    return ___peerDisconnected(in, current);
+	}
+	case 16:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::Qwerk::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::Qwerk::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::Qwerk::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::Qwerk was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::Qwerk::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::Qwerk was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__QwerkPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::QwerkPtr* p = static_cast< ::TeRK::QwerkPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::QwerkPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::Qwerk::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::Qwerk& l, const ::TeRK::Qwerk& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::Qwerk& l, const ::TeRK::Qwerk& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::Qwerk& l, const ::TeRK::Qwerk& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::Qwerk& l, const ::TeRK::Qwerk& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::Qwerk& l, const ::TeRK::Qwerk& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::Qwerk& l, const ::TeRK::Qwerk& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+TeRK::TerkClient::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __TeRK__TerkClient_ids[8] =
+{
+    "::Ice::Object",
+    "::TeRK::PropertyManager",
+    "::TeRK::TerkClient",
+    "::TeRK::TerkUser",
+    "::TeRK::VideoStreamerClient",
+    "::peer::ConnectionEventHandler",
+    "::peer::PeerConnectionEventHandler",
+    "::peer::UserConnectionEventHandler"
+};
+
+bool
+TeRK::TerkClient::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__TeRK__TerkClient_ids, __TeRK__TerkClient_ids + 8, _s);
+}
+
+::std::vector< ::std::string>
+TeRK::TerkClient::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__TeRK__TerkClient_ids[0], &__TeRK__TerkClient_ids[8]);
+}
+
+const ::std::string&
+TeRK::TerkClient::ice_id(const ::Ice::Current&) const
+{
+    return __TeRK__TerkClient_ids[2];
+}
+
+const ::std::string&
+TeRK::TerkClient::ice_staticId()
+{
+    return __TeRK__TerkClient_ids[2];
+}
+
+static ::std::string __TeRK__TerkClient_all[] =
+{
+    "forcedLogoutNotification",
+    "getProperties",
+    "getProperty",
+    "getPropertyKeys",
+    "getSupportedServices",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "newFrame",
+    "peerConnected",
+    "peerConnectedNoProxy",
+    "peerDisconnected",
+    "setProperty"
+};
+
+::IceInternal::DispatchStatus
+TeRK::TerkClient::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__TeRK__TerkClient_all, __TeRK__TerkClient_all + 14, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __TeRK__TerkClient_all)
+    {
+	case 0:
+	{
+	    return ___forcedLogoutNotification(in, current);
+	}
+	case 1:
+	{
+	    return ___getProperties(in, current);
+	}
+	case 2:
+	{
+	    return ___getProperty(in, current);
+	}
+	case 3:
+	{
+	    return ___getPropertyKeys(in, current);
+	}
+	case 4:
+	{
+	    return ___getSupportedServices(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 6:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 7:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 8:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 9:
+	{
+	    return ___newFrame(in, current);
+	}
+	case 10:
+	{
+	    return ___peerConnected(in, current);
+	}
+	case 11:
+	{
+	    return ___peerConnectedNoProxy(in, current);
+	}
+	case 12:
+	{
+	    return ___peerDisconnected(in, current);
+	}
+	case 13:
+	{
+	    return ___setProperty(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+TeRK::TerkClient::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+TeRK::TerkClient::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+TeRK::TerkClient::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::TerkClient was not generated with stream support";
+    throw ex;
+}
+
+void
+TeRK::TerkClient::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type TeRK::TerkClient was not generated with stream support";
+    throw ex;
+}
+
+void 
+TeRK::__patch__TerkClientPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::TeRK::TerkClientPtr* p = static_cast< ::TeRK::TerkClientPtr*>(__addr);
+    assert(p);
+    *p = ::TeRK::TerkClientPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::TeRK::TerkClient::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+TeRK::operator==(const ::TeRK::TerkClient& l, const ::TeRK::TerkClient& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator!=(const ::TeRK::TerkClient& l, const ::TeRK::TerkClient& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<(const ::TeRK::TerkClient& l, const ::TeRK::TerkClient& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+TeRK::operator<=(const ::TeRK::TerkClient& l, const ::TeRK::TerkClient& r)
+{
+    return l < r || l == r;
+}
+
+bool
+TeRK::operator>(const ::TeRK::TerkClient& l, const ::TeRK::TerkClient& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+TeRK::operator>=(const ::TeRK::TerkClient& l, const ::TeRK::TerkClient& r)
+{
+    return !(l < r);
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/TeRKPeerCommon.h ./local/terk/TeRKPeerCommon.h
--- ../Tekkotsu_3.0/local/terk/TeRKPeerCommon.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/TeRKPeerCommon.h	2007-04-09 17:18:12.000000000 -0400
@@ -0,0 +1,3166 @@
+// **********************************************************************
+//
+// Copyright (c) 2003-2006 ZeroC, Inc. All rights reserved.
+//
+// This copy of Ice is licensed to you under the terms described in the
+// ICE_LICENSE file included in this distribution.
+//
+// **********************************************************************
+
+// Ice version 3.1.1
+// Generated from file `TeRKPeerCommon.ice'
+
+#ifndef ___home_btsai_terk_source_TeRKPeerCommon_code_c____TeRKPeerCommon_h__
+#define ___home_btsai_terk_source_TeRKPeerCommon_code_c____TeRKPeerCommon_h__
+
+#include <Ice/LocalObjectF.h>
+#include <Ice/ProxyF.h>
+#include <Ice/ObjectF.h>
+#include <Ice/Exception.h>
+#include <Ice/LocalObject.h>
+#include <Ice/Proxy.h>
+#include <Ice/Object.h>
+#include <Ice/Outgoing.h>
+#include <Ice/OutgoingAsync.h>
+#include <Ice/Incoming.h>
+#include <Ice/Direct.h>
+#include <Ice/UserExceptionFactory.h>
+#include <Ice/FactoryTable.h>
+#include <Ice/StreamF.h>
+#include <Ice/Identity.h>
+#include "peer/MRPLPeer.h"
+#include <Ice/UndefSysMacros.h>
+
+#ifndef ICE_IGNORE_VERSION
+#   if ICE_INT_VERSION / 100 != 301
+#       error Ice version mismatch!
+#   endif
+#   if ICE_INT_VERSION % 100 < 1
+#       error Ice patch level mismatch!
+#   endif
+#endif
+
+namespace IceProxy
+{
+
+namespace TeRK
+{
+
+class PropertyManager;
+bool operator==(const PropertyManager&, const PropertyManager&);
+bool operator!=(const PropertyManager&, const PropertyManager&);
+bool operator<(const PropertyManager&, const PropertyManager&);
+bool operator<=(const PropertyManager&, const PropertyManager&);
+bool operator>(const PropertyManager&, const PropertyManager&);
+bool operator>=(const PropertyManager&, const PropertyManager&);
+
+class AbstractCommandController;
+bool operator==(const AbstractCommandController&, const AbstractCommandController&);
+bool operator!=(const AbstractCommandController&, const AbstractCommandController&);
+bool operator<(const AbstractCommandController&, const AbstractCommandController&);
+bool operator<=(const AbstractCommandController&, const AbstractCommandController&);
+bool operator>(const AbstractCommandController&, const AbstractCommandController&);
+bool operator>=(const AbstractCommandController&, const AbstractCommandController&);
+
+class AnalogInController;
+bool operator==(const AnalogInController&, const AnalogInController&);
+bool operator!=(const AnalogInController&, const AnalogInController&);
+bool operator<(const AnalogInController&, const AnalogInController&);
+bool operator<=(const AnalogInController&, const AnalogInController&);
+bool operator>(const AnalogInController&, const AnalogInController&);
+bool operator>=(const AnalogInController&, const AnalogInController&);
+
+class AudioController;
+bool operator==(const AudioController&, const AudioController&);
+bool operator!=(const AudioController&, const AudioController&);
+bool operator<(const AudioController&, const AudioController&);
+bool operator<=(const AudioController&, const AudioController&);
+bool operator>(const AudioController&, const AudioController&);
+bool operator>=(const AudioController&, const AudioController&);
+
+class DigitalInController;
+bool operator==(const DigitalInController&, const DigitalInController&);
+bool operator!=(const DigitalInController&, const DigitalInController&);
+bool operator<(const DigitalInController&, const DigitalInController&);
+bool operator<=(const DigitalInController&, const DigitalInController&);
+bool operator>(const DigitalInController&, const DigitalInController&);
+bool operator>=(const DigitalInController&, const DigitalInController&);
+
+class DigitalOutController;
+bool operator==(const DigitalOutController&, const DigitalOutController&);
+bool operator!=(const DigitalOutController&, const DigitalOutController&);
+bool operator<(const DigitalOutController&, const DigitalOutController&);
+bool operator<=(const DigitalOutController&, const DigitalOutController&);
+bool operator>(const DigitalOutController&, const DigitalOutController&);
+bool operator>=(const DigitalOutController&, const DigitalOutController&);
+
+class LEDController;
+bool operator==(const LEDController&, const LEDController&);
+bool operator!=(const LEDController&, const LEDController&);
+bool operator<(const LEDController&, const LEDController&);
+bool operator<=(const LEDController&, const LEDController&);
+bool operator>(const LEDController&, const LEDController&);
+bool operator>=(const LEDController&, const LEDController&);
+
+class MotorController;
+bool operator==(const MotorController&, const MotorController&);
+bool operator!=(const MotorController&, const MotorController&);
+bool operator<(const MotorController&, const MotorController&);
+bool operator<=(const MotorController&, const MotorController&);
+bool operator>(const MotorController&, const MotorController&);
+bool operator>=(const MotorController&, const MotorController&);
+
+class ServoController;
+bool operator==(const ServoController&, const ServoController&);
+bool operator!=(const ServoController&, const ServoController&);
+bool operator<(const ServoController&, const ServoController&);
+bool operator<=(const ServoController&, const ServoController&);
+bool operator>(const ServoController&, const ServoController&);
+bool operator>=(const ServoController&, const ServoController&);
+
+class VideoStreamerClient;
+bool operator==(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator!=(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator<(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator<=(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator>(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator>=(const VideoStreamerClient&, const VideoStreamerClient&);
+
+class VideoStreamerServer;
+bool operator==(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator!=(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator<(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator<=(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator>(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator>=(const VideoStreamerServer&, const VideoStreamerServer&);
+
+class TerkUser;
+bool operator==(const TerkUser&, const TerkUser&);
+bool operator!=(const TerkUser&, const TerkUser&);
+bool operator<(const TerkUser&, const TerkUser&);
+bool operator<=(const TerkUser&, const TerkUser&);
+bool operator>(const TerkUser&, const TerkUser&);
+bool operator>=(const TerkUser&, const TerkUser&);
+
+class Qwerk;
+bool operator==(const Qwerk&, const Qwerk&);
+bool operator!=(const Qwerk&, const Qwerk&);
+bool operator<(const Qwerk&, const Qwerk&);
+bool operator<=(const Qwerk&, const Qwerk&);
+bool operator>(const Qwerk&, const Qwerk&);
+bool operator>=(const Qwerk&, const Qwerk&);
+
+class TerkClient;
+bool operator==(const TerkClient&, const TerkClient&);
+bool operator!=(const TerkClient&, const TerkClient&);
+bool operator<(const TerkClient&, const TerkClient&);
+bool operator<=(const TerkClient&, const TerkClient&);
+bool operator>(const TerkClient&, const TerkClient&);
+bool operator>=(const TerkClient&, const TerkClient&);
+
+}
+
+}
+
+namespace TeRK
+{
+
+class PropertyManager;
+bool operator==(const PropertyManager&, const PropertyManager&);
+bool operator!=(const PropertyManager&, const PropertyManager&);
+bool operator<(const PropertyManager&, const PropertyManager&);
+bool operator<=(const PropertyManager&, const PropertyManager&);
+bool operator>(const PropertyManager&, const PropertyManager&);
+bool operator>=(const PropertyManager&, const PropertyManager&);
+
+class AbstractCommandController;
+bool operator==(const AbstractCommandController&, const AbstractCommandController&);
+bool operator!=(const AbstractCommandController&, const AbstractCommandController&);
+bool operator<(const AbstractCommandController&, const AbstractCommandController&);
+bool operator<=(const AbstractCommandController&, const AbstractCommandController&);
+bool operator>(const AbstractCommandController&, const AbstractCommandController&);
+bool operator>=(const AbstractCommandController&, const AbstractCommandController&);
+
+class AnalogInController;
+bool operator==(const AnalogInController&, const AnalogInController&);
+bool operator!=(const AnalogInController&, const AnalogInController&);
+bool operator<(const AnalogInController&, const AnalogInController&);
+bool operator<=(const AnalogInController&, const AnalogInController&);
+bool operator>(const AnalogInController&, const AnalogInController&);
+bool operator>=(const AnalogInController&, const AnalogInController&);
+
+class AudioController;
+bool operator==(const AudioController&, const AudioController&);
+bool operator!=(const AudioController&, const AudioController&);
+bool operator<(const AudioController&, const AudioController&);
+bool operator<=(const AudioController&, const AudioController&);
+bool operator>(const AudioController&, const AudioController&);
+bool operator>=(const AudioController&, const AudioController&);
+
+class DigitalInController;
+bool operator==(const DigitalInController&, const DigitalInController&);
+bool operator!=(const DigitalInController&, const DigitalInController&);
+bool operator<(const DigitalInController&, const DigitalInController&);
+bool operator<=(const DigitalInController&, const DigitalInController&);
+bool operator>(const DigitalInController&, const DigitalInController&);
+bool operator>=(const DigitalInController&, const DigitalInController&);
+
+class DigitalOutController;
+bool operator==(const DigitalOutController&, const DigitalOutController&);
+bool operator!=(const DigitalOutController&, const DigitalOutController&);
+bool operator<(const DigitalOutController&, const DigitalOutController&);
+bool operator<=(const DigitalOutController&, const DigitalOutController&);
+bool operator>(const DigitalOutController&, const DigitalOutController&);
+bool operator>=(const DigitalOutController&, const DigitalOutController&);
+
+class LEDController;
+bool operator==(const LEDController&, const LEDController&);
+bool operator!=(const LEDController&, const LEDController&);
+bool operator<(const LEDController&, const LEDController&);
+bool operator<=(const LEDController&, const LEDController&);
+bool operator>(const LEDController&, const LEDController&);
+bool operator>=(const LEDController&, const LEDController&);
+
+class MotorController;
+bool operator==(const MotorController&, const MotorController&);
+bool operator!=(const MotorController&, const MotorController&);
+bool operator<(const MotorController&, const MotorController&);
+bool operator<=(const MotorController&, const MotorController&);
+bool operator>(const MotorController&, const MotorController&);
+bool operator>=(const MotorController&, const MotorController&);
+
+class ServoController;
+bool operator==(const ServoController&, const ServoController&);
+bool operator!=(const ServoController&, const ServoController&);
+bool operator<(const ServoController&, const ServoController&);
+bool operator<=(const ServoController&, const ServoController&);
+bool operator>(const ServoController&, const ServoController&);
+bool operator>=(const ServoController&, const ServoController&);
+
+class VideoStreamerClient;
+bool operator==(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator!=(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator<(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator<=(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator>(const VideoStreamerClient&, const VideoStreamerClient&);
+bool operator>=(const VideoStreamerClient&, const VideoStreamerClient&);
+
+class VideoStreamerServer;
+bool operator==(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator!=(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator<(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator<=(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator>(const VideoStreamerServer&, const VideoStreamerServer&);
+bool operator>=(const VideoStreamerServer&, const VideoStreamerServer&);
+
+class TerkUser;
+bool operator==(const TerkUser&, const TerkUser&);
+bool operator!=(const TerkUser&, const TerkUser&);
+bool operator<(const TerkUser&, const TerkUser&);
+bool operator<=(const TerkUser&, const TerkUser&);
+bool operator>(const TerkUser&, const TerkUser&);
+bool operator>=(const TerkUser&, const TerkUser&);
+
+class Qwerk;
+bool operator==(const Qwerk&, const Qwerk&);
+bool operator!=(const Qwerk&, const Qwerk&);
+bool operator<(const Qwerk&, const Qwerk&);
+bool operator<=(const Qwerk&, const Qwerk&);
+bool operator>(const Qwerk&, const Qwerk&);
+bool operator>=(const Qwerk&, const Qwerk&);
+
+class TerkClient;
+bool operator==(const TerkClient&, const TerkClient&);
+bool operator!=(const TerkClient&, const TerkClient&);
+bool operator<(const TerkClient&, const TerkClient&);
+bool operator<=(const TerkClient&, const TerkClient&);
+bool operator>(const TerkClient&, const TerkClient&);
+bool operator>=(const TerkClient&, const TerkClient&);
+
+}
+
+namespace IceInternal
+{
+
+void incRef(::TeRK::PropertyManager*);
+void decRef(::TeRK::PropertyManager*);
+
+void incRef(::IceProxy::TeRK::PropertyManager*);
+void decRef(::IceProxy::TeRK::PropertyManager*);
+
+void incRef(::TeRK::AbstractCommandController*);
+void decRef(::TeRK::AbstractCommandController*);
+
+void incRef(::IceProxy::TeRK::AbstractCommandController*);
+void decRef(::IceProxy::TeRK::AbstractCommandController*);
+
+void incRef(::TeRK::AnalogInController*);
+void decRef(::TeRK::AnalogInController*);
+
+void incRef(::IceProxy::TeRK::AnalogInController*);
+void decRef(::IceProxy::TeRK::AnalogInController*);
+
+void incRef(::TeRK::AudioController*);
+void decRef(::TeRK::AudioController*);
+
+void incRef(::IceProxy::TeRK::AudioController*);
+void decRef(::IceProxy::TeRK::AudioController*);
+
+void incRef(::TeRK::DigitalInController*);
+void decRef(::TeRK::DigitalInController*);
+
+void incRef(::IceProxy::TeRK::DigitalInController*);
+void decRef(::IceProxy::TeRK::DigitalInController*);
+
+void incRef(::TeRK::DigitalOutController*);
+void decRef(::TeRK::DigitalOutController*);
+
+void incRef(::IceProxy::TeRK::DigitalOutController*);
+void decRef(::IceProxy::TeRK::DigitalOutController*);
+
+void incRef(::TeRK::LEDController*);
+void decRef(::TeRK::LEDController*);
+
+void incRef(::IceProxy::TeRK::LEDController*);
+void decRef(::IceProxy::TeRK::LEDController*);
+
+void incRef(::TeRK::MotorController*);
+void decRef(::TeRK::MotorController*);
+
+void incRef(::IceProxy::TeRK::MotorController*);
+void decRef(::IceProxy::TeRK::MotorController*);
+
+void incRef(::TeRK::ServoController*);
+void decRef(::TeRK::ServoController*);
+
+void incRef(::IceProxy::TeRK::ServoController*);
+void decRef(::IceProxy::TeRK::ServoController*);
+
+void incRef(::TeRK::VideoStreamerClient*);
+void decRef(::TeRK::VideoStreamerClient*);
+
+void incRef(::IceProxy::TeRK::VideoStreamerClient*);
+void decRef(::IceProxy::TeRK::VideoStreamerClient*);
+
+void incRef(::TeRK::VideoStreamerServer*);
+void decRef(::TeRK::VideoStreamerServer*);
+
+void incRef(::IceProxy::TeRK::VideoStreamerServer*);
+void decRef(::IceProxy::TeRK::VideoStreamerServer*);
+
+void incRef(::TeRK::TerkUser*);
+void decRef(::TeRK::TerkUser*);
+
+void incRef(::IceProxy::TeRK::TerkUser*);
+void decRef(::IceProxy::TeRK::TerkUser*);
+
+void incRef(::TeRK::Qwerk*);
+void decRef(::TeRK::Qwerk*);
+
+void incRef(::IceProxy::TeRK::Qwerk*);
+void decRef(::IceProxy::TeRK::Qwerk*);
+
+void incRef(::TeRK::TerkClient*);
+void decRef(::TeRK::TerkClient*);
+
+void incRef(::IceProxy::TeRK::TerkClient*);
+void decRef(::IceProxy::TeRK::TerkClient*);
+
+}
+
+namespace TeRK
+{
+
+typedef ::IceInternal::Handle< ::TeRK::PropertyManager> PropertyManagerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::PropertyManager> PropertyManagerPrx;
+
+void __write(::IceInternal::BasicStream*, const PropertyManagerPrx&);
+void __read(::IceInternal::BasicStream*, PropertyManagerPrx&);
+void __write(::IceInternal::BasicStream*, const PropertyManagerPtr&);
+void __patch__PropertyManagerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::AbstractCommandController> AbstractCommandControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::AbstractCommandController> AbstractCommandControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const AbstractCommandControllerPrx&);
+void __read(::IceInternal::BasicStream*, AbstractCommandControllerPrx&);
+void __write(::IceInternal::BasicStream*, const AbstractCommandControllerPtr&);
+void __patch__AbstractCommandControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::AnalogInController> AnalogInControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::AnalogInController> AnalogInControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const AnalogInControllerPrx&);
+void __read(::IceInternal::BasicStream*, AnalogInControllerPrx&);
+void __write(::IceInternal::BasicStream*, const AnalogInControllerPtr&);
+void __patch__AnalogInControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::AudioController> AudioControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::AudioController> AudioControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const AudioControllerPrx&);
+void __read(::IceInternal::BasicStream*, AudioControllerPrx&);
+void __write(::IceInternal::BasicStream*, const AudioControllerPtr&);
+void __patch__AudioControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::DigitalInController> DigitalInControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::DigitalInController> DigitalInControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const DigitalInControllerPrx&);
+void __read(::IceInternal::BasicStream*, DigitalInControllerPrx&);
+void __write(::IceInternal::BasicStream*, const DigitalInControllerPtr&);
+void __patch__DigitalInControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::DigitalOutController> DigitalOutControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::DigitalOutController> DigitalOutControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const DigitalOutControllerPrx&);
+void __read(::IceInternal::BasicStream*, DigitalOutControllerPrx&);
+void __write(::IceInternal::BasicStream*, const DigitalOutControllerPtr&);
+void __patch__DigitalOutControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::LEDController> LEDControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::LEDController> LEDControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const LEDControllerPrx&);
+void __read(::IceInternal::BasicStream*, LEDControllerPrx&);
+void __write(::IceInternal::BasicStream*, const LEDControllerPtr&);
+void __patch__LEDControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::MotorController> MotorControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::MotorController> MotorControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const MotorControllerPrx&);
+void __read(::IceInternal::BasicStream*, MotorControllerPrx&);
+void __write(::IceInternal::BasicStream*, const MotorControllerPtr&);
+void __patch__MotorControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::ServoController> ServoControllerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::ServoController> ServoControllerPrx;
+
+void __write(::IceInternal::BasicStream*, const ServoControllerPrx&);
+void __read(::IceInternal::BasicStream*, ServoControllerPrx&);
+void __write(::IceInternal::BasicStream*, const ServoControllerPtr&);
+void __patch__ServoControllerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::VideoStreamerClient> VideoStreamerClientPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::VideoStreamerClient> VideoStreamerClientPrx;
+
+void __write(::IceInternal::BasicStream*, const VideoStreamerClientPrx&);
+void __read(::IceInternal::BasicStream*, VideoStreamerClientPrx&);
+void __write(::IceInternal::BasicStream*, const VideoStreamerClientPtr&);
+void __patch__VideoStreamerClientPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::VideoStreamerServer> VideoStreamerServerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::VideoStreamerServer> VideoStreamerServerPrx;
+
+void __write(::IceInternal::BasicStream*, const VideoStreamerServerPrx&);
+void __read(::IceInternal::BasicStream*, VideoStreamerServerPrx&);
+void __write(::IceInternal::BasicStream*, const VideoStreamerServerPtr&);
+void __patch__VideoStreamerServerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::TerkUser> TerkUserPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::TerkUser> TerkUserPrx;
+
+void __write(::IceInternal::BasicStream*, const TerkUserPrx&);
+void __read(::IceInternal::BasicStream*, TerkUserPrx&);
+void __write(::IceInternal::BasicStream*, const TerkUserPtr&);
+void __patch__TerkUserPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::Qwerk> QwerkPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::Qwerk> QwerkPrx;
+
+void __write(::IceInternal::BasicStream*, const QwerkPrx&);
+void __read(::IceInternal::BasicStream*, QwerkPrx&);
+void __write(::IceInternal::BasicStream*, const QwerkPtr&);
+void __patch__QwerkPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::TeRK::TerkClient> TerkClientPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::TeRK::TerkClient> TerkClientPrx;
+
+void __write(::IceInternal::BasicStream*, const TerkClientPrx&);
+void __read(::IceInternal::BasicStream*, TerkClientPrx&);
+void __write(::IceInternal::BasicStream*, const TerkClientPtr&);
+void __patch__TerkClientPtr(void*, ::Ice::ObjectPtr&);
+
+}
+
+namespace TeRK
+{
+
+enum ImageFormat
+{
+    ImageJPEG,
+    ImageRGB24,
+    ImageRGB32,
+    ImageGray8,
+    ImageYUV420P,
+    ImageUnknown
+};
+
+void __write(::IceInternal::BasicStream*, ImageFormat);
+void __read(::IceInternal::BasicStream*, ImageFormat&);
+
+enum AudioMode
+{
+    AudioTone,
+    AudioClip
+};
+
+void __write(::IceInternal::BasicStream*, AudioMode);
+void __read(::IceInternal::BasicStream*, AudioMode&);
+
+enum LEDMode
+{
+    LEDOn,
+    LEDOff,
+    LEDBlinking
+};
+
+void __write(::IceInternal::BasicStream*, LEDMode);
+void __read(::IceInternal::BasicStream*, LEDMode&);
+
+enum MotorMode
+{
+    MotorSpeedControl,
+    MotorPositionControl,
+    MotorOff
+};
+
+void __write(::IceInternal::BasicStream*, MotorMode);
+void __read(::IceInternal::BasicStream*, MotorMode&);
+
+enum ServoMode
+{
+    ServoMotorSpeedControl,
+    ServoMotorPositionControl,
+    ServoOff
+};
+
+void __write(::IceInternal::BasicStream*, ServoMode);
+void __read(::IceInternal::BasicStream*, ServoMode&);
+
+typedef ::std::vector<bool> BooleanArray;
+
+class __U__BooleanArray { };
+
+typedef ::std::vector< ::Ice::Byte> ByteArray;
+
+class __U__ByteArray { };
+
+typedef ::std::vector< ::Ice::Int> IntArray;
+
+class __U__IntArray { };
+
+typedef ::std::vector< ::Ice::Short> ShortArray;
+
+class __U__ShortArray { };
+
+typedef ::std::vector< ::std::string> StringArray;
+
+class __U__StringArray { };
+
+typedef ::std::vector< ::TeRK::LEDMode> LEDModeArray;
+
+class __U__LEDModeArray { };
+void __write(::IceInternal::BasicStream*, const ::TeRK::LEDMode*, const ::TeRK::LEDMode*, __U__LEDModeArray);
+void __read(::IceInternal::BasicStream*, LEDModeArray&, __U__LEDModeArray);
+
+typedef ::std::vector< ::TeRK::MotorMode> MotorModeArray;
+
+class __U__MotorModeArray { };
+void __write(::IceInternal::BasicStream*, const ::TeRK::MotorMode*, const ::TeRK::MotorMode*, __U__MotorModeArray);
+void __read(::IceInternal::BasicStream*, MotorModeArray&, __U__MotorModeArray);
+
+typedef ::std::vector< ::TeRK::ServoMode> ServoModeArray;
+
+class __U__ServoModeArray { };
+void __write(::IceInternal::BasicStream*, const ::TeRK::ServoMode*, const ::TeRK::ServoMode*, __U__ServoModeArray);
+void __read(::IceInternal::BasicStream*, ServoModeArray&, __U__ServoModeArray);
+
+typedef ::std::map< ::std::string, ::Ice::Identity> ProxyTypeIdToIdentityMap;
+
+class __U__ProxyTypeIdToIdentityMap { };
+void __write(::IceInternal::BasicStream*, const ProxyTypeIdToIdentityMap&, __U__ProxyTypeIdToIdentityMap);
+void __read(::IceInternal::BasicStream*, ProxyTypeIdToIdentityMap&, __U__ProxyTypeIdToIdentityMap);
+
+typedef ::std::map< ::std::string, ::std::string> PropertyMap;
+
+class __U__PropertyMap { };
+void __write(::IceInternal::BasicStream*, const PropertyMap&, __U__PropertyMap);
+void __read(::IceInternal::BasicStream*, PropertyMap&, __U__PropertyMap);
+
+class GenericError : public ::Ice::UserException
+{
+public:
+
+    GenericError() {}
+    explicit GenericError(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    ::std::string reason;
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+static GenericError __GenericError_init;
+
+class TeRKException : public ::Ice::UserException
+{
+public:
+
+    TeRKException() {}
+    explicit TeRKException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    ::std::string reason;
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class MotorException : public ::TeRK::TeRKException
+{
+public:
+
+    MotorException() {}
+    explicit MotorException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class VideoException : public ::TeRK::TeRKException
+{
+public:
+
+    VideoException() {}
+    explicit VideoException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class ReadOnlyPropertyException : public ::TeRK::TeRKException
+{
+public:
+
+    ReadOnlyPropertyException() {}
+    explicit ReadOnlyPropertyException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class CommandException : public ::TeRK::TeRKException
+{
+public:
+
+    CommandException() {}
+    explicit CommandException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class AudioCommandException : public ::TeRK::CommandException
+{
+public:
+
+    AudioCommandException() {}
+    explicit AudioCommandException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class AudioCommandQueueFullException : public ::TeRK::AudioCommandException
+{
+public:
+
+    AudioCommandQueueFullException() {}
+    explicit AudioCommandQueueFullException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class AudioFileTooLargeException : public ::TeRK::AudioCommandException
+{
+public:
+
+    AudioFileTooLargeException() {}
+    explicit AudioFileTooLargeException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class DigitalOutCommandException : public ::TeRK::CommandException
+{
+public:
+
+    DigitalOutCommandException() {}
+    explicit DigitalOutCommandException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class LEDCommandException : public ::TeRK::CommandException
+{
+public:
+
+    LEDCommandException() {}
+    explicit LEDCommandException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class MotorCommandException : public ::TeRK::CommandException
+{
+public:
+
+    MotorCommandException() {}
+    explicit MotorCommandException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class ServoCommandException : public ::TeRK::CommandException
+{
+public:
+
+    ServoCommandException() {}
+    explicit ServoCommandException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+struct MotorBuffer
+{
+    ::TeRK::IntArray values;
+
+    bool operator==(const MotorBuffer&) const;
+    bool operator!=(const MotorBuffer&) const;
+    bool operator<(const MotorBuffer&) const;
+    bool operator<=(const MotorBuffer& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const MotorBuffer& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const MotorBuffer& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+typedef ::std::vector< ::TeRK::MotorBuffer> MotorBufferArray;
+
+class __U__MotorBufferArray { };
+void __write(::IceInternal::BasicStream*, const ::TeRK::MotorBuffer*, const ::TeRK::MotorBuffer*, __U__MotorBufferArray);
+void __read(::IceInternal::BasicStream*, MotorBufferArray&, __U__MotorBufferArray);
+
+struct Image
+{
+    ::Ice::Int height;
+    ::Ice::Int width;
+    ::Ice::Int frameNum;
+    ::TeRK::ImageFormat format;
+    ::TeRK::ByteArray data;
+
+    bool operator==(const Image&) const;
+    bool operator!=(const Image&) const;
+    bool operator<(const Image&) const;
+    bool operator<=(const Image& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const Image& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const Image& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct AnalogInState
+{
+    ::TeRK::ShortArray analogInValues;
+
+    bool operator==(const AnalogInState&) const;
+    bool operator!=(const AnalogInState&) const;
+    bool operator<(const AnalogInState&) const;
+    bool operator<=(const AnalogInState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const AnalogInState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const AnalogInState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct BatteryState
+{
+    ::Ice::Int batteryVoltage;
+
+    bool operator==(const BatteryState&) const;
+    bool operator!=(const BatteryState&) const;
+    bool operator<(const BatteryState&) const;
+    bool operator<=(const BatteryState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const BatteryState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const BatteryState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct ButtonState
+{
+    ::TeRK::BooleanArray buttonStates;
+
+    bool operator==(const ButtonState&) const;
+    bool operator!=(const ButtonState&) const;
+    bool operator<(const ButtonState&) const;
+    bool operator<=(const ButtonState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const ButtonState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const ButtonState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct DigitalInState
+{
+    ::TeRK::BooleanArray digitalInStates;
+
+    bool operator==(const DigitalInState&) const;
+    bool operator!=(const DigitalInState&) const;
+    bool operator<(const DigitalInState&) const;
+    bool operator<=(const DigitalInState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const DigitalInState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const DigitalInState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct MotorState
+{
+    ::TeRK::IntArray motorVelocities;
+    ::TeRK::IntArray motorPositions;
+    ::TeRK::IntArray motorCurrents;
+    ::TeRK::IntArray motorDutyCycles;
+    ::TeRK::BooleanArray motorDone;
+
+    bool operator==(const MotorState&) const;
+    bool operator!=(const MotorState&) const;
+    bool operator<(const MotorState&) const;
+    bool operator<=(const MotorState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const MotorState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const MotorState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct ServoState
+{
+    ::TeRK::IntArray servoPositions;
+
+    bool operator==(const ServoState&) const;
+    bool operator!=(const ServoState&) const;
+    bool operator<(const ServoState&) const;
+    bool operator<=(const ServoState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const ServoState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const ServoState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct QwerkState
+{
+    ::TeRK::AnalogInState analogIn;
+    ::TeRK::BatteryState battery;
+    ::TeRK::ButtonState button;
+    ::TeRK::DigitalInState digitalIn;
+    ::TeRK::MotorState motor;
+    ::TeRK::ServoState servo;
+
+    bool operator==(const QwerkState&) const;
+    bool operator!=(const QwerkState&) const;
+    bool operator<(const QwerkState&) const;
+    bool operator<=(const QwerkState& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const QwerkState& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const QwerkState& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct AudioCommand
+{
+    ::TeRK::AudioMode mode;
+    ::Ice::Int frequency;
+    ::Ice::Byte amplitude;
+    ::Ice::Int duration;
+    ::TeRK::ByteArray sound;
+
+    bool operator==(const AudioCommand&) const;
+    bool operator!=(const AudioCommand&) const;
+    bool operator<(const AudioCommand&) const;
+    bool operator<=(const AudioCommand& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const AudioCommand& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const AudioCommand& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct DigitalOutCommand
+{
+    ::TeRK::BooleanArray digitalOutMask;
+    ::TeRK::BooleanArray digitalOutValues;
+
+    bool operator==(const DigitalOutCommand&) const;
+    bool operator!=(const DigitalOutCommand&) const;
+    bool operator<(const DigitalOutCommand&) const;
+    bool operator<=(const DigitalOutCommand& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const DigitalOutCommand& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const DigitalOutCommand& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct LEDCommand
+{
+    ::TeRK::BooleanArray ledMask;
+    ::TeRK::LEDModeArray ledModes;
+
+    bool operator==(const LEDCommand&) const;
+    bool operator!=(const LEDCommand&) const;
+    bool operator<(const LEDCommand&) const;
+    bool operator<=(const LEDCommand& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const LEDCommand& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const LEDCommand& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct MotorCommand
+{
+    ::TeRK::BooleanArray motorMask;
+    ::TeRK::MotorModeArray motorModes;
+    ::TeRK::IntArray motorPositions;
+    ::TeRK::IntArray motorVelocities;
+    ::TeRK::IntArray motorAccelerations;
+
+    bool operator==(const MotorCommand&) const;
+    bool operator!=(const MotorCommand&) const;
+    bool operator<(const MotorCommand&) const;
+    bool operator<=(const MotorCommand& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const MotorCommand& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const MotorCommand& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct ServoCommand
+{
+    ::TeRK::BooleanArray servoMask;
+    ::TeRK::ServoModeArray servoModes;
+    ::TeRK::IntArray servoPositions;
+    ::TeRK::IntArray servoSpeeds;
+
+    bool operator==(const ServoCommand&) const;
+    bool operator!=(const ServoCommand&) const;
+    bool operator<(const ServoCommand&) const;
+    bool operator<=(const ServoCommand& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const ServoCommand& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const ServoCommand& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+struct QwerkCommand
+{
+    ::TeRK::AudioCommand audioCmd;
+    ::TeRK::DigitalOutCommand digitalOutCmd;
+    ::TeRK::LEDCommand ledCmd;
+    ::TeRK::MotorCommand motorCmd;
+    ::TeRK::ServoCommand servoCmd;
+
+    bool operator==(const QwerkCommand&) const;
+    bool operator!=(const QwerkCommand&) const;
+    bool operator<(const QwerkCommand&) const;
+    bool operator<=(const QwerkCommand& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const QwerkCommand& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const QwerkCommand& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+typedef ::std::vector< ::TeRK::AbstractCommandControllerPrx> AbstractCommandControllerProxyArray;
+
+class __U__AbstractCommandControllerProxyArray { };
+void __write(::IceInternal::BasicStream*, const ::TeRK::AbstractCommandControllerPrx*, const ::TeRK::AbstractCommandControllerPrx*, __U__AbstractCommandControllerProxyArray);
+void __read(::IceInternal::BasicStream*, AbstractCommandControllerProxyArray&, __U__AbstractCommandControllerProxyArray);
+
+}
+
+namespace TeRK
+{
+
+class AMI_PropertyManager_getProperty : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::std::string&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::PropertyManagerPrx&, const ::std::string&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_PropertyManager_getProperty> AMI_PropertyManager_getPropertyPtr;
+
+class AMI_PropertyManager_getProperties : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::PropertyMap&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::PropertyManagerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_PropertyManager_getProperties> AMI_PropertyManager_getPropertiesPtr;
+
+class AMI_PropertyManager_getPropertyKeys : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::StringArray&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::PropertyManagerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_PropertyManager_getPropertyKeys> AMI_PropertyManager_getPropertyKeysPtr;
+
+class AMI_PropertyManager_setProperty : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::PropertyManagerPrx&, const ::std::string&, const ::std::string&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_PropertyManager_setProperty> AMI_PropertyManager_setPropertyPtr;
+
+class AMI_AnalogInController_getState : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::AnalogInState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::AnalogInControllerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_AnalogInController_getState> AMI_AnalogInController_getStatePtr;
+
+class AMI_AudioController_execute : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::AudioControllerPrx&, const ::TeRK::AudioCommand&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_AudioController_execute> AMI_AudioController_executePtr;
+
+class AMI_DigitalInController_getState : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::DigitalInState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::DigitalInControllerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_DigitalInController_getState> AMI_DigitalInController_getStatePtr;
+
+class AMI_DigitalOutController_execute : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::DigitalOutControllerPrx&, const ::TeRK::DigitalOutCommand&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_DigitalOutController_execute> AMI_DigitalOutController_executePtr;
+
+class AMI_LEDController_execute : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::LEDControllerPrx&, const ::TeRK::LEDCommand&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_LEDController_execute> AMI_LEDController_executePtr;
+
+class AMI_MotorController_execute : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::MotorState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::TeRK::MotorCommand&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_execute> AMI_MotorController_executePtr;
+
+class AMI_MotorController_getFrequency : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(::Ice::Int) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_getFrequency> AMI_MotorController_getFrequencyPtr;
+
+class AMI_MotorController_startMotorBufferRecord : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_startMotorBufferRecord> AMI_MotorController_startMotorBufferRecordPtr;
+
+class AMI_MotorController_stopMotorBufferRecord : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_stopMotorBufferRecord> AMI_MotorController_stopMotorBufferRecordPtr;
+
+class AMI_MotorController_getMotorBuffers : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::MotorBufferArray&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_getMotorBuffers> AMI_MotorController_getMotorBuffersPtr;
+
+class AMI_MotorController_setMotorBuffer : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_setMotorBuffer> AMI_MotorController_setMotorBufferPtr;
+
+class AMI_MotorController_playMotorBuffer : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::MotorControllerPrx&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_MotorController_playMotorBuffer> AMI_MotorController_playMotorBufferPtr;
+
+class AMI_ServoController_execute : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ServoState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::ServoControllerPrx&, const ::TeRK::ServoCommand&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_ServoController_execute> AMI_ServoController_executePtr;
+
+class AMI_VideoStreamerServer_startVideoStream : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::VideoStreamerServerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_VideoStreamerServer_startVideoStream> AMI_VideoStreamerServer_startVideoStreamPtr;
+
+class AMI_VideoStreamerServer_stopVideoStream : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::VideoStreamerServerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_VideoStreamerServer_stopVideoStream> AMI_VideoStreamerServer_stopVideoStreamPtr;
+
+class AMI_VideoStreamerServer_startCamera : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(::Ice::Int) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::VideoStreamerServerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_VideoStreamerServer_startCamera> AMI_VideoStreamerServer_startCameraPtr;
+
+class AMI_VideoStreamerServer_stopCamera : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(::Ice::Int) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::VideoStreamerServerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_VideoStreamerServer_stopCamera> AMI_VideoStreamerServer_stopCameraPtr;
+
+class AMI_VideoStreamerServer_getFrame : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::Image&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::VideoStreamerServerPrx&, ::Ice::Int, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_VideoStreamerServer_getFrame> AMI_VideoStreamerServer_getFramePtr;
+
+class AMI_TerkUser_getSupportedServices : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ProxyTypeIdToIdentityMap&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::TerkUserPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_TerkUser_getSupportedServices> AMI_TerkUser_getSupportedServicesPtr;
+
+class AMI_Qwerk_getState : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::QwerkState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::QwerkPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_Qwerk_getState> AMI_Qwerk_getStatePtr;
+
+class AMI_Qwerk_execute : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::QwerkState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::QwerkPrx&, const ::TeRK::QwerkCommand&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_Qwerk_execute> AMI_Qwerk_executePtr;
+
+class AMI_Qwerk_emergencyStop : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::QwerkState&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::QwerkPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_Qwerk_emergencyStop> AMI_Qwerk_emergencyStopPtr;
+
+class AMI_Qwerk_getCommandControllerTypeToProxyIdentityMap : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response(const ::TeRK::ProxyTypeIdToIdentityMap&) = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::TeRK::QwerkPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMap> AMI_Qwerk_getCommandControllerTypeToProxyIdentityMapPtr;
+
+}
+
+namespace IceProxy
+{
+
+namespace TeRK
+{
+
+class PropertyManager : virtual public ::IceProxy::Ice::Object
+{
+public:
+
+    ::std::string getProperty(const ::std::string& key)
+    {
+	return getProperty(key, __defaultContext());
+    }
+    ::std::string getProperty(const ::std::string&, const ::Ice::Context&);
+    void getProperty_async(const ::TeRK::AMI_PropertyManager_getPropertyPtr&, const ::std::string&);
+    void getProperty_async(const ::TeRK::AMI_PropertyManager_getPropertyPtr&, const ::std::string&, const ::Ice::Context&);
+
+    ::TeRK::PropertyMap getProperties()
+    {
+	return getProperties(__defaultContext());
+    }
+    ::TeRK::PropertyMap getProperties(const ::Ice::Context&);
+    void getProperties_async(const ::TeRK::AMI_PropertyManager_getPropertiesPtr&);
+    void getProperties_async(const ::TeRK::AMI_PropertyManager_getPropertiesPtr&, const ::Ice::Context&);
+
+    ::TeRK::StringArray getPropertyKeys()
+    {
+	return getPropertyKeys(__defaultContext());
+    }
+    ::TeRK::StringArray getPropertyKeys(const ::Ice::Context&);
+    void getPropertyKeys_async(const ::TeRK::AMI_PropertyManager_getPropertyKeysPtr&);
+    void getPropertyKeys_async(const ::TeRK::AMI_PropertyManager_getPropertyKeysPtr&, const ::Ice::Context&);
+
+    void setProperty(const ::std::string& key, const ::std::string& value)
+    {
+	setProperty(key, value, __defaultContext());
+    }
+    void setProperty(const ::std::string&, const ::std::string&, const ::Ice::Context&);
+    void setProperty_async(const ::TeRK::AMI_PropertyManager_setPropertyPtr&, const ::std::string&, const ::std::string&);
+    void setProperty_async(const ::TeRK::AMI_PropertyManager_setPropertyPtr&, const ::std::string&, const ::std::string&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class AbstractCommandController : virtual public ::IceProxy::TeRK::PropertyManager
+{
+public:
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class AnalogInController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    ::TeRK::AnalogInState getState()
+    {
+	return getState(__defaultContext());
+    }
+    ::TeRK::AnalogInState getState(const ::Ice::Context&);
+    void getState_async(const ::TeRK::AMI_AnalogInController_getStatePtr&);
+    void getState_async(const ::TeRK::AMI_AnalogInController_getStatePtr&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class AudioController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    void execute(const ::TeRK::AudioCommand& command)
+    {
+	execute(command, __defaultContext());
+    }
+    void execute(const ::TeRK::AudioCommand&, const ::Ice::Context&);
+    void execute_async(const ::TeRK::AMI_AudioController_executePtr&, const ::TeRK::AudioCommand&);
+    void execute_async(const ::TeRK::AMI_AudioController_executePtr&, const ::TeRK::AudioCommand&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class DigitalInController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    ::TeRK::DigitalInState getState()
+    {
+	return getState(__defaultContext());
+    }
+    ::TeRK::DigitalInState getState(const ::Ice::Context&);
+    void getState_async(const ::TeRK::AMI_DigitalInController_getStatePtr&);
+    void getState_async(const ::TeRK::AMI_DigitalInController_getStatePtr&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class DigitalOutController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    void execute(const ::TeRK::DigitalOutCommand& command)
+    {
+	execute(command, __defaultContext());
+    }
+    void execute(const ::TeRK::DigitalOutCommand&, const ::Ice::Context&);
+    void execute_async(const ::TeRK::AMI_DigitalOutController_executePtr&, const ::TeRK::DigitalOutCommand&);
+    void execute_async(const ::TeRK::AMI_DigitalOutController_executePtr&, const ::TeRK::DigitalOutCommand&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class LEDController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    void execute(const ::TeRK::LEDCommand& command)
+    {
+	execute(command, __defaultContext());
+    }
+    void execute(const ::TeRK::LEDCommand&, const ::Ice::Context&);
+    void execute_async(const ::TeRK::AMI_LEDController_executePtr&, const ::TeRK::LEDCommand&);
+    void execute_async(const ::TeRK::AMI_LEDController_executePtr&, const ::TeRK::LEDCommand&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class MotorController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    ::TeRK::MotorState execute(const ::TeRK::MotorCommand& command)
+    {
+	return execute(command, __defaultContext());
+    }
+    ::TeRK::MotorState execute(const ::TeRK::MotorCommand&, const ::Ice::Context&);
+    void execute_async(const ::TeRK::AMI_MotorController_executePtr&, const ::TeRK::MotorCommand&);
+    void execute_async(const ::TeRK::AMI_MotorController_executePtr&, const ::TeRK::MotorCommand&, const ::Ice::Context&);
+
+    ::Ice::Int getFrequency()
+    {
+	return getFrequency(__defaultContext());
+    }
+    ::Ice::Int getFrequency(const ::Ice::Context&);
+    void getFrequency_async(const ::TeRK::AMI_MotorController_getFrequencyPtr&);
+    void getFrequency_async(const ::TeRK::AMI_MotorController_getFrequencyPtr&, const ::Ice::Context&);
+
+    void startMotorBufferRecord(const ::TeRK::BooleanArray& motorMask)
+    {
+	startMotorBufferRecord(motorMask, __defaultContext());
+    }
+    void startMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+    void startMotorBufferRecord_async(const ::TeRK::AMI_MotorController_startMotorBufferRecordPtr&, const ::TeRK::BooleanArray&);
+    void startMotorBufferRecord_async(const ::TeRK::AMI_MotorController_startMotorBufferRecordPtr&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    void stopMotorBufferRecord(const ::TeRK::BooleanArray& motorMask)
+    {
+	stopMotorBufferRecord(motorMask, __defaultContext());
+    }
+    void stopMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+    void stopMotorBufferRecord_async(const ::TeRK::AMI_MotorController_stopMotorBufferRecordPtr&, const ::TeRK::BooleanArray&);
+    void stopMotorBufferRecord_async(const ::TeRK::AMI_MotorController_stopMotorBufferRecordPtr&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    ::TeRK::MotorBufferArray getMotorBuffers(const ::TeRK::BooleanArray& motorMask)
+    {
+	return getMotorBuffers(motorMask, __defaultContext());
+    }
+    ::TeRK::MotorBufferArray getMotorBuffers(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+    void getMotorBuffers_async(const ::TeRK::AMI_MotorController_getMotorBuffersPtr&, const ::TeRK::BooleanArray&);
+    void getMotorBuffers_async(const ::TeRK::AMI_MotorController_getMotorBuffersPtr&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    void setMotorBuffer(const ::TeRK::BooleanArray& motorMask, const ::TeRK::MotorBufferArray& motorBuffers)
+    {
+	setMotorBuffer(motorMask, motorBuffers, __defaultContext());
+    }
+    void setMotorBuffer(const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Context&);
+    void setMotorBuffer_async(const ::TeRK::AMI_MotorController_setMotorBufferPtr&, const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&);
+    void setMotorBuffer_async(const ::TeRK::AMI_MotorController_setMotorBufferPtr&, const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Context&);
+
+    void playMotorBuffer(const ::TeRK::BooleanArray& motorMask)
+    {
+	playMotorBuffer(motorMask, __defaultContext());
+    }
+    void playMotorBuffer(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+    void playMotorBuffer_async(const ::TeRK::AMI_MotorController_playMotorBufferPtr&, const ::TeRK::BooleanArray&);
+    void playMotorBuffer_async(const ::TeRK::AMI_MotorController_playMotorBufferPtr&, const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    void driveForward()
+    {
+	driveForward(__defaultContext());
+    }
+    void driveForward(const ::Ice::Context&);
+
+    void driveBack()
+    {
+	driveBack(__defaultContext());
+    }
+    void driveBack(const ::Ice::Context&);
+
+    void spinLeft()
+    {
+	spinLeft(__defaultContext());
+    }
+    void spinLeft(const ::Ice::Context&);
+
+    void spinRight()
+    {
+	spinRight(__defaultContext());
+    }
+    void spinRight(const ::Ice::Context&);
+
+    void setMotorVelocities(const ::TeRK::IntArray& motorValues)
+    {
+	setMotorVelocities(motorValues, __defaultContext());
+    }
+    void setMotorVelocities(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    void stopMotors()
+    {
+	stopMotors(__defaultContext());
+    }
+    void stopMotors(const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class ServoController : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    ::TeRK::ServoState execute(const ::TeRK::ServoCommand& command)
+    {
+	return execute(command, __defaultContext());
+    }
+    ::TeRK::ServoState execute(const ::TeRK::ServoCommand&, const ::Ice::Context&);
+    void execute_async(const ::TeRK::AMI_ServoController_executePtr&, const ::TeRK::ServoCommand&);
+    void execute_async(const ::TeRK::AMI_ServoController_executePtr&, const ::TeRK::ServoCommand&, const ::Ice::Context&);
+
+    void cameraTiltUp()
+    {
+	cameraTiltUp(__defaultContext());
+    }
+    void cameraTiltUp(const ::Ice::Context&);
+
+    void cameraTiltDown()
+    {
+	cameraTiltDown(__defaultContext());
+    }
+    void cameraTiltDown(const ::Ice::Context&);
+
+    void cameraPanLeft()
+    {
+	cameraPanLeft(__defaultContext());
+    }
+    void cameraPanLeft(const ::Ice::Context&);
+
+    void cameraPanRight()
+    {
+	cameraPanRight(__defaultContext());
+    }
+    void cameraPanRight(const ::Ice::Context&);
+
+    void setServoPositions(const ::TeRK::IntArray& servoPositions)
+    {
+	setServoPositions(servoPositions, __defaultContext());
+    }
+    void setServoPositions(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    void setServoVelocities(const ::TeRK::IntArray& servoVelocities)
+    {
+	setServoVelocities(servoVelocities, __defaultContext());
+    }
+    void setServoVelocities(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    void stopServos()
+    {
+	stopServos(__defaultContext());
+    }
+    void stopServos(const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class VideoStreamerClient : virtual public ::IceProxy::Ice::Object
+{
+public:
+
+    void newFrame(const ::TeRK::Image& frame)
+    {
+	newFrame(frame, __defaultContext());
+    }
+    void newFrame(const ::TeRK::Image&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class VideoStreamerServer : virtual public ::IceProxy::TeRK::AbstractCommandController
+{
+public:
+
+    void startVideoStream()
+    {
+	startVideoStream(__defaultContext());
+    }
+    void startVideoStream(const ::Ice::Context&);
+    void startVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_startVideoStreamPtr&);
+    void startVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_startVideoStreamPtr&, const ::Ice::Context&);
+
+    void stopVideoStream()
+    {
+	stopVideoStream(__defaultContext());
+    }
+    void stopVideoStream(const ::Ice::Context&);
+    void stopVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_stopVideoStreamPtr&);
+    void stopVideoStream_async(const ::TeRK::AMI_VideoStreamerServer_stopVideoStreamPtr&, const ::Ice::Context&);
+
+    ::Ice::Int startCamera()
+    {
+	return startCamera(__defaultContext());
+    }
+    ::Ice::Int startCamera(const ::Ice::Context&);
+    void startCamera_async(const ::TeRK::AMI_VideoStreamerServer_startCameraPtr&);
+    void startCamera_async(const ::TeRK::AMI_VideoStreamerServer_startCameraPtr&, const ::Ice::Context&);
+
+    ::Ice::Int stopCamera()
+    {
+	return stopCamera(__defaultContext());
+    }
+    ::Ice::Int stopCamera(const ::Ice::Context&);
+    void stopCamera_async(const ::TeRK::AMI_VideoStreamerServer_stopCameraPtr&);
+    void stopCamera_async(const ::TeRK::AMI_VideoStreamerServer_stopCameraPtr&, const ::Ice::Context&);
+
+    ::TeRK::Image getFrame(::Ice::Int frameNumber)
+    {
+	return getFrame(frameNumber, __defaultContext());
+    }
+    ::TeRK::Image getFrame(::Ice::Int, const ::Ice::Context&);
+    void getFrame_async(const ::TeRK::AMI_VideoStreamerServer_getFramePtr&, ::Ice::Int);
+    void getFrame_async(const ::TeRK::AMI_VideoStreamerServer_getFramePtr&, ::Ice::Int, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class TerkUser : virtual public ::IceProxy::peer::ConnectionEventHandler,
+		 virtual public ::IceProxy::TeRK::PropertyManager
+{
+public:
+
+    ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices()
+    {
+	return getSupportedServices(__defaultContext());
+    }
+    ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices(const ::Ice::Context&);
+    void getSupportedServices_async(const ::TeRK::AMI_TerkUser_getSupportedServicesPtr&);
+    void getSupportedServices_async(const ::TeRK::AMI_TerkUser_getSupportedServicesPtr&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class Qwerk : virtual public ::IceProxy::TeRK::TerkUser
+{
+public:
+
+    ::TeRK::QwerkState getState()
+    {
+	return getState(__defaultContext());
+    }
+    ::TeRK::QwerkState getState(const ::Ice::Context&);
+    void getState_async(const ::TeRK::AMI_Qwerk_getStatePtr&);
+    void getState_async(const ::TeRK::AMI_Qwerk_getStatePtr&, const ::Ice::Context&);
+
+    ::TeRK::QwerkState execute(const ::TeRK::QwerkCommand& command)
+    {
+	return execute(command, __defaultContext());
+    }
+    ::TeRK::QwerkState execute(const ::TeRK::QwerkCommand&, const ::Ice::Context&);
+    void execute_async(const ::TeRK::AMI_Qwerk_executePtr&, const ::TeRK::QwerkCommand&);
+    void execute_async(const ::TeRK::AMI_Qwerk_executePtr&, const ::TeRK::QwerkCommand&, const ::Ice::Context&);
+
+    ::TeRK::QwerkState emergencyStop()
+    {
+	return emergencyStop(__defaultContext());
+    }
+    ::TeRK::QwerkState emergencyStop(const ::Ice::Context&);
+    void emergencyStop_async(const ::TeRK::AMI_Qwerk_emergencyStopPtr&);
+    void emergencyStop_async(const ::TeRK::AMI_Qwerk_emergencyStopPtr&, const ::Ice::Context&);
+
+    ::TeRK::ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap()
+    {
+	return getCommandControllerTypeToProxyIdentityMap(__defaultContext());
+    }
+    ::TeRK::ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context&);
+    void getCommandControllerTypeToProxyIdentityMap_async(const ::TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMapPtr&);
+    void getCommandControllerTypeToProxyIdentityMap_async(const ::TeRK::AMI_Qwerk_getCommandControllerTypeToProxyIdentityMapPtr&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class TerkClient : virtual public ::IceProxy::TeRK::TerkUser,
+		   virtual public ::IceProxy::TeRK::VideoStreamerClient
+{
+public:
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+}
+
+}
+
+namespace IceDelegate
+{
+
+namespace TeRK
+{
+
+class PropertyManager : virtual public ::IceDelegate::Ice::Object
+{
+public:
+
+    virtual ::std::string getProperty(const ::std::string&, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::PropertyMap getProperties(const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::StringArray getPropertyKeys(const ::Ice::Context&) = 0;
+
+    virtual void setProperty(const ::std::string&, const ::std::string&, const ::Ice::Context&) = 0;
+};
+
+class AbstractCommandController : virtual public ::IceDelegate::TeRK::PropertyManager
+{
+public:
+};
+
+class AnalogInController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::AnalogInState getState(const ::Ice::Context&) = 0;
+};
+
+class AudioController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::AudioCommand&, const ::Ice::Context&) = 0;
+};
+
+class DigitalInController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::DigitalInState getState(const ::Ice::Context&) = 0;
+};
+
+class DigitalOutController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::DigitalOutCommand&, const ::Ice::Context&) = 0;
+};
+
+class LEDController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::LEDCommand&, const ::Ice::Context&) = 0;
+};
+
+class MotorController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::MotorState execute(const ::TeRK::MotorCommand&, const ::Ice::Context&) = 0;
+
+    virtual ::Ice::Int getFrequency(const ::Ice::Context&) = 0;
+
+    virtual void startMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&) = 0;
+
+    virtual void stopMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::MotorBufferArray getMotorBuffers(const ::TeRK::BooleanArray&, const ::Ice::Context&) = 0;
+
+    virtual void setMotorBuffer(const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Context&) = 0;
+
+    virtual void playMotorBuffer(const ::TeRK::BooleanArray&, const ::Ice::Context&) = 0;
+
+    virtual void driveForward(const ::Ice::Context&) = 0;
+
+    virtual void driveBack(const ::Ice::Context&) = 0;
+
+    virtual void spinLeft(const ::Ice::Context&) = 0;
+
+    virtual void spinRight(const ::Ice::Context&) = 0;
+
+    virtual void setMotorVelocities(const ::TeRK::IntArray&, const ::Ice::Context&) = 0;
+
+    virtual void stopMotors(const ::Ice::Context&) = 0;
+};
+
+class ServoController : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::ServoState execute(const ::TeRK::ServoCommand&, const ::Ice::Context&) = 0;
+
+    virtual void cameraTiltUp(const ::Ice::Context&) = 0;
+
+    virtual void cameraTiltDown(const ::Ice::Context&) = 0;
+
+    virtual void cameraPanLeft(const ::Ice::Context&) = 0;
+
+    virtual void cameraPanRight(const ::Ice::Context&) = 0;
+
+    virtual void setServoPositions(const ::TeRK::IntArray&, const ::Ice::Context&) = 0;
+
+    virtual void setServoVelocities(const ::TeRK::IntArray&, const ::Ice::Context&) = 0;
+
+    virtual void stopServos(const ::Ice::Context&) = 0;
+};
+
+class VideoStreamerClient : virtual public ::IceDelegate::Ice::Object
+{
+public:
+
+    virtual void newFrame(const ::TeRK::Image&, const ::Ice::Context&) = 0;
+};
+
+class VideoStreamerServer : virtual public ::IceDelegate::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void startVideoStream(const ::Ice::Context&) = 0;
+
+    virtual void stopVideoStream(const ::Ice::Context&) = 0;
+
+    virtual ::Ice::Int startCamera(const ::Ice::Context&) = 0;
+
+    virtual ::Ice::Int stopCamera(const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::Image getFrame(::Ice::Int, const ::Ice::Context&) = 0;
+};
+
+class TerkUser : virtual public ::IceDelegate::peer::ConnectionEventHandler,
+		 virtual public ::IceDelegate::TeRK::PropertyManager
+{
+public:
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices(const ::Ice::Context&) = 0;
+};
+
+class Qwerk : virtual public ::IceDelegate::TeRK::TerkUser
+{
+public:
+
+    virtual ::TeRK::QwerkState getState(const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::QwerkState execute(const ::TeRK::QwerkCommand&, const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::QwerkState emergencyStop(const ::Ice::Context&) = 0;
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context&) = 0;
+};
+
+class TerkClient : virtual public ::IceDelegate::TeRK::TerkUser,
+		   virtual public ::IceDelegate::TeRK::VideoStreamerClient
+{
+public:
+};
+
+}
+
+}
+
+namespace IceDelegateM
+{
+
+namespace TeRK
+{
+
+class PropertyManager : virtual public ::IceDelegate::TeRK::PropertyManager,
+			virtual public ::IceDelegateM::Ice::Object
+{
+public:
+
+    virtual ::std::string getProperty(const ::std::string&, const ::Ice::Context&);
+
+    virtual ::TeRK::PropertyMap getProperties(const ::Ice::Context&);
+
+    virtual ::TeRK::StringArray getPropertyKeys(const ::Ice::Context&);
+
+    virtual void setProperty(const ::std::string&, const ::std::string&, const ::Ice::Context&);
+};
+
+class AbstractCommandController : virtual public ::IceDelegate::TeRK::AbstractCommandController,
+				  virtual public ::IceDelegateM::TeRK::PropertyManager
+{
+public:
+};
+
+class AnalogInController : virtual public ::IceDelegate::TeRK::AnalogInController,
+			   virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::AnalogInState getState(const ::Ice::Context&);
+};
+
+class AudioController : virtual public ::IceDelegate::TeRK::AudioController,
+			virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::AudioCommand&, const ::Ice::Context&);
+};
+
+class DigitalInController : virtual public ::IceDelegate::TeRK::DigitalInController,
+			    virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::DigitalInState getState(const ::Ice::Context&);
+};
+
+class DigitalOutController : virtual public ::IceDelegate::TeRK::DigitalOutController,
+			     virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::DigitalOutCommand&, const ::Ice::Context&);
+};
+
+class LEDController : virtual public ::IceDelegate::TeRK::LEDController,
+		      virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::LEDCommand&, const ::Ice::Context&);
+};
+
+class MotorController : virtual public ::IceDelegate::TeRK::MotorController,
+			virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::MotorState execute(const ::TeRK::MotorCommand&, const ::Ice::Context&);
+
+    virtual ::Ice::Int getFrequency(const ::Ice::Context&);
+
+    virtual void startMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual void stopMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual ::TeRK::MotorBufferArray getMotorBuffers(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual void setMotorBuffer(const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Context&);
+
+    virtual void playMotorBuffer(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual void driveForward(const ::Ice::Context&);
+
+    virtual void driveBack(const ::Ice::Context&);
+
+    virtual void spinLeft(const ::Ice::Context&);
+
+    virtual void spinRight(const ::Ice::Context&);
+
+    virtual void setMotorVelocities(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    virtual void stopMotors(const ::Ice::Context&);
+};
+
+class ServoController : virtual public ::IceDelegate::TeRK::ServoController,
+			virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::ServoState execute(const ::TeRK::ServoCommand&, const ::Ice::Context&);
+
+    virtual void cameraTiltUp(const ::Ice::Context&);
+
+    virtual void cameraTiltDown(const ::Ice::Context&);
+
+    virtual void cameraPanLeft(const ::Ice::Context&);
+
+    virtual void cameraPanRight(const ::Ice::Context&);
+
+    virtual void setServoPositions(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    virtual void setServoVelocities(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    virtual void stopServos(const ::Ice::Context&);
+};
+
+class VideoStreamerClient : virtual public ::IceDelegate::TeRK::VideoStreamerClient,
+			    virtual public ::IceDelegateM::Ice::Object
+{
+public:
+
+    virtual void newFrame(const ::TeRK::Image&, const ::Ice::Context&);
+};
+
+class VideoStreamerServer : virtual public ::IceDelegate::TeRK::VideoStreamerServer,
+			    virtual public ::IceDelegateM::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void startVideoStream(const ::Ice::Context&);
+
+    virtual void stopVideoStream(const ::Ice::Context&);
+
+    virtual ::Ice::Int startCamera(const ::Ice::Context&);
+
+    virtual ::Ice::Int stopCamera(const ::Ice::Context&);
+
+    virtual ::TeRK::Image getFrame(::Ice::Int, const ::Ice::Context&);
+};
+
+class TerkUser : virtual public ::IceDelegate::TeRK::TerkUser,
+		 virtual public ::IceDelegateM::peer::ConnectionEventHandler,
+		 virtual public ::IceDelegateM::TeRK::PropertyManager
+{
+public:
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices(const ::Ice::Context&);
+};
+
+class Qwerk : virtual public ::IceDelegate::TeRK::Qwerk,
+	      virtual public ::IceDelegateM::TeRK::TerkUser
+{
+public:
+
+    virtual ::TeRK::QwerkState getState(const ::Ice::Context&);
+
+    virtual ::TeRK::QwerkState execute(const ::TeRK::QwerkCommand&, const ::Ice::Context&);
+
+    virtual ::TeRK::QwerkState emergencyStop(const ::Ice::Context&);
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context&);
+};
+
+class TerkClient : virtual public ::IceDelegate::TeRK::TerkClient,
+		   virtual public ::IceDelegateM::TeRK::TerkUser,
+		   virtual public ::IceDelegateM::TeRK::VideoStreamerClient
+{
+public:
+};
+
+}
+
+}
+
+namespace IceDelegateD
+{
+
+namespace TeRK
+{
+
+class PropertyManager : virtual public ::IceDelegate::TeRK::PropertyManager,
+			virtual public ::IceDelegateD::Ice::Object
+{
+public:
+
+    virtual ::std::string getProperty(const ::std::string&, const ::Ice::Context&);
+
+    virtual ::TeRK::PropertyMap getProperties(const ::Ice::Context&);
+
+    virtual ::TeRK::StringArray getPropertyKeys(const ::Ice::Context&);
+
+    virtual void setProperty(const ::std::string&, const ::std::string&, const ::Ice::Context&);
+};
+
+class AbstractCommandController : virtual public ::IceDelegate::TeRK::AbstractCommandController,
+				  virtual public ::IceDelegateD::TeRK::PropertyManager
+{
+public:
+};
+
+class AnalogInController : virtual public ::IceDelegate::TeRK::AnalogInController,
+			   virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::AnalogInState getState(const ::Ice::Context&);
+};
+
+class AudioController : virtual public ::IceDelegate::TeRK::AudioController,
+			virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::AudioCommand&, const ::Ice::Context&);
+};
+
+class DigitalInController : virtual public ::IceDelegate::TeRK::DigitalInController,
+			    virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::DigitalInState getState(const ::Ice::Context&);
+};
+
+class DigitalOutController : virtual public ::IceDelegate::TeRK::DigitalOutController,
+			     virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::DigitalOutCommand&, const ::Ice::Context&);
+};
+
+class LEDController : virtual public ::IceDelegate::TeRK::LEDController,
+		      virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void execute(const ::TeRK::LEDCommand&, const ::Ice::Context&);
+};
+
+class MotorController : virtual public ::IceDelegate::TeRK::MotorController,
+			virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::MotorState execute(const ::TeRK::MotorCommand&, const ::Ice::Context&);
+
+    virtual ::Ice::Int getFrequency(const ::Ice::Context&);
+
+    virtual void startMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual void stopMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual ::TeRK::MotorBufferArray getMotorBuffers(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual void setMotorBuffer(const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Context&);
+
+    virtual void playMotorBuffer(const ::TeRK::BooleanArray&, const ::Ice::Context&);
+
+    virtual void driveForward(const ::Ice::Context&);
+
+    virtual void driveBack(const ::Ice::Context&);
+
+    virtual void spinLeft(const ::Ice::Context&);
+
+    virtual void spinRight(const ::Ice::Context&);
+
+    virtual void setMotorVelocities(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    virtual void stopMotors(const ::Ice::Context&);
+};
+
+class ServoController : virtual public ::IceDelegate::TeRK::ServoController,
+			virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual ::TeRK::ServoState execute(const ::TeRK::ServoCommand&, const ::Ice::Context&);
+
+    virtual void cameraTiltUp(const ::Ice::Context&);
+
+    virtual void cameraTiltDown(const ::Ice::Context&);
+
+    virtual void cameraPanLeft(const ::Ice::Context&);
+
+    virtual void cameraPanRight(const ::Ice::Context&);
+
+    virtual void setServoPositions(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    virtual void setServoVelocities(const ::TeRK::IntArray&, const ::Ice::Context&);
+
+    virtual void stopServos(const ::Ice::Context&);
+};
+
+class VideoStreamerClient : virtual public ::IceDelegate::TeRK::VideoStreamerClient,
+			    virtual public ::IceDelegateD::Ice::Object
+{
+public:
+
+    virtual void newFrame(const ::TeRK::Image&, const ::Ice::Context&);
+};
+
+class VideoStreamerServer : virtual public ::IceDelegate::TeRK::VideoStreamerServer,
+			    virtual public ::IceDelegateD::TeRK::AbstractCommandController
+{
+public:
+
+    virtual void startVideoStream(const ::Ice::Context&);
+
+    virtual void stopVideoStream(const ::Ice::Context&);
+
+    virtual ::Ice::Int startCamera(const ::Ice::Context&);
+
+    virtual ::Ice::Int stopCamera(const ::Ice::Context&);
+
+    virtual ::TeRK::Image getFrame(::Ice::Int, const ::Ice::Context&);
+};
+
+class TerkUser : virtual public ::IceDelegate::TeRK::TerkUser,
+		 virtual public ::IceDelegateD::peer::ConnectionEventHandler,
+		 virtual public ::IceDelegateD::TeRK::PropertyManager
+{
+public:
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices(const ::Ice::Context&);
+};
+
+class Qwerk : virtual public ::IceDelegate::TeRK::Qwerk,
+	      virtual public ::IceDelegateD::TeRK::TerkUser
+{
+public:
+
+    virtual ::TeRK::QwerkState getState(const ::Ice::Context&);
+
+    virtual ::TeRK::QwerkState execute(const ::TeRK::QwerkCommand&, const ::Ice::Context&);
+
+    virtual ::TeRK::QwerkState emergencyStop(const ::Ice::Context&);
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap(const ::Ice::Context&);
+};
+
+class TerkClient : virtual public ::IceDelegate::TeRK::TerkClient,
+		   virtual public ::IceDelegateD::TeRK::TerkUser,
+		   virtual public ::IceDelegateD::TeRK::VideoStreamerClient
+{
+public:
+};
+
+}
+
+}
+
+namespace TeRK
+{
+
+class PropertyManager : virtual public ::Ice::Object
+{
+public:
+
+    typedef PropertyManagerPrx ProxyType;
+    typedef PropertyManagerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::std::string getProperty(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getProperty(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::PropertyMap getProperties(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getProperties(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::StringArray getPropertyKeys(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getPropertyKeys(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void setProperty(const ::std::string&, const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___setProperty(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__PropertyManagerPtr(void*, ::Ice::ObjectPtr&);
+
+class AbstractCommandController : virtual public ::TeRK::PropertyManager
+{
+public:
+
+    typedef AbstractCommandControllerPrx ProxyType;
+    typedef AbstractCommandControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__AbstractCommandControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class AnalogInController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef AnalogInControllerPrx ProxyType;
+    typedef AnalogInControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::TeRK::AnalogInState getState(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getState(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__AnalogInControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class AudioController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef AudioControllerPrx ProxyType;
+    typedef AudioControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void execute(const ::TeRK::AudioCommand&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___execute(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__AudioControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class DigitalInController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef DigitalInControllerPrx ProxyType;
+    typedef DigitalInControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::TeRK::DigitalInState getState(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getState(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__DigitalInControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class DigitalOutController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef DigitalOutControllerPrx ProxyType;
+    typedef DigitalOutControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void execute(const ::TeRK::DigitalOutCommand&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___execute(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__DigitalOutControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class LEDController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef LEDControllerPrx ProxyType;
+    typedef LEDControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void execute(const ::TeRK::LEDCommand&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___execute(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__LEDControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class MotorController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef MotorControllerPrx ProxyType;
+    typedef MotorControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::TeRK::MotorState execute(const ::TeRK::MotorCommand&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___execute(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::Ice::Int getFrequency(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getFrequency(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void startMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___startMotorBufferRecord(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void stopMotorBufferRecord(const ::TeRK::BooleanArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___stopMotorBufferRecord(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::MotorBufferArray getMotorBuffers(const ::TeRK::BooleanArray&, const ::Ice::Current& = ::Ice::Current()) const = 0;
+    ::IceInternal::DispatchStatus ___getMotorBuffers(::IceInternal::Incoming&, const ::Ice::Current&) const;
+
+    virtual void setMotorBuffer(const ::TeRK::BooleanArray&, const ::TeRK::MotorBufferArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___setMotorBuffer(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void playMotorBuffer(const ::TeRK::BooleanArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___playMotorBuffer(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void driveForward(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___driveForward(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void driveBack(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___driveBack(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void spinLeft(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___spinLeft(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void spinRight(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___spinRight(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void setMotorVelocities(const ::TeRK::IntArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___setMotorVelocities(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void stopMotors(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___stopMotors(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__MotorControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class ServoController : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef ServoControllerPrx ProxyType;
+    typedef ServoControllerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::TeRK::ServoState execute(const ::TeRK::ServoCommand&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___execute(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void cameraTiltUp(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___cameraTiltUp(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void cameraTiltDown(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___cameraTiltDown(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void cameraPanLeft(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___cameraPanLeft(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void cameraPanRight(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___cameraPanRight(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void setServoPositions(const ::TeRK::IntArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___setServoPositions(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void setServoVelocities(const ::TeRK::IntArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___setServoVelocities(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void stopServos(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___stopServos(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__ServoControllerPtr(void*, ::Ice::ObjectPtr&);
+
+class VideoStreamerClient : virtual public ::Ice::Object
+{
+public:
+
+    typedef VideoStreamerClientPrx ProxyType;
+    typedef VideoStreamerClientPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void newFrame(const ::TeRK::Image&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___newFrame(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__VideoStreamerClientPtr(void*, ::Ice::ObjectPtr&);
+
+class VideoStreamerServer : virtual public ::TeRK::AbstractCommandController
+{
+public:
+
+    typedef VideoStreamerServerPrx ProxyType;
+    typedef VideoStreamerServerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void startVideoStream(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___startVideoStream(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void stopVideoStream(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___stopVideoStream(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::Ice::Int startCamera(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___startCamera(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::Ice::Int stopCamera(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___stopCamera(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::Image getFrame(::Ice::Int, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getFrame(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__VideoStreamerServerPtr(void*, ::Ice::ObjectPtr&);
+
+class TerkUser : virtual public ::peer::ConnectionEventHandler,
+		 virtual public ::TeRK::PropertyManager
+{
+public:
+
+    typedef TerkUserPrx ProxyType;
+    typedef TerkUserPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices(const ::Ice::Current& = ::Ice::Current()) const = 0;
+    ::IceInternal::DispatchStatus ___getSupportedServices(::IceInternal::Incoming&, const ::Ice::Current&) const;
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__TerkUserPtr(void*, ::Ice::ObjectPtr&);
+
+class Qwerk : virtual public ::TeRK::TerkUser
+{
+public:
+
+    typedef QwerkPrx ProxyType;
+    typedef QwerkPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::TeRK::QwerkState getState(const ::Ice::Current& = ::Ice::Current()) const = 0;
+    ::IceInternal::DispatchStatus ___getState(::IceInternal::Incoming&, const ::Ice::Current&) const;
+
+    virtual ::TeRK::QwerkState execute(const ::TeRK::QwerkCommand&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___execute(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::QwerkState emergencyStop(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___emergencyStop(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::TeRK::ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap(const ::Ice::Current& = ::Ice::Current()) const = 0;
+    ::IceInternal::DispatchStatus ___getCommandControllerTypeToProxyIdentityMap(::IceInternal::Incoming&, const ::Ice::Current&) const;
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__QwerkPtr(void*, ::Ice::ObjectPtr&);
+
+class TerkClient : virtual public ::TeRK::TerkUser,
+		   virtual public ::TeRK::VideoStreamerClient
+{
+public:
+
+    typedef TerkClientPrx ProxyType;
+    typedef TerkClientPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__TerkClientPtr(void*, ::Ice::ObjectPtr&);
+
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/TeRKPeerCommon.ice ./local/terk/TeRKPeerCommon.ice
--- ../Tekkotsu_3.0/local/terk/TeRKPeerCommon.ice	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/TeRKPeerCommon.ice	2007-03-12 18:34:10.000000000 -0400
@@ -0,0 +1,260 @@
+#ifndef TERK_PEER_COMMON_ICE
+#define TERK_PEER_COMMON_ICE
+
+#include <Ice/Identity.ice>
+#include <peer/MRPLPeer.ice>
+
+[["java:package:edu.cmu.ri.mrpl"]]
+module TeRK
+   {
+   enum ImageFormat {ImageJPEG, ImageRGB24, ImageRGB32, ImageGray8, ImageYUV420P, ImageUnknown};
+   enum AudioMode {AudioTone,AudioClip};
+   enum LEDMode {LEDOn,LEDOff,LEDBlinking};
+   enum MotorMode {MotorSpeedControl,MotorPositionControl,MotorOff};
+   enum ServoMode {ServoMotorSpeedControl,ServoMotorPositionControl,ServoOff};
+
+   sequence<bool> BooleanArray;
+   sequence<byte> ByteArray;
+   sequence<int> IntArray;
+   sequence<short> ShortArray;
+   ["java:type:java.util.ArrayList<String>"] sequence<string> StringArray;
+   sequence<LEDMode> LEDModeArray;
+   sequence<MotorMode> MotorModeArray;
+   sequence<ServoMode> ServoModeArray;
+
+   ["java:type:java.util.HashMap<String,Ice.Identity>"] dictionary<string,Ice::Identity> ProxyTypeIdToIdentityMap;
+
+   // todo: remove this once we get rid of the old API commands
+   exception GenericError
+      {
+      string reason;
+      };
+
+   exception TeRKException
+      {
+      string reason;
+      };
+
+   exception MotorException             extends TeRKException { };
+   exception VideoException             extends TeRKException { };
+   exception ReadOnlyPropertyException  extends TeRKException { };
+
+   exception CommandException           extends TeRKException { };
+   exception AudioCommandException      extends CommandException { };
+   exception DigitalOutCommandException extends CommandException { };
+   exception LEDCommandException        extends CommandException { };
+   exception MotorCommandException      extends CommandException { };
+   exception ServoCommandException      extends CommandException { };
+
+   struct MotorBuffer
+      {
+      IntArray values;
+      };
+
+   sequence<MotorBuffer> MotorBufferArray;
+
+   struct Image
+      {
+      int           height;
+      int           width;
+      int           frameNum;
+      ImageFormat   format;
+      ByteArray     data;
+      };
+
+   struct AnalogInState
+      {
+      ShortArray analogInValues;
+      };
+
+   struct BatteryState
+      {
+      int batteryVoltage;
+      };
+
+   struct ButtonState
+      {
+      BooleanArray buttonStates;       // buttons are not latched, so this just returns instantaneous value
+      };
+
+   struct DigitalInState
+      {
+      BooleanArray digitalInStates;
+      };
+
+   struct MotorState
+      {
+      IntArray       motorVelocities;
+      IntArray       motorPositions;
+      IntArray       motorCurrents;       // in mA
+      IntArray       motorDutyCycles;
+      BooleanArray   motorDone;
+      };
+
+   struct ServoState
+      {
+      IntArray servoPositions;
+      };
+
+   struct QwerkState
+      {
+      AnalogInState    analogIn;
+      BatteryState     battery;
+      ButtonState      button;
+      DigitalInState   digitalIn;
+      MotorState       motor;
+      ServoState       servo;
+      };
+
+   struct AudioCommand
+      {
+      AudioMode mode;
+      int       frequency;
+      byte      amplitude;
+      int       duration;     // milliseconds
+      ByteArray sound;
+      };
+
+   struct DigitalOutCommand
+      {
+      BooleanArray digitalOutMask;
+      BooleanArray digitalOutValues;
+      };
+
+   struct LEDCommand
+      {
+      BooleanArray ledMask;
+      LEDModeArray ledModes;
+      };
+
+   struct MotorCommand
+      {
+      BooleanArray motorMask;
+      MotorModeArray motorModes;
+      IntArray motorPositions;
+      IntArray motorVelocities;
+      IntArray motorAccelerations;
+      };
+
+   struct ServoCommand
+      {
+      BooleanArray servoMask;
+      ServoModeArray servoModes;
+      IntArray servoPositions;
+      IntArray servoSpeeds;
+      };
+
+   struct QwerkCommand
+      {
+      AudioCommand        audioCmd;
+      DigitalOutCommand   digitalOutCmd;
+      LEDCommand          ledCmd;
+      MotorCommand        motorCmd;
+      ServoCommand        servoCmd;
+      };
+
+   interface PropertyManager
+      {
+      ["ami"] string getProperty(string key);
+      ["ami"] void setProperty(string key, string value) throws ReadOnlyPropertyException;
+      ["ami"] StringArray getPropertyKeys();
+      };
+
+   interface AbstractCommandController extends PropertyManager { };
+
+   sequence<AbstractCommandController*> AbstractCommandControllerProxyArray;
+
+   interface AudioController extends AbstractCommandController
+      {
+      ["ami"] void execute(AudioCommand command) throws AudioCommandException;
+      };
+
+   interface DigitalOutController extends AbstractCommandController
+      {
+      ["ami"] void execute(DigitalOutCommand command) throws DigitalOutCommandException;
+      };
+
+   interface LEDController extends AbstractCommandController
+      {
+      ["ami"] void execute(LEDCommand command) throws LEDCommandException;
+      };
+
+   interface MotorController extends AbstractCommandController
+      {
+      ["ami"] MotorState execute(MotorCommand command) throws MotorCommandException;
+
+      // Motor buffer commands
+      ["ami"] int getFrequency();  // control periods per second
+      ["ami"] void startMotorBufferRecord(BooleanArray motorMask) throws MotorException;
+      ["ami"] idempotent void stopMotorBufferRecord(BooleanArray motorMask) throws MotorException;
+      ["ami"] nonmutating MotorBufferArray getMotorBuffers(BooleanArray motorMask) throws MotorException;
+      ["ami"] idempotent void setMotorBuffer(BooleanArray motorMask, MotorBufferArray motorBuffers) throws MotorException;
+      ["ami"] void playMotorBuffer(BooleanArray motorMask) throws MotorException;
+
+      // Old API (todo: remove these eventually)
+      void driveForward();
+      void driveBack();
+      void spinLeft();
+      void spinRight();
+      idempotent void setMotorVelocities(IntArray motorValues) throws GenericError;
+      void stopMotors();
+      };
+
+   interface ServoController extends AbstractCommandController
+      {
+      ["ami"] ServoState execute(ServoCommand command) throws ServoCommandException;
+
+      // Old API (todo: remove these eventually)
+      void cameraTiltUp();
+      void cameraTiltDown();
+      void cameraPanLeft();
+      void cameraPanRight();
+      void setServoPositions(IntArray servoPositions);
+      void setServoVelocities(IntArray servoVelocities);
+      void stopServos();
+      };
+
+   interface VideoStreamerClient
+      {
+      void newFrame(Image frame);
+      };
+
+   interface VideoStreamerServer extends AbstractCommandController
+      {
+      // for push model
+      ["ami"] idempotent void startVideoStream() throws VideoException;
+      ["ami"] idempotent void stopVideoStream() throws VideoException;
+
+      // for pull model
+      ["ami"] Image getFrame(int frameNumber) throws VideoException;
+      };
+
+   interface TerkUser extends peer::ConnectionEventHandler, PropertyManager
+      {
+      // Returns a map which specifies all the services that this TerkUser supports. The
+      // map associates proxy types (i.e. the result of .ice_getId()) with the private proxy
+      // identities that the user used to register the services with the relay (via
+      // the registerProxy() or registerProxies() method).  Peers call this method to see which
+      // commands the user supports so they know what kind of commands they can send to the peer.
+      // Peers will typically use the private identities in the returned map to fetch proxies
+      // from the relay via the getPeerProxy() or getPeerProxies() methods.
+      ["ami"] nonmutating ProxyTypeIdToIdentityMap getSupportedServices();
+      };
+
+   interface Qwerk extends TerkUser
+      {
+      ["ami"] nonmutating QwerkState getState();
+      ["ami"] QwerkState execute(QwerkCommand command) throws CommandException;
+      ["ami"] idempotent QwerkState emergencyStop();
+
+      // deprecated, use getSupportedServices() instead
+      ["ami"] nonmutating ProxyTypeIdToIdentityMap getCommandControllerTypeToProxyIdentityMap();
+      };
+
+   // todo: eventually change the client from Is-A to Has-A for the VideoStreamerClient interface
+   interface TerkClient extends TerkUser, VideoStreamerClient
+      {
+      };
+   };
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/TerkUserI.cc ./local/terk/TerkUserI.cc
--- ../Tekkotsu_3.0/local/terk/TerkUserI.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/TerkUserI.cc	2007-10-08 12:03:56.000000000 -0400
@@ -0,0 +1,64 @@
+#ifdef HAVE_ICE
+
+#include <Ice/Application.h>
+#include <Glacier2/Router.h>
+#include "TeRKPeerCommon.h"
+#include "peer/MRPLPeer.h"
+#include "TerkUserI.h"
+
+#include <unistd.h>
+#include <map>
+#include <iostream>
+#include <fstream>
+
+using namespace std;
+using namespace peer;
+using namespace TeRK;
+
+
+TerkUserI::TerkUserI():frameCount(0),ic(0){
+
+}
+
+void TerkUserI::forcedLogoutNotification(const Ice::Current&){
+  printf("forced Logout!\n");
+  exit(1);
+}
+
+void TerkUserI::peerConnected(const ::std::string& peerUserId,
+			      ::peer::PeerAccessLevel accessLevel,
+			      const ::Ice::ObjectPrx& peerProxy,
+			      const Ice::Current& current){
+  printf("Peer connected\n");
+}
+
+void TerkUserI::peerConnectedNoProxy(const ::std::string& peerUserId, 
+				     ::peer::PeerAccessLevel accessLevel, 
+				     const Ice::Current& current){
+  printf("Peer connected without a proxy\n");
+}
+
+void TerkUserI::peerDisconnected(const ::std::string& peerUserId, const Ice::Current& current){
+  printf("Peer Disconnected");
+}
+
+ProxyTypeIdToIdentityMap TerkUserI::getSupportedServices(const Ice::Current&) const{
+  return ProxyTypeIdToIdentityMap();
+}
+
+void TerkUserI::newFrame(const ::TeRK::Image& img, const ::Ice::Current& current){
+	if(ic)
+		ic->newImage(img.data);
+}
+
+
+void TerkUserI::setImageCache(ImageCache* in_ic){
+  this->ic = in_ic;
+}
+
+PropertyMap TerkUserI::getProperties(const Ice::Current& current){
+  PropertyMap p;
+  return p;
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/TerkUserI.h ./local/terk/TerkUserI.h
--- ../Tekkotsu_3.0/local/terk/TerkUserI.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/TerkUserI.h	2007-11-11 18:57:31.000000000 -0500
@@ -0,0 +1,44 @@
+#ifndef TERK_USER_I
+#define TERK_USER_I
+
+#include <Ice/Application.h>
+#include <Glacier2/Router.h>
+#include "TeRKPeerCommon.h"
+#include "peer/MRPLPeer.h"
+#include "PropertyManagerI.h"
+#include "ImageCache.h"
+
+#include <unistd.h>
+#include <map>
+#include <iostream>
+#include <fstream>
+
+class TerkUserI : public PropertyManagerI, public ::TeRK::TerkClient
+{
+public:
+  int frameCount;
+  TerkUserI();
+  void forcedLogoutNotification(const Ice::Current&);
+  void peerConnected(const ::std::string& peerUserId,
+		     ::peer::PeerAccessLevel accessLevel,
+		     const ::Ice::ObjectPrx& peerProxy,
+		     const Ice::Current& current);
+  void peerConnectedNoProxy(const ::std::string& peerUserId, 
+			    ::peer::PeerAccessLevel accessLevel, 
+			    const Ice::Current& current);
+  void peerDisconnected(const ::std::string& peerUserId, const Ice::Current& current);
+  //void bindFrameEvent(ImageCache ic);
+  ::TeRK::ProxyTypeIdToIdentityMap getSupportedServices(const Ice::Current&) const;
+  virtual void newFrame(const ::TeRK::Image& img, const ::Ice::Current& current);
+  ::TeRK::PropertyMap getProperties(const Ice::Current&);
+  virtual void setImageCache(ImageCache* ic);
+ private:
+  ImageCache* ic;
+
+	TerkUserI(const TerkUserI&); //!< do not call
+	TerkUserI& operator=(const TerkUserI&); //!< do not call
+};
+
+
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/config ./local/terk/config
--- ../Tekkotsu_3.0/local/terk/config	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/config	2007-03-12 18:34:10.000000000 -0400
@@ -0,0 +1,55 @@
+#
+# The proxy to the Glacier2 router for all outgoing connections. This
+# must match the value of Glacier2.Client.Endpoints in config.glacier2.
+#
+Ice.Default.Router=TerkGlacier/router:tcp -p 10004 -h 128.2.211.159
+
+#
+# The proxy for the Glacier2 router, installed in the client's
+# object adapter named Chat.Client. This router proxy must
+# match the value of Glacier2.Client.Endpoints.
+#
+TerkClient.Client.Router=TerkGlacier/router:tcp -p 10004 -h 128.2.211.159
+
+#
+# We don't need any endpoints for the client if we use a
+# router. Incoming requests are received through connections
+# established from the client to the router.
+#
+TerkClient.Client.Endpoints=
+
+#
+# No active connection management is permitted with Glacier2.
+# Connections must remain established.
+#
+Ice.ACM.Client=0
+Ice.ACM.Server=0
+
+#
+# Ice.MonitorConnections defaults to the smaller of Ice.ACM.Client or
+# Ice.ACM.Server, which we set to 0 above. However we still want the
+# connection monitor thread for AMI timeouts (for completeness, even
+# if this demo doesn't use AMI).
+#
+Ice.MonitorConnections=60
+
+#
+# Connection retry is not possible with Glacier2. Connections must
+# remain established.
+#
+Ice.RetryIntervals=-1
+
+#
+# Other settings.
+#
+
+#Ice.Trace.Network=1
+#Ice.Trace.Protocol=1
+Ice.Warn.Connections=1
+
+Ice.Plugin.IceSSL=IceSSL:create
+IceSSL.Client.CertPath=certs
+IceSSL.Client.Config=sslconfig.xml
+IceSSL.Server.CertPath=certs
+IceSSL.Server.Config=sslconfig.xml
+#IceSSL.Trace.Security=1
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/direct-config ./local/terk/direct-config
--- ../Tekkotsu_3.0/local/terk/direct-config	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/direct-config	2007-03-12 18:34:10.000000000 -0400
@@ -0,0 +1,23 @@
+Ice.Package.peer=edu.cmu.ri.mrpl
+Ice.Package.TeRK=edu.cmu.ri.mrpl
+Ice.Default.Package=edu.cmu.ri.mrpl
+
+TerkClient.Client.Endpoints=tcp
+
+# Active connection management must be disabled when using bidirectional connections.
+Ice.ACM.Client=0
+Ice.ACM.Server=0
+
+# Print warning messages for certain exceptional conditions in connections
+Ice.Warn.Connections=1
+
+Ice.Logger.Timestamp=1
+
+Ice.ThreadPool.Client.Size=5
+Ice.ThreadPool.Client.SizeMax=20
+Ice.ThreadPool.Server.Size=5
+Ice.ThreadPool.Server.SizeMax=20
+
+# protocol and port to use for direct connect
+TeRK.direct-connect.protocol=tcp
+TeRK.direct-connect.port=10101
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/password ./local/terk/password
--- ../Tekkotsu_3.0/local/terk/password	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/password	2007-03-12 18:34:10.000000000 -0400
@@ -0,0 +1 @@
+testing
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/peer/MRPLPeer.cc ./local/terk/peer/MRPLPeer.cc
--- ../Tekkotsu_3.0/local/terk/peer/MRPLPeer.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/peer/MRPLPeer.cc	2007-06-07 14:28:19.000000000 -0400
@@ -0,0 +1,4335 @@
+#ifdef HAVE_ICE
+
+// **********************************************************************
+//
+// Copyright (c) 2003-2006 ZeroC, Inc. All rights reserved.
+//
+// This copy of Ice is licensed to you under the terms described in the
+// ICE_LICENSE file included in this distribution.
+//
+// **********************************************************************
+
+// Ice version 3.1.1
+// Generated from file `MRPLPeer.ice'
+
+#include "MRPLPeer.h"
+#include <Ice/LocalException.h>
+#include <Ice/ObjectFactory.h>
+#include <Ice/BasicStream.h>
+#include <Ice/Object.h>
+#include <IceUtil/Iterator.h>
+
+#ifndef ICE_IGNORE_VERSION
+#   if ICE_INT_VERSION / 100 != 301
+#       error Ice version mismatch!
+#   endif
+#   if ICE_INT_VERSION % 100 < 1
+#       error Ice patch level mismatch!
+#   endif
+#endif
+
+static const ::std::string __peer__UserConnectionEventHandler__forcedLogoutNotification_name = "forcedLogoutNotification";
+
+static const ::std::string __peer__PeerConnectionEventHandler__peerConnected_name = "peerConnected";
+
+static const ::std::string __peer__PeerConnectionEventHandler__peerConnectedNoProxy_name = "peerConnectedNoProxy";
+
+static const ::std::string __peer__PeerConnectionEventHandler__peerDisconnected_name = "peerDisconnected";
+
+static const ::std::string __peer__PeerRegistrationHandler__registerCallbacks_name = "registerCallbacks";
+
+static const ::std::string __peer__PeerRegistrationHandler__registerProxy_name = "registerProxy";
+
+static const ::std::string __peer__PeerRegistrationHandler__registerProxies_name = "registerProxies";
+
+static const ::std::string __peer__PeerRegistrationHandler__getPeerProxy_name = "getPeerProxy";
+
+static const ::std::string __peer__PeerRegistrationHandler__getPeerProxies_name = "getPeerProxies";
+
+static const ::std::string __peer__UserSession__getMyAvailablePeers_name = "getMyAvailablePeers";
+
+static const ::std::string __peer__UserSession__connectToPeer_name = "connectToPeer";
+
+static const ::std::string __peer__UserSession__getConnectedPeers_name = "getConnectedPeers";
+
+static const ::std::string __peer__UserSession__disconnectFromPeer_name = "disconnectFromPeer";
+
+static const ::std::string __peer__UserSession__disconnectFromPeers_name = "disconnectFromPeers";
+
+void
+IceInternal::incRef(::peer::UserConnectionEventHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::peer::UserConnectionEventHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::peer::UserConnectionEventHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::peer::UserConnectionEventHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::peer::PeerConnectionEventHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::peer::PeerConnectionEventHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::peer::PeerConnectionEventHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::peer::PeerConnectionEventHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::peer::ConnectionEventHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::peer::ConnectionEventHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::peer::ConnectionEventHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::peer::ConnectionEventHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::peer::PeerRegistrationHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::peer::PeerRegistrationHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::peer::PeerRegistrationHandler* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::peer::PeerRegistrationHandler* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::peer::UserSession* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::peer::UserSession* p)
+{
+    p->__decRef();
+}
+
+void
+IceInternal::incRef(::IceProxy::peer::UserSession* p)
+{
+    p->__incRef();
+}
+
+void
+IceInternal::decRef(::IceProxy::peer::UserSession* p)
+{
+    p->__decRef();
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::UserConnectionEventHandlerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::UserConnectionEventHandlerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::peer::UserConnectionEventHandler;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::UserConnectionEventHandlerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::PeerConnectionEventHandlerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::PeerConnectionEventHandlerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::peer::PeerConnectionEventHandler;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::PeerConnectionEventHandlerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::ConnectionEventHandlerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::ConnectionEventHandlerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::peer::ConnectionEventHandler;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::ConnectionEventHandlerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::PeerRegistrationHandlerPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::PeerRegistrationHandlerPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::peer::PeerRegistrationHandler;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::PeerRegistrationHandlerPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::UserSessionPrx& v)
+{
+    __os->write(::Ice::ObjectPrx(v));
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::UserSessionPrx& v)
+{
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    if(!proxy)
+    {
+	v = 0;
+    }
+    else
+    {
+	v = new ::IceProxy::peer::UserSession;
+	v->__copyFrom(proxy);
+    }
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::UserSessionPtr& v)
+{
+    __os->write(::Ice::ObjectPtr(v));
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, ::peer::PeerAccessLevel v)
+{
+    __os->write(static_cast< ::Ice::Byte>(v));
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::PeerAccessLevel& v)
+{
+    ::Ice::Byte val;
+    __is->read(val);
+    v = static_cast< ::peer::PeerAccessLevel>(val);
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::Ice::Identity* begin, const ::Ice::Identity* end, ::peer::__U__IdentityArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	begin[i].__write(__os);
+    }
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::IdentityArray& v, ::peer::__U__IdentityArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->startSeq(sz, 2);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	v[i].__read(__is);
+	__is->checkSeq();
+	__is->endElement();
+    }
+    __is->endSeq(sz);
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::Ice::ObjectPrx* begin, const ::Ice::ObjectPrx* end, ::peer::__U__ObjectProxyArray)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	__os->write(begin[i]);
+    }
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::ObjectProxyArray& v, ::peer::__U__ObjectProxyArray)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->startSeq(sz, 2);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	__is->read(v[i]);
+	__is->checkSeq();
+	__is->endElement();
+    }
+    __is->endSeq(sz);
+}
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::IdentityToProxyMap& v, ::peer::__U__IdentityToProxyMap)
+{
+    __os->writeSize(::Ice::Int(v.size()));
+    ::peer::IdentityToProxyMap::const_iterator p;
+    for(p = v.begin(); p != v.end(); ++p)
+    {
+	p->first.__write(__os);
+	__os->write(p->second);
+    }
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::IdentityToProxyMap& v, ::peer::__U__IdentityToProxyMap)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    while(sz--)
+    {
+	::std::pair<const  ::Ice::Identity, ::Ice::ObjectPrx> pair;
+	const_cast< ::Ice::Identity&>(pair.first).__read(__is);
+	::peer::IdentityToProxyMap::iterator __i = v.insert(v.end(), pair);
+	__is->read(__i->second);
+    }
+}
+
+bool
+peer::PeerIdentifier::operator==(const PeerIdentifier& __rhs) const
+{
+    return !operator!=(__rhs);
+}
+
+bool
+peer::PeerIdentifier::operator!=(const PeerIdentifier& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(userId != __rhs.userId)
+    {
+	return true;
+    }
+    if(firstName != __rhs.firstName)
+    {
+	return true;
+    }
+    if(lastName != __rhs.lastName)
+    {
+	return true;
+    }
+    return false;
+}
+
+bool
+peer::PeerIdentifier::operator<(const PeerIdentifier& __rhs) const
+{
+    if(this == &__rhs)
+    {
+	return false;
+    }
+    if(userId < __rhs.userId)
+    {
+	return true;
+    }
+    else if(__rhs.userId < userId)
+    {
+	return false;
+    }
+    if(firstName < __rhs.firstName)
+    {
+	return true;
+    }
+    else if(__rhs.firstName < firstName)
+    {
+	return false;
+    }
+    if(lastName < __rhs.lastName)
+    {
+	return true;
+    }
+    else if(__rhs.lastName < lastName)
+    {
+	return false;
+    }
+    return false;
+}
+
+void
+peer::PeerIdentifier::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(userId);
+    __os->write(firstName);
+    __os->write(lastName);
+}
+
+void
+peer::PeerIdentifier::__read(::IceInternal::BasicStream* __is)
+{
+    __is->read(userId);
+    __is->read(firstName);
+    __is->read(lastName);
+}
+
+peer::PeerException::PeerException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    UserException(),
+#else
+    ::Ice::UserException(),
+#endif
+    reason(__ice_reason)
+{
+}
+
+static const char* __peer__PeerException_name = "peer::PeerException";
+
+const ::std::string
+peer::PeerException::ice_name() const
+{
+    return __peer__PeerException_name;
+}
+
+::Ice::Exception*
+peer::PeerException::ice_clone() const
+{
+    return new PeerException(*this);
+}
+
+void
+peer::PeerException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::PeerException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::PeerException"), false);
+    __os->startWriteSlice();
+    __os->write(reason);
+    __os->endWriteSlice();
+}
+
+void
+peer::PeerException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->read(reason);
+    __is->endReadSlice();
+}
+
+void
+peer::PeerException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::PeerException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__PeerException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::PeerException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__PeerException__Ptr = new __F__peer__PeerException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::PeerException::ice_factory()
+{
+    return __F__peer__PeerException__Ptr;
+}
+
+class __F__peer__PeerException__Init
+{
+public:
+
+    __F__peer__PeerException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::PeerException", ::peer::PeerException::ice_factory());
+    }
+
+    ~__F__peer__PeerException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::PeerException");
+    }
+};
+
+static __F__peer__PeerException__Init __F__peer__PeerException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__PeerException__initializer() {} }
+#endif
+
+peer::InvalidIdentityException::InvalidIdentityException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException(__ice_reason)
+#else
+    ::peer::PeerException(__ice_reason)
+#endif
+{
+}
+
+static const char* __peer__InvalidIdentityException_name = "peer::InvalidIdentityException";
+
+const ::std::string
+peer::InvalidIdentityException::ice_name() const
+{
+    return __peer__InvalidIdentityException_name;
+}
+
+::Ice::Exception*
+peer::InvalidIdentityException::ice_clone() const
+{
+    return new InvalidIdentityException(*this);
+}
+
+void
+peer::InvalidIdentityException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::InvalidIdentityException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::InvalidIdentityException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__write(__os);
+#else
+    ::peer::PeerException::__write(__os);
+#endif
+}
+
+void
+peer::InvalidIdentityException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__read(__is, true);
+#else
+    ::peer::PeerException::__read(__is, true);
+#endif
+}
+
+void
+peer::InvalidIdentityException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::InvalidIdentityException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::InvalidIdentityException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::InvalidIdentityException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__InvalidIdentityException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::InvalidIdentityException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__InvalidIdentityException__Ptr = new __F__peer__InvalidIdentityException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::InvalidIdentityException::ice_factory()
+{
+    return __F__peer__InvalidIdentityException__Ptr;
+}
+
+class __F__peer__InvalidIdentityException__Init
+{
+public:
+
+    __F__peer__InvalidIdentityException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::InvalidIdentityException", ::peer::InvalidIdentityException::ice_factory());
+    }
+
+    ~__F__peer__InvalidIdentityException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::InvalidIdentityException");
+    }
+};
+
+static __F__peer__InvalidIdentityException__Init __F__peer__InvalidIdentityException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__InvalidIdentityException__initializer() {} }
+#endif
+
+peer::PeerAccessException::PeerAccessException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException(__ice_reason)
+#else
+    ::peer::PeerException(__ice_reason)
+#endif
+{
+}
+
+static const char* __peer__PeerAccessException_name = "peer::PeerAccessException";
+
+const ::std::string
+peer::PeerAccessException::ice_name() const
+{
+    return __peer__PeerAccessException_name;
+}
+
+::Ice::Exception*
+peer::PeerAccessException::ice_clone() const
+{
+    return new PeerAccessException(*this);
+}
+
+void
+peer::PeerAccessException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::PeerAccessException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::PeerAccessException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__write(__os);
+#else
+    ::peer::PeerException::__write(__os);
+#endif
+}
+
+void
+peer::PeerAccessException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__read(__is, true);
+#else
+    ::peer::PeerException::__read(__is, true);
+#endif
+}
+
+void
+peer::PeerAccessException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerAccessException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::PeerAccessException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerAccessException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__PeerAccessException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::PeerAccessException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__PeerAccessException__Ptr = new __F__peer__PeerAccessException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::PeerAccessException::ice_factory()
+{
+    return __F__peer__PeerAccessException__Ptr;
+}
+
+class __F__peer__PeerAccessException__Init
+{
+public:
+
+    __F__peer__PeerAccessException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::PeerAccessException", ::peer::PeerAccessException::ice_factory());
+    }
+
+    ~__F__peer__PeerAccessException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::PeerAccessException");
+    }
+};
+
+static __F__peer__PeerAccessException__Init __F__peer__PeerAccessException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__PeerAccessException__initializer() {} }
+#endif
+
+peer::PeerUnavailableException::PeerUnavailableException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException(__ice_reason)
+#else
+    ::peer::PeerException(__ice_reason)
+#endif
+{
+}
+
+static const char* __peer__PeerUnavailableException_name = "peer::PeerUnavailableException";
+
+const ::std::string
+peer::PeerUnavailableException::ice_name() const
+{
+    return __peer__PeerUnavailableException_name;
+}
+
+::Ice::Exception*
+peer::PeerUnavailableException::ice_clone() const
+{
+    return new PeerUnavailableException(*this);
+}
+
+void
+peer::PeerUnavailableException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::PeerUnavailableException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::PeerUnavailableException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__write(__os);
+#else
+    ::peer::PeerException::__write(__os);
+#endif
+}
+
+void
+peer::PeerUnavailableException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__read(__is, true);
+#else
+    ::peer::PeerException::__read(__is, true);
+#endif
+}
+
+void
+peer::PeerUnavailableException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerUnavailableException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::PeerUnavailableException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerUnavailableException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__PeerUnavailableException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::PeerUnavailableException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__PeerUnavailableException__Ptr = new __F__peer__PeerUnavailableException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::PeerUnavailableException::ice_factory()
+{
+    return __F__peer__PeerUnavailableException__Ptr;
+}
+
+class __F__peer__PeerUnavailableException__Init
+{
+public:
+
+    __F__peer__PeerUnavailableException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::PeerUnavailableException", ::peer::PeerUnavailableException::ice_factory());
+    }
+
+    ~__F__peer__PeerUnavailableException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::PeerUnavailableException");
+    }
+};
+
+static __F__peer__PeerUnavailableException__Init __F__peer__PeerUnavailableException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__PeerUnavailableException__initializer() {} }
+#endif
+
+peer::PeerConnectionFailedException::PeerConnectionFailedException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException(__ice_reason)
+#else
+    ::peer::PeerException(__ice_reason)
+#endif
+{
+}
+
+static const char* __peer__PeerConnectionFailedException_name = "peer::PeerConnectionFailedException";
+
+const ::std::string
+peer::PeerConnectionFailedException::ice_name() const
+{
+    return __peer__PeerConnectionFailedException_name;
+}
+
+::Ice::Exception*
+peer::PeerConnectionFailedException::ice_clone() const
+{
+    return new PeerConnectionFailedException(*this);
+}
+
+void
+peer::PeerConnectionFailedException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::PeerConnectionFailedException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::PeerConnectionFailedException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__write(__os);
+#else
+    ::peer::PeerException::__write(__os);
+#endif
+}
+
+void
+peer::PeerConnectionFailedException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__read(__is, true);
+#else
+    ::peer::PeerException::__read(__is, true);
+#endif
+}
+
+void
+peer::PeerConnectionFailedException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerConnectionFailedException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::PeerConnectionFailedException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::PeerConnectionFailedException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__PeerConnectionFailedException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::PeerConnectionFailedException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__PeerConnectionFailedException__Ptr = new __F__peer__PeerConnectionFailedException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::PeerConnectionFailedException::ice_factory()
+{
+    return __F__peer__PeerConnectionFailedException__Ptr;
+}
+
+class __F__peer__PeerConnectionFailedException__Init
+{
+public:
+
+    __F__peer__PeerConnectionFailedException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::PeerConnectionFailedException", ::peer::PeerConnectionFailedException::ice_factory());
+    }
+
+    ~__F__peer__PeerConnectionFailedException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::PeerConnectionFailedException");
+    }
+};
+
+static __F__peer__PeerConnectionFailedException__Init __F__peer__PeerConnectionFailedException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__PeerConnectionFailedException__initializer() {} }
+#endif
+
+peer::DuplicateConnectionException::DuplicateConnectionException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException(__ice_reason)
+#else
+    ::peer::PeerException(__ice_reason)
+#endif
+{
+}
+
+static const char* __peer__DuplicateConnectionException_name = "peer::DuplicateConnectionException";
+
+const ::std::string
+peer::DuplicateConnectionException::ice_name() const
+{
+    return __peer__DuplicateConnectionException_name;
+}
+
+::Ice::Exception*
+peer::DuplicateConnectionException::ice_clone() const
+{
+    return new DuplicateConnectionException(*this);
+}
+
+void
+peer::DuplicateConnectionException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::DuplicateConnectionException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::DuplicateConnectionException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__write(__os);
+#else
+    ::peer::PeerException::__write(__os);
+#endif
+}
+
+void
+peer::DuplicateConnectionException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__read(__is, true);
+#else
+    ::peer::PeerException::__read(__is, true);
+#endif
+}
+
+void
+peer::DuplicateConnectionException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::DuplicateConnectionException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::DuplicateConnectionException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::DuplicateConnectionException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__DuplicateConnectionException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::DuplicateConnectionException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__DuplicateConnectionException__Ptr = new __F__peer__DuplicateConnectionException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::DuplicateConnectionException::ice_factory()
+{
+    return __F__peer__DuplicateConnectionException__Ptr;
+}
+
+class __F__peer__DuplicateConnectionException__Init
+{
+public:
+
+    __F__peer__DuplicateConnectionException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::DuplicateConnectionException", ::peer::DuplicateConnectionException::ice_factory());
+    }
+
+    ~__F__peer__DuplicateConnectionException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::DuplicateConnectionException");
+    }
+};
+
+static __F__peer__DuplicateConnectionException__Init __F__peer__DuplicateConnectionException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__DuplicateConnectionException__initializer() {} }
+#endif
+
+peer::RegistrationException::RegistrationException(const ::std::string& __ice_reason) :
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException(__ice_reason)
+#else
+    ::peer::PeerException(__ice_reason)
+#endif
+{
+}
+
+static const char* __peer__RegistrationException_name = "peer::RegistrationException";
+
+const ::std::string
+peer::RegistrationException::ice_name() const
+{
+    return __peer__RegistrationException_name;
+}
+
+::Ice::Exception*
+peer::RegistrationException::ice_clone() const
+{
+    return new RegistrationException(*this);
+}
+
+void
+peer::RegistrationException::ice_throw() const
+{
+    throw *this;
+}
+
+void
+peer::RegistrationException::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->write(::std::string("::peer::RegistrationException"), false);
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__write(__os);
+#else
+    ::peer::PeerException::__write(__os);
+#endif
+}
+
+void
+peer::RegistrationException::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->read(myId, false);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if (defined(_MSC_VER) && (_MSC_VER < 1300)) // VC++ 6 compiler bug
+    PeerException::__read(__is, true);
+#else
+    ::peer::PeerException::__read(__is, true);
+#endif
+}
+
+void
+peer::RegistrationException::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::RegistrationException was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::RegistrationException::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "exception peer::RegistrationException was not generated with stream support";
+    throw ex;
+}
+
+struct __F__peer__RegistrationException : public ::IceInternal::UserExceptionFactory
+{
+    virtual void
+    createAndThrow()
+    {
+	throw ::peer::RegistrationException();
+    }
+};
+
+static ::IceInternal::UserExceptionFactoryPtr __F__peer__RegistrationException__Ptr = new __F__peer__RegistrationException;
+
+const ::IceInternal::UserExceptionFactoryPtr&
+peer::RegistrationException::ice_factory()
+{
+    return __F__peer__RegistrationException__Ptr;
+}
+
+class __F__peer__RegistrationException__Init
+{
+public:
+
+    __F__peer__RegistrationException__Init()
+    {
+	::IceInternal::factoryTable->addExceptionFactory("::peer::RegistrationException", ::peer::RegistrationException::ice_factory());
+    }
+
+    ~__F__peer__RegistrationException__Init()
+    {
+	::IceInternal::factoryTable->removeExceptionFactory("::peer::RegistrationException");
+    }
+};
+
+static __F__peer__RegistrationException__Init __F__peer__RegistrationException__i;
+
+#ifdef __APPLE__
+extern "C" { void __F__peer__RegistrationException__initializer() {} }
+#endif
+
+void
+peer::__write(::IceInternal::BasicStream* __os, const ::peer::PeerIdentifier* begin, const ::peer::PeerIdentifier* end, ::peer::__U__PeerIdentifierSet)
+{
+    ::Ice::Int size = static_cast< ::Ice::Int>(end - begin);
+    __os->writeSize(size);
+    for(int i = 0; i < size; ++i)
+    {
+	begin[i].__write(__os);
+    }
+}
+
+void
+peer::__read(::IceInternal::BasicStream* __is, ::peer::PeerIdentifierSet& v, ::peer::__U__PeerIdentifierSet)
+{
+    ::Ice::Int sz;
+    __is->readSize(sz);
+    __is->startSeq(sz, 3);
+    v.resize(sz);
+    for(int i = 0; i < sz; ++i)
+    {
+	v[i].__read(__is);
+	__is->checkSeq();
+	__is->endElement();
+    }
+    __is->endSeq(sz);
+}
+
+void
+peer::AMI_UserConnectionEventHandler_forcedLogoutNotification::__invoke(const ::peer::UserConnectionEventHandlerPrx& __prx, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __peer__UserConnectionEventHandler__forcedLogoutNotification_name, ::Ice::Normal, __ctx);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+peer::AMI_UserConnectionEventHandler_forcedLogoutNotification::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+peer::AMI_PeerConnectionEventHandler_peerConnected::__invoke(const ::peer::PeerConnectionEventHandlerPrx& __prx, const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __peer__PeerConnectionEventHandler__peerConnected_name, ::Ice::Normal, __ctx);
+	__os->write(peerUserId);
+	::peer::__write(__os, accessLevel);
+	__os->write(peerProxy);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+peer::AMI_PeerConnectionEventHandler_peerConnected::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxy::__invoke(const ::peer::PeerConnectionEventHandlerPrx& __prx, const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __peer__PeerConnectionEventHandler__peerConnectedNoProxy_name, ::Ice::Normal, __ctx);
+	__os->write(peerUserId);
+	::peer::__write(__os, accessLevel);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxy::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+peer::AMI_PeerConnectionEventHandler_peerDisconnected::__invoke(const ::peer::PeerConnectionEventHandlerPrx& __prx, const ::std::string& peerUserId, const ::Ice::Context& __ctx)
+{
+    try
+    {
+	__prepare(__prx, __peer__PeerConnectionEventHandler__peerDisconnected_name, ::Ice::Normal, __ctx);
+	__os->write(peerUserId);
+	__os->endWriteEncaps();
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    __send();
+}
+
+void
+peer::AMI_PeerConnectionEventHandler_peerDisconnected::__response(bool __ok)
+{
+    try
+    {
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__finished(__ex);
+	return;
+    }
+    ice_response();
+}
+
+void
+IceProxy::peer::UserConnectionEventHandler::forcedLogoutNotification(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::UserConnectionEventHandler* __del = dynamic_cast< ::IceDelegate::peer::UserConnectionEventHandler*>(__delBase.get());
+	    __del->forcedLogoutNotification(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::UserConnectionEventHandler::forcedLogoutNotification_async(const ::peer::AMI_UserConnectionEventHandler_forcedLogoutNotificationPtr& __cb)
+{
+    forcedLogoutNotification_async(__cb, __defaultContext());
+}
+
+void
+IceProxy::peer::UserConnectionEventHandler::forcedLogoutNotification_async(const ::peer::AMI_UserConnectionEventHandler_forcedLogoutNotificationPtr& __cb, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, __ctx);
+}
+
+const ::std::string&
+IceProxy::peer::UserConnectionEventHandler::ice_staticId()
+{
+    return ::peer::UserConnectionEventHandler::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::peer::UserConnectionEventHandler::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::peer::UserConnectionEventHandler);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::peer::UserConnectionEventHandler::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::peer::UserConnectionEventHandler);
+}
+
+bool
+IceProxy::peer::operator==(const ::IceProxy::peer::UserConnectionEventHandler& l, const ::IceProxy::peer::UserConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator!=(const ::IceProxy::peer::UserConnectionEventHandler& l, const ::IceProxy::peer::UserConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<(const ::IceProxy::peer::UserConnectionEventHandler& l, const ::IceProxy::peer::UserConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<=(const ::IceProxy::peer::UserConnectionEventHandler& l, const ::IceProxy::peer::UserConnectionEventHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::peer::operator>(const ::IceProxy::peer::UserConnectionEventHandler& l, const ::IceProxy::peer::UserConnectionEventHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::peer::operator>=(const ::IceProxy::peer::UserConnectionEventHandler& l, const ::IceProxy::peer::UserConnectionEventHandler& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerConnected(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerConnectionEventHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerConnectionEventHandler*>(__delBase.get());
+	    __del->peerConnected(peerUserId, accessLevel, peerProxy, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerConnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedPtr& __cb, const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy)
+{
+    peerConnected_async(__cb, peerUserId, accessLevel, peerProxy, __defaultContext());
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerConnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedPtr& __cb, const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, peerUserId, accessLevel, peerProxy, __ctx);
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerConnectedNoProxy(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerConnectionEventHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerConnectionEventHandler*>(__delBase.get());
+	    __del->peerConnectedNoProxy(peerUserId, accessLevel, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerConnectedNoProxy_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxyPtr& __cb, const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel)
+{
+    peerConnectedNoProxy_async(__cb, peerUserId, accessLevel, __defaultContext());
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerConnectedNoProxy_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxyPtr& __cb, const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, peerUserId, accessLevel, __ctx);
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerDisconnected(const ::std::string& peerUserId, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerConnectionEventHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerConnectionEventHandler*>(__delBase.get());
+	    __del->peerDisconnected(peerUserId, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerDisconnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerDisconnectedPtr& __cb, const ::std::string& peerUserId)
+{
+    peerDisconnected_async(__cb, peerUserId, __defaultContext());
+}
+
+void
+IceProxy::peer::PeerConnectionEventHandler::peerDisconnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerDisconnectedPtr& __cb, const ::std::string& peerUserId, const ::Ice::Context& __ctx)
+{
+    __cb->__invoke(this, peerUserId, __ctx);
+}
+
+const ::std::string&
+IceProxy::peer::PeerConnectionEventHandler::ice_staticId()
+{
+    return ::peer::PeerConnectionEventHandler::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::peer::PeerConnectionEventHandler::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::peer::PeerConnectionEventHandler);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::peer::PeerConnectionEventHandler::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::peer::PeerConnectionEventHandler);
+}
+
+bool
+IceProxy::peer::operator==(const ::IceProxy::peer::PeerConnectionEventHandler& l, const ::IceProxy::peer::PeerConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator!=(const ::IceProxy::peer::PeerConnectionEventHandler& l, const ::IceProxy::peer::PeerConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<(const ::IceProxy::peer::PeerConnectionEventHandler& l, const ::IceProxy::peer::PeerConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<=(const ::IceProxy::peer::PeerConnectionEventHandler& l, const ::IceProxy::peer::PeerConnectionEventHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::peer::operator>(const ::IceProxy::peer::PeerConnectionEventHandler& l, const ::IceProxy::peer::PeerConnectionEventHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::peer::operator>=(const ::IceProxy::peer::PeerConnectionEventHandler& l, const ::IceProxy::peer::PeerConnectionEventHandler& r)
+{
+    return !(l < r);
+}
+
+const ::std::string&
+IceProxy::peer::ConnectionEventHandler::ice_staticId()
+{
+    return ::peer::ConnectionEventHandler::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::peer::ConnectionEventHandler::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::peer::ConnectionEventHandler);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::peer::ConnectionEventHandler::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::peer::ConnectionEventHandler);
+}
+
+bool
+IceProxy::peer::operator==(const ::IceProxy::peer::ConnectionEventHandler& l, const ::IceProxy::peer::ConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator!=(const ::IceProxy::peer::ConnectionEventHandler& l, const ::IceProxy::peer::ConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<(const ::IceProxy::peer::ConnectionEventHandler& l, const ::IceProxy::peer::ConnectionEventHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<=(const ::IceProxy::peer::ConnectionEventHandler& l, const ::IceProxy::peer::ConnectionEventHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::peer::operator>(const ::IceProxy::peer::ConnectionEventHandler& l, const ::IceProxy::peer::ConnectionEventHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::peer::operator>=(const ::IceProxy::peer::ConnectionEventHandler& l, const ::IceProxy::peer::ConnectionEventHandler& r)
+{
+    return !(l < r);
+}
+
+void
+IceProxy::peer::PeerRegistrationHandler::registerCallbacks(const ::Ice::ObjectPrx& selfCallbackProxy, const ::peer::ConnectionEventHandlerPrx& connectionEventHandlerProxy, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__PeerRegistrationHandler__registerCallbacks_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerRegistrationHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerRegistrationHandler*>(__delBase.get());
+	    __del->registerCallbacks(selfCallbackProxy, connectionEventHandlerProxy, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::PeerRegistrationHandler::registerProxy(const ::Ice::ObjectPrx& proxy, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__PeerRegistrationHandler__registerProxy_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerRegistrationHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerRegistrationHandler*>(__delBase.get());
+	    __del->registerProxy(proxy, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::PeerRegistrationHandler::registerProxies(const ::peer::ObjectProxyArray& proxies, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__PeerRegistrationHandler__registerProxies_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerRegistrationHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerRegistrationHandler*>(__delBase.get());
+	    __del->registerProxies(proxies, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+::Ice::ObjectPrx
+IceProxy::peer::PeerRegistrationHandler::getPeerProxy(const ::std::string& peerUserId, const ::Ice::Identity& privateProxyIdentity, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__PeerRegistrationHandler__getPeerProxy_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerRegistrationHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerRegistrationHandler*>(__delBase.get());
+	    return __del->getPeerProxy(peerUserId, privateProxyIdentity, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+::peer::IdentityToProxyMap
+IceProxy::peer::PeerRegistrationHandler::getPeerProxies(const ::std::string& peerUserId, const ::peer::IdentityArray& privateProxyIdentities, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__PeerRegistrationHandler__getPeerProxies_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::PeerRegistrationHandler* __del = dynamic_cast< ::IceDelegate::peer::PeerRegistrationHandler*>(__delBase.get());
+	    return __del->getPeerProxies(peerUserId, privateProxyIdentities, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+const ::std::string&
+IceProxy::peer::PeerRegistrationHandler::ice_staticId()
+{
+    return ::peer::PeerRegistrationHandler::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::peer::PeerRegistrationHandler::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::peer::PeerRegistrationHandler);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::peer::PeerRegistrationHandler::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::peer::PeerRegistrationHandler);
+}
+
+bool
+IceProxy::peer::operator==(const ::IceProxy::peer::PeerRegistrationHandler& l, const ::IceProxy::peer::PeerRegistrationHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator!=(const ::IceProxy::peer::PeerRegistrationHandler& l, const ::IceProxy::peer::PeerRegistrationHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<(const ::IceProxy::peer::PeerRegistrationHandler& l, const ::IceProxy::peer::PeerRegistrationHandler& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<=(const ::IceProxy::peer::PeerRegistrationHandler& l, const ::IceProxy::peer::PeerRegistrationHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::peer::operator>(const ::IceProxy::peer::PeerRegistrationHandler& l, const ::IceProxy::peer::PeerRegistrationHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::peer::operator>=(const ::IceProxy::peer::PeerRegistrationHandler& l, const ::IceProxy::peer::PeerRegistrationHandler& r)
+{
+    return !(l < r);
+}
+
+::peer::PeerIdentifierSet
+IceProxy::peer::UserSession::getMyAvailablePeers(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__UserSession__getMyAvailablePeers_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::UserSession* __del = dynamic_cast< ::IceDelegate::peer::UserSession*>(__delBase.get());
+	    return __del->getMyAvailablePeers(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+::Ice::ObjectPrx
+IceProxy::peer::UserSession::connectToPeer(const ::std::string& peerUserId, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__UserSession__connectToPeer_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::UserSession* __del = dynamic_cast< ::IceDelegate::peer::UserSession*>(__delBase.get());
+	    return __del->connectToPeer(peerUserId, __ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+::peer::PeerIdentifierSet
+IceProxy::peer::UserSession::getConnectedPeers(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    __checkTwowayOnly(__peer__UserSession__getConnectedPeers_name);
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::UserSession* __del = dynamic_cast< ::IceDelegate::peer::UserSession*>(__delBase.get());
+	    return __del->getConnectedPeers(__ctx);
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::UserSession::disconnectFromPeer(const ::std::string& peerUserId, const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::UserSession* __del = dynamic_cast< ::IceDelegate::peer::UserSession*>(__delBase.get());
+	    __del->disconnectFromPeer(peerUserId, __ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+void
+IceProxy::peer::UserSession::disconnectFromPeers(const ::Ice::Context& __ctx)
+{
+    int __cnt = 0;
+    while(true)
+    {
+	try
+	{
+	    ::IceInternal::Handle< ::IceDelegate::Ice::Object> __delBase = __getDelegate();
+	    ::IceDelegate::peer::UserSession* __del = dynamic_cast< ::IceDelegate::peer::UserSession*>(__delBase.get());
+	    __del->disconnectFromPeers(__ctx);
+	    return;
+	}
+	catch(const ::IceInternal::LocalExceptionWrapper& __ex)
+	{
+	    __handleExceptionWrapper(__ex);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    __handleException(__ex, __cnt);
+	}
+    }
+}
+
+const ::std::string&
+IceProxy::peer::UserSession::ice_staticId()
+{
+    return ::peer::UserSession::ice_staticId();
+}
+
+::IceInternal::Handle< ::IceDelegateM::Ice::Object>
+IceProxy::peer::UserSession::__createDelegateM()
+{
+    return ::IceInternal::Handle< ::IceDelegateM::Ice::Object>(new ::IceDelegateM::peer::UserSession);
+}
+
+::IceInternal::Handle< ::IceDelegateD::Ice::Object>
+IceProxy::peer::UserSession::__createDelegateD()
+{
+    return ::IceInternal::Handle< ::IceDelegateD::Ice::Object>(new ::IceDelegateD::peer::UserSession);
+}
+
+bool
+IceProxy::peer::operator==(const ::IceProxy::peer::UserSession& l, const ::IceProxy::peer::UserSession& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) == static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator!=(const ::IceProxy::peer::UserSession& l, const ::IceProxy::peer::UserSession& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) != static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<(const ::IceProxy::peer::UserSession& l, const ::IceProxy::peer::UserSession& r)
+{
+    return static_cast<const ::IceProxy::Ice::Object&>(l) < static_cast<const ::IceProxy::Ice::Object&>(r);
+}
+
+bool
+IceProxy::peer::operator<=(const ::IceProxy::peer::UserSession& l, const ::IceProxy::peer::UserSession& r)
+{
+    return l < r || l == r;
+}
+
+bool
+IceProxy::peer::operator>(const ::IceProxy::peer::UserSession& l, const ::IceProxy::peer::UserSession& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+IceProxy::peer::operator>=(const ::IceProxy::peer::UserSession& l, const ::IceProxy::peer::UserSession& r)
+{
+    return !(l < r);
+}
+
+void
+IceDelegateM::peer::UserConnectionEventHandler::forcedLogoutNotification(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__UserConnectionEventHandler__forcedLogoutNotification_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::PeerConnectionEventHandler::peerConnected(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerConnectionEventHandler__peerConnected_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+	::peer::__write(__os, accessLevel);
+	__os->write(peerProxy);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::PeerConnectionEventHandler::peerConnectedNoProxy(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerConnectionEventHandler__peerConnectedNoProxy_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+	::peer::__write(__os, accessLevel);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::PeerConnectionEventHandler::peerDisconnected(const ::std::string& peerUserId, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerConnectionEventHandler__peerDisconnected_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::PeerRegistrationHandler::registerCallbacks(const ::Ice::ObjectPrx& selfCallbackProxy, const ::peer::ConnectionEventHandlerPrx& connectionEventHandlerProxy, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerRegistrationHandler__registerCallbacks_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(selfCallbackProxy);
+	::peer::__write(__os, connectionEventHandlerProxy);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::RegistrationException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::PeerRegistrationHandler::registerProxy(const ::Ice::ObjectPrx& proxy, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerRegistrationHandler__registerProxy_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(proxy);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::RegistrationException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::PeerRegistrationHandler::registerProxies(const ::peer::ObjectProxyArray& proxies, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerRegistrationHandler__registerProxies_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	if(proxies.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::peer::__write(__os, &proxies[0], &proxies[0] + proxies.size(), ::peer::__U__ObjectProxyArray());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::RegistrationException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::Ice::ObjectPrx
+IceDelegateM::peer::PeerRegistrationHandler::getPeerProxy(const ::std::string& peerUserId, const ::Ice::Identity& privateProxyIdentity, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerRegistrationHandler__getPeerProxy_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+	privateProxyIdentity.__write(__os);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::InvalidIdentityException&)
+	    {
+		throw;
+	    }
+	    catch(const ::peer::PeerAccessException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::Ice::ObjectPrx __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::peer::IdentityToProxyMap
+IceDelegateM::peer::PeerRegistrationHandler::getPeerProxies(const ::std::string& peerUserId, const ::peer::IdentityArray& privateProxyIdentities, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__PeerRegistrationHandler__getPeerProxies_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+	if(privateProxyIdentities.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::peer::__write(__os, &privateProxyIdentities[0], &privateProxyIdentities[0] + privateProxyIdentities.size(), ::peer::__U__IdentityArray());
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::InvalidIdentityException&)
+	    {
+		throw;
+	    }
+	    catch(const ::peer::PeerAccessException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::peer::IdentityToProxyMap __ret;
+	::peer::__read(__is, __ret, ::peer::__U__IdentityToProxyMap());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::peer::PeerIdentifierSet
+IceDelegateM::peer::UserSession::getMyAvailablePeers(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__UserSession__getMyAvailablePeers_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::PeerException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::peer::PeerIdentifierSet __ret;
+	::peer::__read(__is, __ret, ::peer::__U__PeerIdentifierSet());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::Ice::ObjectPrx
+IceDelegateM::peer::UserSession::connectToPeer(const ::std::string& peerUserId, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__UserSession__connectToPeer_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::DuplicateConnectionException&)
+	    {
+		throw;
+	    }
+	    catch(const ::peer::PeerAccessException&)
+	    {
+		throw;
+	    }
+	    catch(const ::peer::PeerConnectionFailedException&)
+	    {
+		throw;
+	    }
+	    catch(const ::peer::PeerUnavailableException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::Ice::ObjectPrx __ret;
+	__is->read(__ret);
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+::peer::PeerIdentifierSet
+IceDelegateM::peer::UserSession::getConnectedPeers(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__UserSession__getConnectedPeers_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::peer::PeerException&)
+	    {
+		throw;
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+	::peer::PeerIdentifierSet __ret;
+	::peer::__read(__is, __ret, ::peer::__U__PeerIdentifierSet());
+	return __ret;
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::UserSession::disconnectFromPeer(const ::std::string& peerUserId, const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__UserSession__disconnectFromPeer_name, ::Ice::Normal, __context, __compress);
+    try
+    {
+	::IceInternal::BasicStream* __os = __og.os();
+	__os->write(peerUserId);
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	__og.abort(__ex);
+    }
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateM::peer::UserSession::disconnectFromPeers(const ::Ice::Context& __context)
+{
+    ::IceInternal::Outgoing __og(__connection.get(), __reference.get(), __peer__UserSession__disconnectFromPeers_name, ::Ice::Normal, __context, __compress);
+    bool __ok = __og.invoke();
+    try
+    {
+	::IceInternal::BasicStream* __is = __og.is();
+	if(!__ok)
+	{
+	    try
+	    {
+		__is->throwException();
+	    }
+	    catch(const ::Ice::UserException& __ex)
+	    {
+		throw ::Ice::UnknownUserException(__FILE__, __LINE__, __ex.ice_name());
+	    }
+	}
+    }
+    catch(const ::Ice::LocalException& __ex)
+    {
+	throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+    }
+}
+
+void
+IceDelegateD::peer::UserConnectionEventHandler::forcedLogoutNotification(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__UserConnectionEventHandler__forcedLogoutNotification_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::UserConnectionEventHandler* __servant = dynamic_cast< ::peer::UserConnectionEventHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->forcedLogoutNotification(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::PeerConnectionEventHandler::peerConnected(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerConnectionEventHandler__peerConnected_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerConnectionEventHandler* __servant = dynamic_cast< ::peer::PeerConnectionEventHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->peerConnected(peerUserId, accessLevel, peerProxy, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::PeerConnectionEventHandler::peerConnectedNoProxy(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerConnectionEventHandler__peerConnectedNoProxy_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerConnectionEventHandler* __servant = dynamic_cast< ::peer::PeerConnectionEventHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->peerConnectedNoProxy(peerUserId, accessLevel, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::PeerConnectionEventHandler::peerDisconnected(const ::std::string& peerUserId, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerConnectionEventHandler__peerDisconnected_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerConnectionEventHandler* __servant = dynamic_cast< ::peer::PeerConnectionEventHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->peerDisconnected(peerUserId, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::PeerRegistrationHandler::registerCallbacks(const ::Ice::ObjectPrx& selfCallbackProxy, const ::peer::ConnectionEventHandlerPrx& connectionEventHandlerProxy, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerRegistrationHandler__registerCallbacks_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerRegistrationHandler* __servant = dynamic_cast< ::peer::PeerRegistrationHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->registerCallbacks(selfCallbackProxy, connectionEventHandlerProxy, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::PeerRegistrationHandler::registerProxy(const ::Ice::ObjectPrx& proxy, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerRegistrationHandler__registerProxy_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerRegistrationHandler* __servant = dynamic_cast< ::peer::PeerRegistrationHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->registerProxy(proxy, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::PeerRegistrationHandler::registerProxies(const ::peer::ObjectProxyArray& proxies, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerRegistrationHandler__registerProxies_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerRegistrationHandler* __servant = dynamic_cast< ::peer::PeerRegistrationHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->registerProxies(proxies, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::ObjectPrx
+IceDelegateD::peer::PeerRegistrationHandler::getPeerProxy(const ::std::string& peerUserId, const ::Ice::Identity& privateProxyIdentity, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerRegistrationHandler__getPeerProxy_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerRegistrationHandler* __servant = dynamic_cast< ::peer::PeerRegistrationHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getPeerProxy(peerUserId, privateProxyIdentity, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::peer::IdentityToProxyMap
+IceDelegateD::peer::PeerRegistrationHandler::getPeerProxies(const ::std::string& peerUserId, const ::peer::IdentityArray& privateProxyIdentities, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__PeerRegistrationHandler__getPeerProxies_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::PeerRegistrationHandler* __servant = dynamic_cast< ::peer::PeerRegistrationHandler*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getPeerProxies(peerUserId, privateProxyIdentities, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::peer::PeerIdentifierSet
+IceDelegateD::peer::UserSession::getMyAvailablePeers(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__UserSession__getMyAvailablePeers_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::UserSession* __servant = dynamic_cast< ::peer::UserSession*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getMyAvailablePeers(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::ObjectPrx
+IceDelegateD::peer::UserSession::connectToPeer(const ::std::string& peerUserId, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__UserSession__connectToPeer_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::UserSession* __servant = dynamic_cast< ::peer::UserSession*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->connectToPeer(peerUserId, __current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::peer::PeerIdentifierSet
+IceDelegateD::peer::UserSession::getConnectedPeers(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__UserSession__getConnectedPeers_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::UserSession* __servant = dynamic_cast< ::peer::UserSession*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    return __servant->getConnectedPeers(__current);
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::UserSession::disconnectFromPeer(const ::std::string& peerUserId, const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__UserSession__disconnectFromPeer_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::UserSession* __servant = dynamic_cast< ::peer::UserSession*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->disconnectFromPeer(peerUserId, __current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+void
+IceDelegateD::peer::UserSession::disconnectFromPeers(const ::Ice::Context& __context)
+{
+    ::Ice::Current __current;
+    __initCurrent(__current, __peer__UserSession__disconnectFromPeers_name, ::Ice::Normal, __context);
+    while(true)
+    {
+	::IceInternal::Direct __direct(__current);
+	::peer::UserSession* __servant = dynamic_cast< ::peer::UserSession*>(__direct.servant().get());
+	if(!__servant)
+	{
+	    ::Ice::OperationNotExistException __opEx(__FILE__, __LINE__);
+	    __opEx.id = __current.id;
+	    __opEx.facet = __current.facet;
+	    __opEx.operation = __current.operation;
+	    throw __opEx;
+	}
+	try
+	{
+	    __servant->disconnectFromPeers(__current);
+	    return;
+	}
+	catch(const ::Ice::LocalException& __ex)
+	{
+	    throw ::IceInternal::LocalExceptionWrapper(__ex, false);
+	}
+    }
+}
+
+::Ice::ObjectPtr
+peer::UserConnectionEventHandler::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __peer__UserConnectionEventHandler_ids[2] =
+{
+    "::Ice::Object",
+    "::peer::UserConnectionEventHandler"
+};
+
+bool
+peer::UserConnectionEventHandler::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__peer__UserConnectionEventHandler_ids, __peer__UserConnectionEventHandler_ids + 2, _s);
+}
+
+::std::vector< ::std::string>
+peer::UserConnectionEventHandler::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__peer__UserConnectionEventHandler_ids[0], &__peer__UserConnectionEventHandler_ids[2]);
+}
+
+const ::std::string&
+peer::UserConnectionEventHandler::ice_id(const ::Ice::Current&) const
+{
+    return __peer__UserConnectionEventHandler_ids[1];
+}
+
+const ::std::string&
+peer::UserConnectionEventHandler::ice_staticId()
+{
+    return __peer__UserConnectionEventHandler_ids[1];
+}
+
+::IceInternal::DispatchStatus
+peer::UserConnectionEventHandler::___forcedLogoutNotification(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    forcedLogoutNotification(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __peer__UserConnectionEventHandler_all[] =
+{
+    "forcedLogoutNotification",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping"
+};
+
+::IceInternal::DispatchStatus
+peer::UserConnectionEventHandler::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__peer__UserConnectionEventHandler_all, __peer__UserConnectionEventHandler_all + 5, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __peer__UserConnectionEventHandler_all)
+    {
+	case 0:
+	{
+	    return ___forcedLogoutNotification(in, current);
+	}
+	case 1:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 2:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_ping(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+peer::UserConnectionEventHandler::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+peer::UserConnectionEventHandler::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+peer::UserConnectionEventHandler::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::UserConnectionEventHandler was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::UserConnectionEventHandler::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::UserConnectionEventHandler was not generated with stream support";
+    throw ex;
+}
+
+void 
+peer::__patch__UserConnectionEventHandlerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::peer::UserConnectionEventHandlerPtr* p = static_cast< ::peer::UserConnectionEventHandlerPtr*>(__addr);
+    assert(p);
+    *p = ::peer::UserConnectionEventHandlerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::peer::UserConnectionEventHandler::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+peer::operator==(const ::peer::UserConnectionEventHandler& l, const ::peer::UserConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator!=(const ::peer::UserConnectionEventHandler& l, const ::peer::UserConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<(const ::peer::UserConnectionEventHandler& l, const ::peer::UserConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<=(const ::peer::UserConnectionEventHandler& l, const ::peer::UserConnectionEventHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+peer::operator>(const ::peer::UserConnectionEventHandler& l, const ::peer::UserConnectionEventHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+peer::operator>=(const ::peer::UserConnectionEventHandler& l, const ::peer::UserConnectionEventHandler& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+peer::PeerConnectionEventHandler::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __peer__PeerConnectionEventHandler_ids[2] =
+{
+    "::Ice::Object",
+    "::peer::PeerConnectionEventHandler"
+};
+
+bool
+peer::PeerConnectionEventHandler::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__peer__PeerConnectionEventHandler_ids, __peer__PeerConnectionEventHandler_ids + 2, _s);
+}
+
+::std::vector< ::std::string>
+peer::PeerConnectionEventHandler::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__peer__PeerConnectionEventHandler_ids[0], &__peer__PeerConnectionEventHandler_ids[2]);
+}
+
+const ::std::string&
+peer::PeerConnectionEventHandler::ice_id(const ::Ice::Current&) const
+{
+    return __peer__PeerConnectionEventHandler_ids[1];
+}
+
+const ::std::string&
+peer::PeerConnectionEventHandler::ice_staticId()
+{
+    return __peer__PeerConnectionEventHandler_ids[1];
+}
+
+::IceInternal::DispatchStatus
+peer::PeerConnectionEventHandler::___peerConnected(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::std::string peerUserId;
+    ::peer::PeerAccessLevel accessLevel;
+    ::Ice::ObjectPrx peerProxy;
+    __is->read(peerUserId);
+    ::peer::__read(__is, accessLevel);
+    __is->read(peerProxy);
+    peerConnected(peerUserId, accessLevel, peerProxy, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::PeerConnectionEventHandler::___peerConnectedNoProxy(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::std::string peerUserId;
+    ::peer::PeerAccessLevel accessLevel;
+    __is->read(peerUserId);
+    ::peer::__read(__is, accessLevel);
+    peerConnectedNoProxy(peerUserId, accessLevel, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::PeerConnectionEventHandler::___peerDisconnected(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::std::string peerUserId;
+    __is->read(peerUserId);
+    peerDisconnected(peerUserId, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __peer__PeerConnectionEventHandler_all[] =
+{
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "peerConnected",
+    "peerConnectedNoProxy",
+    "peerDisconnected"
+};
+
+::IceInternal::DispatchStatus
+peer::PeerConnectionEventHandler::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__peer__PeerConnectionEventHandler_all, __peer__PeerConnectionEventHandler_all + 7, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __peer__PeerConnectionEventHandler_all)
+    {
+	case 0:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 1:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 2:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 4:
+	{
+	    return ___peerConnected(in, current);
+	}
+	case 5:
+	{
+	    return ___peerConnectedNoProxy(in, current);
+	}
+	case 6:
+	{
+	    return ___peerDisconnected(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+peer::PeerConnectionEventHandler::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+peer::PeerConnectionEventHandler::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+peer::PeerConnectionEventHandler::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::PeerConnectionEventHandler was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::PeerConnectionEventHandler::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::PeerConnectionEventHandler was not generated with stream support";
+    throw ex;
+}
+
+void 
+peer::__patch__PeerConnectionEventHandlerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::peer::PeerConnectionEventHandlerPtr* p = static_cast< ::peer::PeerConnectionEventHandlerPtr*>(__addr);
+    assert(p);
+    *p = ::peer::PeerConnectionEventHandlerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::peer::PeerConnectionEventHandler::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+peer::operator==(const ::peer::PeerConnectionEventHandler& l, const ::peer::PeerConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator!=(const ::peer::PeerConnectionEventHandler& l, const ::peer::PeerConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<(const ::peer::PeerConnectionEventHandler& l, const ::peer::PeerConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<=(const ::peer::PeerConnectionEventHandler& l, const ::peer::PeerConnectionEventHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+peer::operator>(const ::peer::PeerConnectionEventHandler& l, const ::peer::PeerConnectionEventHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+peer::operator>=(const ::peer::PeerConnectionEventHandler& l, const ::peer::PeerConnectionEventHandler& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+peer::ConnectionEventHandler::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __peer__ConnectionEventHandler_ids[4] =
+{
+    "::Ice::Object",
+    "::peer::ConnectionEventHandler",
+    "::peer::PeerConnectionEventHandler",
+    "::peer::UserConnectionEventHandler"
+};
+
+bool
+peer::ConnectionEventHandler::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__peer__ConnectionEventHandler_ids, __peer__ConnectionEventHandler_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+peer::ConnectionEventHandler::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__peer__ConnectionEventHandler_ids[0], &__peer__ConnectionEventHandler_ids[4]);
+}
+
+const ::std::string&
+peer::ConnectionEventHandler::ice_id(const ::Ice::Current&) const
+{
+    return __peer__ConnectionEventHandler_ids[1];
+}
+
+const ::std::string&
+peer::ConnectionEventHandler::ice_staticId()
+{
+    return __peer__ConnectionEventHandler_ids[1];
+}
+
+static ::std::string __peer__ConnectionEventHandler_all[] =
+{
+    "forcedLogoutNotification",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "peerConnected",
+    "peerConnectedNoProxy",
+    "peerDisconnected"
+};
+
+::IceInternal::DispatchStatus
+peer::ConnectionEventHandler::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__peer__ConnectionEventHandler_all, __peer__ConnectionEventHandler_all + 8, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __peer__ConnectionEventHandler_all)
+    {
+	case 0:
+	{
+	    return ___forcedLogoutNotification(in, current);
+	}
+	case 1:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 2:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 5:
+	{
+	    return ___peerConnected(in, current);
+	}
+	case 6:
+	{
+	    return ___peerConnectedNoProxy(in, current);
+	}
+	case 7:
+	{
+	    return ___peerDisconnected(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+peer::ConnectionEventHandler::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+peer::ConnectionEventHandler::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+peer::ConnectionEventHandler::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::ConnectionEventHandler was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::ConnectionEventHandler::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::ConnectionEventHandler was not generated with stream support";
+    throw ex;
+}
+
+void 
+peer::__patch__ConnectionEventHandlerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::peer::ConnectionEventHandlerPtr* p = static_cast< ::peer::ConnectionEventHandlerPtr*>(__addr);
+    assert(p);
+    *p = ::peer::ConnectionEventHandlerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::peer::ConnectionEventHandler::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+peer::operator==(const ::peer::ConnectionEventHandler& l, const ::peer::ConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator!=(const ::peer::ConnectionEventHandler& l, const ::peer::ConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<(const ::peer::ConnectionEventHandler& l, const ::peer::ConnectionEventHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<=(const ::peer::ConnectionEventHandler& l, const ::peer::ConnectionEventHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+peer::operator>(const ::peer::ConnectionEventHandler& l, const ::peer::ConnectionEventHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+peer::operator>=(const ::peer::ConnectionEventHandler& l, const ::peer::ConnectionEventHandler& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+peer::PeerRegistrationHandler::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __peer__PeerRegistrationHandler_ids[2] =
+{
+    "::Ice::Object",
+    "::peer::PeerRegistrationHandler"
+};
+
+bool
+peer::PeerRegistrationHandler::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__peer__PeerRegistrationHandler_ids, __peer__PeerRegistrationHandler_ids + 2, _s);
+}
+
+::std::vector< ::std::string>
+peer::PeerRegistrationHandler::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__peer__PeerRegistrationHandler_ids[0], &__peer__PeerRegistrationHandler_ids[2]);
+}
+
+const ::std::string&
+peer::PeerRegistrationHandler::ice_id(const ::Ice::Current&) const
+{
+    return __peer__PeerRegistrationHandler_ids[1];
+}
+
+const ::std::string&
+peer::PeerRegistrationHandler::ice_staticId()
+{
+    return __peer__PeerRegistrationHandler_ids[1];
+}
+
+::IceInternal::DispatchStatus
+peer::PeerRegistrationHandler::___registerCallbacks(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::Ice::ObjectPrx selfCallbackProxy;
+    ::peer::ConnectionEventHandlerPrx connectionEventHandlerProxy;
+    __is->read(selfCallbackProxy);
+    ::peer::__read(__is, connectionEventHandlerProxy);
+    try
+    {
+	registerCallbacks(selfCallbackProxy, connectionEventHandlerProxy, __current);
+    }
+    catch(const ::peer::RegistrationException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::PeerRegistrationHandler::___registerProxy(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::Ice::ObjectPrx proxy;
+    __is->read(proxy);
+    try
+    {
+	registerProxy(proxy, __current);
+    }
+    catch(const ::peer::RegistrationException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::PeerRegistrationHandler::___registerProxies(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::peer::ObjectProxyArray proxies;
+    ::peer::__read(__is, proxies, ::peer::__U__ObjectProxyArray());
+    try
+    {
+	registerProxies(proxies, __current);
+    }
+    catch(const ::peer::RegistrationException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::PeerRegistrationHandler::___getPeerProxy(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string peerUserId;
+    ::Ice::Identity privateProxyIdentity;
+    __is->read(peerUserId);
+    privateProxyIdentity.__read(__is);
+    try
+    {
+	::Ice::ObjectPrx __ret = getPeerProxy(peerUserId, privateProxyIdentity, __current);
+	__os->write(__ret);
+    }
+    catch(const ::peer::InvalidIdentityException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    catch(const ::peer::PeerAccessException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::PeerRegistrationHandler::___getPeerProxies(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string peerUserId;
+    ::peer::IdentityArray privateProxyIdentities;
+    __is->read(peerUserId);
+    ::peer::__read(__is, privateProxyIdentities, ::peer::__U__IdentityArray());
+    try
+    {
+	::peer::IdentityToProxyMap __ret = getPeerProxies(peerUserId, privateProxyIdentities, __current);
+	::peer::__write(__os, __ret, ::peer::__U__IdentityToProxyMap());
+    }
+    catch(const ::peer::InvalidIdentityException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    catch(const ::peer::PeerAccessException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __peer__PeerRegistrationHandler_all[] =
+{
+    "getPeerProxies",
+    "getPeerProxy",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "registerCallbacks",
+    "registerProxies",
+    "registerProxy"
+};
+
+::IceInternal::DispatchStatus
+peer::PeerRegistrationHandler::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__peer__PeerRegistrationHandler_all, __peer__PeerRegistrationHandler_all + 9, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __peer__PeerRegistrationHandler_all)
+    {
+	case 0:
+	{
+	    return ___getPeerProxies(in, current);
+	}
+	case 1:
+	{
+	    return ___getPeerProxy(in, current);
+	}
+	case 2:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 3:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 4:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 5:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 6:
+	{
+	    return ___registerCallbacks(in, current);
+	}
+	case 7:
+	{
+	    return ___registerProxies(in, current);
+	}
+	case 8:
+	{
+	    return ___registerProxy(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+peer::PeerRegistrationHandler::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+peer::PeerRegistrationHandler::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+peer::PeerRegistrationHandler::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::PeerRegistrationHandler was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::PeerRegistrationHandler::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::PeerRegistrationHandler was not generated with stream support";
+    throw ex;
+}
+
+void 
+peer::__patch__PeerRegistrationHandlerPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::peer::PeerRegistrationHandlerPtr* p = static_cast< ::peer::PeerRegistrationHandlerPtr*>(__addr);
+    assert(p);
+    *p = ::peer::PeerRegistrationHandlerPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::peer::PeerRegistrationHandler::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+peer::operator==(const ::peer::PeerRegistrationHandler& l, const ::peer::PeerRegistrationHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator!=(const ::peer::PeerRegistrationHandler& l, const ::peer::PeerRegistrationHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<(const ::peer::PeerRegistrationHandler& l, const ::peer::PeerRegistrationHandler& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<=(const ::peer::PeerRegistrationHandler& l, const ::peer::PeerRegistrationHandler& r)
+{
+    return l < r || l == r;
+}
+
+bool
+peer::operator>(const ::peer::PeerRegistrationHandler& l, const ::peer::PeerRegistrationHandler& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+peer::operator>=(const ::peer::PeerRegistrationHandler& l, const ::peer::PeerRegistrationHandler& r)
+{
+    return !(l < r);
+}
+
+::Ice::ObjectPtr
+peer::UserSession::ice_clone() const
+{
+    throw ::Ice::CloneNotImplementedException(__FILE__, __LINE__);
+    return 0; // to avoid a warning with some compilers
+}
+
+static const ::std::string __peer__UserSession_ids[4] =
+{
+    "::Glacier2::Session",
+    "::Ice::Object",
+    "::peer::PeerRegistrationHandler",
+    "::peer::UserSession"
+};
+
+bool
+peer::UserSession::ice_isA(const ::std::string& _s, const ::Ice::Current&) const
+{
+    return ::std::binary_search(__peer__UserSession_ids, __peer__UserSession_ids + 4, _s);
+}
+
+::std::vector< ::std::string>
+peer::UserSession::ice_ids(const ::Ice::Current&) const
+{
+    return ::std::vector< ::std::string>(&__peer__UserSession_ids[0], &__peer__UserSession_ids[4]);
+}
+
+const ::std::string&
+peer::UserSession::ice_id(const ::Ice::Current&) const
+{
+    return __peer__UserSession_ids[3];
+}
+
+const ::std::string&
+peer::UserSession::ice_staticId()
+{
+    return __peer__UserSession_ids[3];
+}
+
+::IceInternal::DispatchStatus
+peer::UserSession::___getMyAvailablePeers(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    try
+    {
+	::peer::PeerIdentifierSet __ret = getMyAvailablePeers(__current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::peer::__write(__os, &__ret[0], &__ret[0] + __ret.size(), ::peer::__U__PeerIdentifierSet());
+	}
+    }
+    catch(const ::peer::PeerException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::UserSession::___connectToPeer(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::IceInternal::BasicStream* __os = __inS.os();
+    ::std::string peerUserId;
+    __is->read(peerUserId);
+    try
+    {
+	::Ice::ObjectPrx __ret = connectToPeer(peerUserId, __current);
+	__os->write(__ret);
+    }
+    catch(const ::peer::DuplicateConnectionException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    catch(const ::peer::PeerAccessException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    catch(const ::peer::PeerConnectionFailedException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    catch(const ::peer::PeerUnavailableException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::UserSession::___getConnectedPeers(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __os = __inS.os();
+    try
+    {
+	::peer::PeerIdentifierSet __ret = getConnectedPeers(__current);
+	if(__ret.size() == 0)
+	{
+	    __os->writeSize(0);
+	}
+	else
+	{
+	    ::peer::__write(__os, &__ret[0], &__ret[0] + __ret.size(), ::peer::__U__PeerIdentifierSet());
+	}
+    }
+    catch(const ::peer::PeerException& __ex)
+    {
+	__os->write(__ex);
+	return ::IceInternal::DispatchUserException;
+    }
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::UserSession::___disconnectFromPeer(::IceInternal::Incoming&__inS, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    ::IceInternal::BasicStream* __is = __inS.is();
+    ::std::string peerUserId;
+    __is->read(peerUserId);
+    disconnectFromPeer(peerUserId, __current);
+    return ::IceInternal::DispatchOK;
+}
+
+::IceInternal::DispatchStatus
+peer::UserSession::___disconnectFromPeers(::IceInternal::Incoming&, const ::Ice::Current& __current)
+{
+    __checkMode(::Ice::Normal, __current.mode);
+    disconnectFromPeers(__current);
+    return ::IceInternal::DispatchOK;
+}
+
+static ::std::string __peer__UserSession_all[] =
+{
+    "connectToPeer",
+    "destroy",
+    "disconnectFromPeer",
+    "disconnectFromPeers",
+    "getConnectedPeers",
+    "getMyAvailablePeers",
+    "getPeerProxies",
+    "getPeerProxy",
+    "ice_id",
+    "ice_ids",
+    "ice_isA",
+    "ice_ping",
+    "registerCallbacks",
+    "registerProxies",
+    "registerProxy"
+};
+
+::IceInternal::DispatchStatus
+peer::UserSession::__dispatch(::IceInternal::Incoming& in, const ::Ice::Current& current)
+{
+    ::std::pair< ::std::string*, ::std::string*> r = ::std::equal_range(__peer__UserSession_all, __peer__UserSession_all + 15, current.operation);
+    if(r.first == r.second)
+    {
+	return ::IceInternal::DispatchOperationNotExist;
+    }
+
+    switch(r.first - __peer__UserSession_all)
+    {
+	case 0:
+	{
+	    return ___connectToPeer(in, current);
+	}
+	case 1:
+	{
+	    return ___destroy(in, current);
+	}
+	case 2:
+	{
+	    return ___disconnectFromPeer(in, current);
+	}
+	case 3:
+	{
+	    return ___disconnectFromPeers(in, current);
+	}
+	case 4:
+	{
+	    return ___getConnectedPeers(in, current);
+	}
+	case 5:
+	{
+	    return ___getMyAvailablePeers(in, current);
+	}
+	case 6:
+	{
+	    return ___getPeerProxies(in, current);
+	}
+	case 7:
+	{
+	    return ___getPeerProxy(in, current);
+	}
+	case 8:
+	{
+	    return ___ice_id(in, current);
+	}
+	case 9:
+	{
+	    return ___ice_ids(in, current);
+	}
+	case 10:
+	{
+	    return ___ice_isA(in, current);
+	}
+	case 11:
+	{
+	    return ___ice_ping(in, current);
+	}
+	case 12:
+	{
+	    return ___registerCallbacks(in, current);
+	}
+	case 13:
+	{
+	    return ___registerProxies(in, current);
+	}
+	case 14:
+	{
+	    return ___registerProxy(in, current);
+	}
+    }
+
+    assert(false);
+    return ::IceInternal::DispatchOperationNotExist;
+}
+
+void
+peer::UserSession::__write(::IceInternal::BasicStream* __os) const
+{
+    __os->writeTypeId(ice_staticId());
+    __os->startWriteSlice();
+    __os->endWriteSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__write(__os);
+#else
+    ::Ice::Object::__write(__os);
+#endif
+}
+
+void
+peer::UserSession::__read(::IceInternal::BasicStream* __is, bool __rid)
+{
+    if(__rid)
+    {
+	::std::string myId;
+	__is->readTypeId(myId);
+    }
+    __is->startReadSlice();
+    __is->endReadSlice();
+#if defined(_MSC_VER) && (_MSC_VER < 1300) // VC++ 6 compiler bug
+    Object::__read(__is, true);
+#else
+    ::Ice::Object::__read(__is, true);
+#endif
+}
+
+void
+peer::UserSession::__write(const ::Ice::OutputStreamPtr&) const
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::UserSession was not generated with stream support";
+    throw ex;
+}
+
+void
+peer::UserSession::__read(const ::Ice::InputStreamPtr&, bool)
+{
+    Ice::MarshalException ex(__FILE__, __LINE__);
+    ex.reason = "type peer::UserSession was not generated with stream support";
+    throw ex;
+}
+
+void 
+peer::__patch__UserSessionPtr(void* __addr, ::Ice::ObjectPtr& v)
+{
+    ::peer::UserSessionPtr* p = static_cast< ::peer::UserSessionPtr*>(__addr);
+    assert(p);
+    *p = ::peer::UserSessionPtr::dynamicCast(v);
+    if(v && !*p)
+    {
+	::Ice::NoObjectFactoryException e(__FILE__, __LINE__);
+	e.type = ::peer::UserSession::ice_staticId();
+	throw e;
+    }
+}
+
+bool
+peer::operator==(const ::peer::UserSession& l, const ::peer::UserSession& r)
+{
+    return static_cast<const ::Ice::Object&>(l) == static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator!=(const ::peer::UserSession& l, const ::peer::UserSession& r)
+{
+    return static_cast<const ::Ice::Object&>(l) != static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<(const ::peer::UserSession& l, const ::peer::UserSession& r)
+{
+    return static_cast<const ::Ice::Object&>(l) < static_cast<const ::Ice::Object&>(r);
+}
+
+bool
+peer::operator<=(const ::peer::UserSession& l, const ::peer::UserSession& r)
+{
+    return l < r || l == r;
+}
+
+bool
+peer::operator>(const ::peer::UserSession& l, const ::peer::UserSession& r)
+{
+    return !(l < r) && !(l == r);
+}
+
+bool
+peer::operator>=(const ::peer::UserSession& l, const ::peer::UserSession& r)
+{
+    return !(l < r);
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/local/terk/peer/MRPLPeer.h ./local/terk/peer/MRPLPeer.h
--- ../Tekkotsu_3.0/local/terk/peer/MRPLPeer.h	1969-12-31 19:00:00.000000000 -0500
+++ ./local/terk/peer/MRPLPeer.h	2007-04-09 17:18:13.000000000 -0400
@@ -0,0 +1,1040 @@
+// **********************************************************************
+//
+// Copyright (c) 2003-2006 ZeroC, Inc. All rights reserved.
+//
+// This copy of Ice is licensed to you under the terms described in the
+// ICE_LICENSE file included in this distribution.
+//
+// **********************************************************************
+
+// Ice version 3.1.1
+// Generated from file `MRPLPeer.ice'
+
+#ifndef ___home_btsai_terk_source_TeRKPeerCommon_code_c____MRPLPeer_h__
+#define ___home_btsai_terk_source_TeRKPeerCommon_code_c____MRPLPeer_h__
+
+#include <Ice/LocalObjectF.h>
+#include <Ice/ProxyF.h>
+#include <Ice/ObjectF.h>
+#include <Ice/Exception.h>
+#include <Ice/LocalObject.h>
+#include <Ice/Proxy.h>
+#include <Ice/Object.h>
+#include <Ice/Outgoing.h>
+#include <Ice/OutgoingAsync.h>
+#include <Ice/Incoming.h>
+#include <Ice/Direct.h>
+#include <Ice/UserExceptionFactory.h>
+#include <Ice/FactoryTable.h>
+#include <Ice/StreamF.h>
+#include <Ice/Identity.h>
+#include <Glacier2/Session.h>
+#include <Ice/UndefSysMacros.h>
+
+#ifndef ICE_IGNORE_VERSION
+#   if ICE_INT_VERSION / 100 != 301
+#       error Ice version mismatch!
+#   endif
+#   if ICE_INT_VERSION % 100 < 1
+#       error Ice patch level mismatch!
+#   endif
+#endif
+
+namespace IceProxy
+{
+
+namespace peer
+{
+
+class UserConnectionEventHandler;
+bool operator==(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator!=(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator<(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator<=(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator>(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator>=(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+
+class PeerConnectionEventHandler;
+bool operator==(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator!=(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator<(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator<=(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator>(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator>=(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+
+class ConnectionEventHandler;
+bool operator==(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator!=(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator<(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator<=(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator>(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator>=(const ConnectionEventHandler&, const ConnectionEventHandler&);
+
+class PeerRegistrationHandler;
+bool operator==(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator!=(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator<(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator<=(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator>(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator>=(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+
+class UserSession;
+bool operator==(const UserSession&, const UserSession&);
+bool operator!=(const UserSession&, const UserSession&);
+bool operator<(const UserSession&, const UserSession&);
+bool operator<=(const UserSession&, const UserSession&);
+bool operator>(const UserSession&, const UserSession&);
+bool operator>=(const UserSession&, const UserSession&);
+
+}
+
+}
+
+namespace peer
+{
+
+class UserConnectionEventHandler;
+bool operator==(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator!=(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator<(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator<=(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator>(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+bool operator>=(const UserConnectionEventHandler&, const UserConnectionEventHandler&);
+
+class PeerConnectionEventHandler;
+bool operator==(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator!=(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator<(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator<=(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator>(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+bool operator>=(const PeerConnectionEventHandler&, const PeerConnectionEventHandler&);
+
+class ConnectionEventHandler;
+bool operator==(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator!=(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator<(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator<=(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator>(const ConnectionEventHandler&, const ConnectionEventHandler&);
+bool operator>=(const ConnectionEventHandler&, const ConnectionEventHandler&);
+
+class PeerRegistrationHandler;
+bool operator==(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator!=(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator<(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator<=(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator>(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+bool operator>=(const PeerRegistrationHandler&, const PeerRegistrationHandler&);
+
+class UserSession;
+bool operator==(const UserSession&, const UserSession&);
+bool operator!=(const UserSession&, const UserSession&);
+bool operator<(const UserSession&, const UserSession&);
+bool operator<=(const UserSession&, const UserSession&);
+bool operator>(const UserSession&, const UserSession&);
+bool operator>=(const UserSession&, const UserSession&);
+
+}
+
+namespace IceInternal
+{
+
+void incRef(::peer::UserConnectionEventHandler*);
+void decRef(::peer::UserConnectionEventHandler*);
+
+void incRef(::IceProxy::peer::UserConnectionEventHandler*);
+void decRef(::IceProxy::peer::UserConnectionEventHandler*);
+
+void incRef(::peer::PeerConnectionEventHandler*);
+void decRef(::peer::PeerConnectionEventHandler*);
+
+void incRef(::IceProxy::peer::PeerConnectionEventHandler*);
+void decRef(::IceProxy::peer::PeerConnectionEventHandler*);
+
+void incRef(::peer::ConnectionEventHandler*);
+void decRef(::peer::ConnectionEventHandler*);
+
+void incRef(::IceProxy::peer::ConnectionEventHandler*);
+void decRef(::IceProxy::peer::ConnectionEventHandler*);
+
+void incRef(::peer::PeerRegistrationHandler*);
+void decRef(::peer::PeerRegistrationHandler*);
+
+void incRef(::IceProxy::peer::PeerRegistrationHandler*);
+void decRef(::IceProxy::peer::PeerRegistrationHandler*);
+
+void incRef(::peer::UserSession*);
+void decRef(::peer::UserSession*);
+
+void incRef(::IceProxy::peer::UserSession*);
+void decRef(::IceProxy::peer::UserSession*);
+
+}
+
+namespace peer
+{
+
+typedef ::IceInternal::Handle< ::peer::UserConnectionEventHandler> UserConnectionEventHandlerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::peer::UserConnectionEventHandler> UserConnectionEventHandlerPrx;
+
+void __write(::IceInternal::BasicStream*, const UserConnectionEventHandlerPrx&);
+void __read(::IceInternal::BasicStream*, UserConnectionEventHandlerPrx&);
+void __write(::IceInternal::BasicStream*, const UserConnectionEventHandlerPtr&);
+void __patch__UserConnectionEventHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::peer::PeerConnectionEventHandler> PeerConnectionEventHandlerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::peer::PeerConnectionEventHandler> PeerConnectionEventHandlerPrx;
+
+void __write(::IceInternal::BasicStream*, const PeerConnectionEventHandlerPrx&);
+void __read(::IceInternal::BasicStream*, PeerConnectionEventHandlerPrx&);
+void __write(::IceInternal::BasicStream*, const PeerConnectionEventHandlerPtr&);
+void __patch__PeerConnectionEventHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::peer::ConnectionEventHandler> ConnectionEventHandlerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::peer::ConnectionEventHandler> ConnectionEventHandlerPrx;
+
+void __write(::IceInternal::BasicStream*, const ConnectionEventHandlerPrx&);
+void __read(::IceInternal::BasicStream*, ConnectionEventHandlerPrx&);
+void __write(::IceInternal::BasicStream*, const ConnectionEventHandlerPtr&);
+void __patch__ConnectionEventHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::peer::PeerRegistrationHandler> PeerRegistrationHandlerPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::peer::PeerRegistrationHandler> PeerRegistrationHandlerPrx;
+
+void __write(::IceInternal::BasicStream*, const PeerRegistrationHandlerPrx&);
+void __read(::IceInternal::BasicStream*, PeerRegistrationHandlerPrx&);
+void __write(::IceInternal::BasicStream*, const PeerRegistrationHandlerPtr&);
+void __patch__PeerRegistrationHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+typedef ::IceInternal::Handle< ::peer::UserSession> UserSessionPtr;
+typedef ::IceInternal::ProxyHandle< ::IceProxy::peer::UserSession> UserSessionPrx;
+
+void __write(::IceInternal::BasicStream*, const UserSessionPrx&);
+void __read(::IceInternal::BasicStream*, UserSessionPrx&);
+void __write(::IceInternal::BasicStream*, const UserSessionPtr&);
+void __patch__UserSessionPtr(void*, ::Ice::ObjectPtr&);
+
+}
+
+namespace peer
+{
+
+enum PeerAccessLevel
+{
+    AccessLevelOwner,
+    AccessLevelOwnerRestricted,
+    AccessLevelNormalEnhanced,
+    AccessLevelNormal,
+    AccessLevelNormalRestricted,
+    AccessLevelGuestEnhanced,
+    AccessLevelGuest,
+    AccessLevelGuestRestricted,
+    AccessLevelNone
+};
+
+void __write(::IceInternal::BasicStream*, PeerAccessLevel);
+void __read(::IceInternal::BasicStream*, PeerAccessLevel&);
+
+typedef ::std::vector< ::Ice::Identity> IdentityArray;
+
+class __U__IdentityArray { };
+void __write(::IceInternal::BasicStream*, const ::Ice::Identity*, const ::Ice::Identity*, __U__IdentityArray);
+void __read(::IceInternal::BasicStream*, IdentityArray&, __U__IdentityArray);
+
+typedef ::std::vector< ::Ice::ObjectPrx> ObjectProxyArray;
+
+class __U__ObjectProxyArray { };
+void __write(::IceInternal::BasicStream*, const ::Ice::ObjectPrx*, const ::Ice::ObjectPrx*, __U__ObjectProxyArray);
+void __read(::IceInternal::BasicStream*, ObjectProxyArray&, __U__ObjectProxyArray);
+
+typedef ::std::map< ::Ice::Identity, ::Ice::ObjectPrx> IdentityToProxyMap;
+
+class __U__IdentityToProxyMap { };
+void __write(::IceInternal::BasicStream*, const IdentityToProxyMap&, __U__IdentityToProxyMap);
+void __read(::IceInternal::BasicStream*, IdentityToProxyMap&, __U__IdentityToProxyMap);
+
+struct PeerIdentifier
+{
+    ::std::string userId;
+    ::std::string firstName;
+    ::std::string lastName;
+
+    bool operator==(const PeerIdentifier&) const;
+    bool operator!=(const PeerIdentifier&) const;
+    bool operator<(const PeerIdentifier&) const;
+    bool operator<=(const PeerIdentifier& __rhs) const
+    {
+	return operator<(__rhs) || operator==(__rhs);
+    }
+    bool operator>(const PeerIdentifier& __rhs) const
+    {
+	return !operator<(__rhs) && !operator==(__rhs);
+    }
+    bool operator>=(const PeerIdentifier& __rhs) const
+    {
+	return !operator<(__rhs);
+    }
+
+    void __write(::IceInternal::BasicStream*) const;
+    void __read(::IceInternal::BasicStream*);
+};
+
+class PeerException : public ::Ice::UserException
+{
+public:
+
+    PeerException() {}
+    explicit PeerException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    ::std::string reason;
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+static PeerException __PeerException_init;
+
+class InvalidIdentityException : public ::peer::PeerException
+{
+public:
+
+    InvalidIdentityException() {}
+    explicit InvalidIdentityException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class PeerAccessException : public ::peer::PeerException
+{
+public:
+
+    PeerAccessException() {}
+    explicit PeerAccessException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class PeerUnavailableException : public ::peer::PeerException
+{
+public:
+
+    PeerUnavailableException() {}
+    explicit PeerUnavailableException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class PeerConnectionFailedException : public ::peer::PeerException
+{
+public:
+
+    PeerConnectionFailedException() {}
+    explicit PeerConnectionFailedException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class DuplicateConnectionException : public ::peer::PeerException
+{
+public:
+
+    DuplicateConnectionException() {}
+    explicit DuplicateConnectionException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+class RegistrationException : public ::peer::PeerException
+{
+public:
+
+    RegistrationException() {}
+    explicit RegistrationException(const ::std::string&);
+
+    virtual const ::std::string ice_name() const;
+    virtual ::Ice::Exception* ice_clone() const;
+    virtual void ice_throw() const;
+
+    static const ::IceInternal::UserExceptionFactoryPtr& ice_factory();
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+typedef ::std::vector< ::peer::PeerIdentifier> PeerIdentifierSet;
+
+class __U__PeerIdentifierSet { };
+void __write(::IceInternal::BasicStream*, const ::peer::PeerIdentifier*, const ::peer::PeerIdentifier*, __U__PeerIdentifierSet);
+void __read(::IceInternal::BasicStream*, PeerIdentifierSet&, __U__PeerIdentifierSet);
+
+}
+
+namespace peer
+{
+
+class AMI_UserConnectionEventHandler_forcedLogoutNotification : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::peer::UserConnectionEventHandlerPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::peer::AMI_UserConnectionEventHandler_forcedLogoutNotification> AMI_UserConnectionEventHandler_forcedLogoutNotificationPtr;
+
+class AMI_PeerConnectionEventHandler_peerConnected : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::peer::PeerConnectionEventHandlerPrx&, const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::peer::AMI_PeerConnectionEventHandler_peerConnected> AMI_PeerConnectionEventHandler_peerConnectedPtr;
+
+class AMI_PeerConnectionEventHandler_peerConnectedNoProxy : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::peer::PeerConnectionEventHandlerPrx&, const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxy> AMI_PeerConnectionEventHandler_peerConnectedNoProxyPtr;
+
+class AMI_PeerConnectionEventHandler_peerDisconnected : public ::IceInternal::OutgoingAsync
+{
+public:
+
+    virtual void ice_response() = 0;
+    virtual void ice_exception(const ::Ice::Exception&) = 0;
+
+    void __invoke(const ::peer::PeerConnectionEventHandlerPrx&, const ::std::string&, const ::Ice::Context&);
+
+protected:
+
+    virtual void __response(bool);
+};
+
+typedef ::IceUtil::Handle< ::peer::AMI_PeerConnectionEventHandler_peerDisconnected> AMI_PeerConnectionEventHandler_peerDisconnectedPtr;
+
+}
+
+namespace IceProxy
+{
+
+namespace peer
+{
+
+class UserConnectionEventHandler : virtual public ::IceProxy::Ice::Object
+{
+public:
+
+    void forcedLogoutNotification()
+    {
+	forcedLogoutNotification(__defaultContext());
+    }
+    void forcedLogoutNotification(const ::Ice::Context&);
+    void forcedLogoutNotification_async(const ::peer::AMI_UserConnectionEventHandler_forcedLogoutNotificationPtr&);
+    void forcedLogoutNotification_async(const ::peer::AMI_UserConnectionEventHandler_forcedLogoutNotificationPtr&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class PeerConnectionEventHandler : virtual public ::IceProxy::Ice::Object
+{
+public:
+
+    void peerConnected(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel, const ::Ice::ObjectPrx& peerProxy)
+    {
+	peerConnected(peerUserId, accessLevel, peerProxy, __defaultContext());
+    }
+    void peerConnected(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Context&);
+    void peerConnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedPtr&, const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&);
+    void peerConnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedPtr&, const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+    void peerConnectedNoProxy(const ::std::string& peerUserId, ::peer::PeerAccessLevel accessLevel)
+    {
+	peerConnectedNoProxy(peerUserId, accessLevel, __defaultContext());
+    }
+    void peerConnectedNoProxy(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Context&);
+    void peerConnectedNoProxy_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxyPtr&, const ::std::string&, ::peer::PeerAccessLevel);
+    void peerConnectedNoProxy_async(const ::peer::AMI_PeerConnectionEventHandler_peerConnectedNoProxyPtr&, const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Context&);
+
+    void peerDisconnected(const ::std::string& peerUserId)
+    {
+	peerDisconnected(peerUserId, __defaultContext());
+    }
+    void peerDisconnected(const ::std::string&, const ::Ice::Context&);
+    void peerDisconnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerDisconnectedPtr&, const ::std::string&);
+    void peerDisconnected_async(const ::peer::AMI_PeerConnectionEventHandler_peerDisconnectedPtr&, const ::std::string&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class ConnectionEventHandler : virtual public ::IceProxy::peer::UserConnectionEventHandler,
+			       virtual public ::IceProxy::peer::PeerConnectionEventHandler
+{
+public:
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class PeerRegistrationHandler : virtual public ::IceProxy::Ice::Object
+{
+public:
+
+    void registerCallbacks(const ::Ice::ObjectPrx& selfCallbackProxy, const ::peer::ConnectionEventHandlerPrx& connectionEventHandlerProxy)
+    {
+	registerCallbacks(selfCallbackProxy, connectionEventHandlerProxy, __defaultContext());
+    }
+    void registerCallbacks(const ::Ice::ObjectPrx&, const ::peer::ConnectionEventHandlerPrx&, const ::Ice::Context&);
+
+    void registerProxy(const ::Ice::ObjectPrx& proxy)
+    {
+	registerProxy(proxy, __defaultContext());
+    }
+    void registerProxy(const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+    void registerProxies(const ::peer::ObjectProxyArray& proxies)
+    {
+	registerProxies(proxies, __defaultContext());
+    }
+    void registerProxies(const ::peer::ObjectProxyArray&, const ::Ice::Context&);
+
+    ::Ice::ObjectPrx getPeerProxy(const ::std::string& peerUserId, const ::Ice::Identity& privateProxyIdentity)
+    {
+	return getPeerProxy(peerUserId, privateProxyIdentity, __defaultContext());
+    }
+    ::Ice::ObjectPrx getPeerProxy(const ::std::string&, const ::Ice::Identity&, const ::Ice::Context&);
+
+    ::peer::IdentityToProxyMap getPeerProxies(const ::std::string& peerUserId, const ::peer::IdentityArray& privateProxyIdentities)
+    {
+	return getPeerProxies(peerUserId, privateProxyIdentities, __defaultContext());
+    }
+    ::peer::IdentityToProxyMap getPeerProxies(const ::std::string&, const ::peer::IdentityArray&, const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+class UserSession : virtual public ::IceProxy::Glacier2::Session,
+		    virtual public ::IceProxy::peer::PeerRegistrationHandler
+{
+public:
+
+    ::peer::PeerIdentifierSet getMyAvailablePeers()
+    {
+	return getMyAvailablePeers(__defaultContext());
+    }
+    ::peer::PeerIdentifierSet getMyAvailablePeers(const ::Ice::Context&);
+
+    ::Ice::ObjectPrx connectToPeer(const ::std::string& peerUserId)
+    {
+	return connectToPeer(peerUserId, __defaultContext());
+    }
+    ::Ice::ObjectPrx connectToPeer(const ::std::string&, const ::Ice::Context&);
+
+    ::peer::PeerIdentifierSet getConnectedPeers()
+    {
+	return getConnectedPeers(__defaultContext());
+    }
+    ::peer::PeerIdentifierSet getConnectedPeers(const ::Ice::Context&);
+
+    void disconnectFromPeer(const ::std::string& peerUserId)
+    {
+	disconnectFromPeer(peerUserId, __defaultContext());
+    }
+    void disconnectFromPeer(const ::std::string&, const ::Ice::Context&);
+
+    void disconnectFromPeers()
+    {
+	disconnectFromPeers(__defaultContext());
+    }
+    void disconnectFromPeers(const ::Ice::Context&);
+    
+    static const ::std::string& ice_staticId();
+
+private: 
+
+    virtual ::IceInternal::Handle< ::IceDelegateM::Ice::Object> __createDelegateM();
+    virtual ::IceInternal::Handle< ::IceDelegateD::Ice::Object> __createDelegateD();
+};
+
+}
+
+}
+
+namespace IceDelegate
+{
+
+namespace peer
+{
+
+class UserConnectionEventHandler : virtual public ::IceDelegate::Ice::Object
+{
+public:
+
+    virtual void forcedLogoutNotification(const ::Ice::Context&) = 0;
+};
+
+class PeerConnectionEventHandler : virtual public ::IceDelegate::Ice::Object
+{
+public:
+
+    virtual void peerConnected(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Context&) = 0;
+
+    virtual void peerConnectedNoProxy(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Context&) = 0;
+
+    virtual void peerDisconnected(const ::std::string&, const ::Ice::Context&) = 0;
+};
+
+class ConnectionEventHandler : virtual public ::IceDelegate::peer::UserConnectionEventHandler,
+			       virtual public ::IceDelegate::peer::PeerConnectionEventHandler
+{
+public:
+};
+
+class PeerRegistrationHandler : virtual public ::IceDelegate::Ice::Object
+{
+public:
+
+    virtual void registerCallbacks(const ::Ice::ObjectPrx&, const ::peer::ConnectionEventHandlerPrx&, const ::Ice::Context&) = 0;
+
+    virtual void registerProxy(const ::Ice::ObjectPrx&, const ::Ice::Context&) = 0;
+
+    virtual void registerProxies(const ::peer::ObjectProxyArray&, const ::Ice::Context&) = 0;
+
+    virtual ::Ice::ObjectPrx getPeerProxy(const ::std::string&, const ::Ice::Identity&, const ::Ice::Context&) = 0;
+
+    virtual ::peer::IdentityToProxyMap getPeerProxies(const ::std::string&, const ::peer::IdentityArray&, const ::Ice::Context&) = 0;
+};
+
+class UserSession : virtual public ::IceDelegate::Glacier2::Session,
+		    virtual public ::IceDelegate::peer::PeerRegistrationHandler
+{
+public:
+
+    virtual ::peer::PeerIdentifierSet getMyAvailablePeers(const ::Ice::Context&) = 0;
+
+    virtual ::Ice::ObjectPrx connectToPeer(const ::std::string&, const ::Ice::Context&) = 0;
+
+    virtual ::peer::PeerIdentifierSet getConnectedPeers(const ::Ice::Context&) = 0;
+
+    virtual void disconnectFromPeer(const ::std::string&, const ::Ice::Context&) = 0;
+
+    virtual void disconnectFromPeers(const ::Ice::Context&) = 0;
+};
+
+}
+
+}
+
+namespace IceDelegateM
+{
+
+namespace peer
+{
+
+class UserConnectionEventHandler : virtual public ::IceDelegate::peer::UserConnectionEventHandler,
+				   virtual public ::IceDelegateM::Ice::Object
+{
+public:
+
+    virtual void forcedLogoutNotification(const ::Ice::Context&);
+};
+
+class PeerConnectionEventHandler : virtual public ::IceDelegate::peer::PeerConnectionEventHandler,
+				   virtual public ::IceDelegateM::Ice::Object
+{
+public:
+
+    virtual void peerConnected(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+    virtual void peerConnectedNoProxy(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Context&);
+
+    virtual void peerDisconnected(const ::std::string&, const ::Ice::Context&);
+};
+
+class ConnectionEventHandler : virtual public ::IceDelegate::peer::ConnectionEventHandler,
+			       virtual public ::IceDelegateM::peer::UserConnectionEventHandler,
+			       virtual public ::IceDelegateM::peer::PeerConnectionEventHandler
+{
+public:
+};
+
+class PeerRegistrationHandler : virtual public ::IceDelegate::peer::PeerRegistrationHandler,
+				virtual public ::IceDelegateM::Ice::Object
+{
+public:
+
+    virtual void registerCallbacks(const ::Ice::ObjectPrx&, const ::peer::ConnectionEventHandlerPrx&, const ::Ice::Context&);
+
+    virtual void registerProxy(const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+    virtual void registerProxies(const ::peer::ObjectProxyArray&, const ::Ice::Context&);
+
+    virtual ::Ice::ObjectPrx getPeerProxy(const ::std::string&, const ::Ice::Identity&, const ::Ice::Context&);
+
+    virtual ::peer::IdentityToProxyMap getPeerProxies(const ::std::string&, const ::peer::IdentityArray&, const ::Ice::Context&);
+};
+
+class UserSession : virtual public ::IceDelegate::peer::UserSession,
+		    virtual public ::IceDelegateM::Glacier2::Session,
+		    virtual public ::IceDelegateM::peer::PeerRegistrationHandler
+{
+public:
+
+    virtual ::peer::PeerIdentifierSet getMyAvailablePeers(const ::Ice::Context&);
+
+    virtual ::Ice::ObjectPrx connectToPeer(const ::std::string&, const ::Ice::Context&);
+
+    virtual ::peer::PeerIdentifierSet getConnectedPeers(const ::Ice::Context&);
+
+    virtual void disconnectFromPeer(const ::std::string&, const ::Ice::Context&);
+
+    virtual void disconnectFromPeers(const ::Ice::Context&);
+};
+
+}
+
+}
+
+namespace IceDelegateD
+{
+
+namespace peer
+{
+
+class UserConnectionEventHandler : virtual public ::IceDelegate::peer::UserConnectionEventHandler,
+				   virtual public ::IceDelegateD::Ice::Object
+{
+public:
+
+    virtual void forcedLogoutNotification(const ::Ice::Context&);
+};
+
+class PeerConnectionEventHandler : virtual public ::IceDelegate::peer::PeerConnectionEventHandler,
+				   virtual public ::IceDelegateD::Ice::Object
+{
+public:
+
+    virtual void peerConnected(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+    virtual void peerConnectedNoProxy(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Context&);
+
+    virtual void peerDisconnected(const ::std::string&, const ::Ice::Context&);
+};
+
+class ConnectionEventHandler : virtual public ::IceDelegate::peer::ConnectionEventHandler,
+			       virtual public ::IceDelegateD::peer::UserConnectionEventHandler,
+			       virtual public ::IceDelegateD::peer::PeerConnectionEventHandler
+{
+public:
+};
+
+class PeerRegistrationHandler : virtual public ::IceDelegate::peer::PeerRegistrationHandler,
+				virtual public ::IceDelegateD::Ice::Object
+{
+public:
+
+    virtual void registerCallbacks(const ::Ice::ObjectPrx&, const ::peer::ConnectionEventHandlerPrx&, const ::Ice::Context&);
+
+    virtual void registerProxy(const ::Ice::ObjectPrx&, const ::Ice::Context&);
+
+    virtual void registerProxies(const ::peer::ObjectProxyArray&, const ::Ice::Context&);
+
+    virtual ::Ice::ObjectPrx getPeerProxy(const ::std::string&, const ::Ice::Identity&, const ::Ice::Context&);
+
+    virtual ::peer::IdentityToProxyMap getPeerProxies(const ::std::string&, const ::peer::IdentityArray&, const ::Ice::Context&);
+};
+
+class UserSession : virtual public ::IceDelegate::peer::UserSession,
+		    virtual public ::IceDelegateD::Glacier2::Session,
+		    virtual public ::IceDelegateD::peer::PeerRegistrationHandler
+{
+public:
+
+    virtual ::peer::PeerIdentifierSet getMyAvailablePeers(const ::Ice::Context&);
+
+    virtual ::Ice::ObjectPrx connectToPeer(const ::std::string&, const ::Ice::Context&);
+
+    virtual ::peer::PeerIdentifierSet getConnectedPeers(const ::Ice::Context&);
+
+    virtual void disconnectFromPeer(const ::std::string&, const ::Ice::Context&);
+
+    virtual void disconnectFromPeers(const ::Ice::Context&);
+};
+
+}
+
+}
+
+namespace peer
+{
+
+class UserConnectionEventHandler : virtual public ::Ice::Object
+{
+public:
+
+    typedef UserConnectionEventHandlerPrx ProxyType;
+    typedef UserConnectionEventHandlerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void forcedLogoutNotification(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___forcedLogoutNotification(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__UserConnectionEventHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+class PeerConnectionEventHandler : virtual public ::Ice::Object
+{
+public:
+
+    typedef PeerConnectionEventHandlerPrx ProxyType;
+    typedef PeerConnectionEventHandlerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void peerConnected(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::ObjectPrx&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___peerConnected(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void peerConnectedNoProxy(const ::std::string&, ::peer::PeerAccessLevel, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___peerConnectedNoProxy(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void peerDisconnected(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___peerDisconnected(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__PeerConnectionEventHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+class ConnectionEventHandler : virtual public ::peer::UserConnectionEventHandler,
+			       virtual public ::peer::PeerConnectionEventHandler
+{
+public:
+
+    typedef ConnectionEventHandlerPrx ProxyType;
+    typedef ConnectionEventHandlerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__ConnectionEventHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+class PeerRegistrationHandler : virtual public ::Ice::Object
+{
+public:
+
+    typedef PeerRegistrationHandlerPrx ProxyType;
+    typedef PeerRegistrationHandlerPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual void registerCallbacks(const ::Ice::ObjectPrx&, const ::peer::ConnectionEventHandlerPrx&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___registerCallbacks(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void registerProxy(const ::Ice::ObjectPrx&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___registerProxy(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void registerProxies(const ::peer::ObjectProxyArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___registerProxies(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::Ice::ObjectPrx getPeerProxy(const ::std::string&, const ::Ice::Identity&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getPeerProxy(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::peer::IdentityToProxyMap getPeerProxies(const ::std::string&, const ::peer::IdentityArray&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getPeerProxies(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__PeerRegistrationHandlerPtr(void*, ::Ice::ObjectPtr&);
+
+class UserSession : virtual public ::Glacier2::Session,
+		    virtual public ::peer::PeerRegistrationHandler
+{
+public:
+
+    typedef UserSessionPrx ProxyType;
+    typedef UserSessionPtr PointerType;
+    
+    virtual ::Ice::ObjectPtr ice_clone() const;
+
+    virtual bool ice_isA(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) const;
+    virtual ::std::vector< ::std::string> ice_ids(const ::Ice::Current& = ::Ice::Current()) const;
+    virtual const ::std::string& ice_id(const ::Ice::Current& = ::Ice::Current()) const;
+    static const ::std::string& ice_staticId();
+
+    virtual ::peer::PeerIdentifierSet getMyAvailablePeers(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getMyAvailablePeers(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::Ice::ObjectPrx connectToPeer(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___connectToPeer(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::peer::PeerIdentifierSet getConnectedPeers(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___getConnectedPeers(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void disconnectFromPeer(const ::std::string&, const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___disconnectFromPeer(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void disconnectFromPeers(const ::Ice::Current& = ::Ice::Current()) = 0;
+    ::IceInternal::DispatchStatus ___disconnectFromPeers(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual ::IceInternal::DispatchStatus __dispatch(::IceInternal::Incoming&, const ::Ice::Current&);
+
+    virtual void __write(::IceInternal::BasicStream*) const;
+    virtual void __read(::IceInternal::BasicStream*, bool);
+    virtual void __write(const ::Ice::OutputStreamPtr&) const;
+    virtual void __read(const ::Ice::InputStreamPtr&, bool);
+};
+
+void __patch__UserSessionPtr(void*, ::Ice::ObjectPtr&);
+
+}
+
+#endif
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/Environment.conf ./project/Environment.conf
--- ../Tekkotsu_3.0/project/Environment.conf	2006-05-09 12:28:42.000000000 -0400
+++ ./project/Environment.conf	2007-11-12 23:16:07.000000000 -0500
@@ -24,27 +24,42 @@
 MEMSTICK_ROOT ?= $(if $(findstring CYGWIN,$(shell uname)),/cygdrive/e,/mnt/memstick)
 endif
 
-# Directory where the OPEN-R SDK was installed
-# See http://www.tekkotsu.org/SDKInstall.html
-# or the OPEN-R website: http://openr.aibo.com/
+# Directory where the OPEN-R SDK was installed, required for building Aibo executables
+# See http://www.tekkotsu.org/openr-install.html
 OPENRSDK_ROOT ?= /usr/local/OPEN_R_SDK
 
+# Directory where ICE is installed, required for TeRK support
+# See http://www.zeroc.com/ice.html
+ICE_ROOT ?= /usr/local/Ice
+
 # What model are you targeting?  This will look at the
 # $TEKKOTSU_ROOT/TARGET_MODEL file to find out.  If the file is not
 # found, it is created with the default setting TGT_ERS2xx.  change
 # the target model, make will automatically recompile everything for
 # you.
-# Legal values: TGT_ERS210 TGT_ERS220 TGT_ERS2xx TGT_ERS7
+# Legal values:
+#   Aibos: TGT_ERS210 TGT_ERS220 TGT_ERS2xx TGT_ERS7
+#   LynxMotion: TGT_LYNXARM6
 TEKKOTSU_TARGET_MODEL ?= TGT_ERS7
 
 # What OS is this going to be running under?
 # Choices are:
 #   PLATFORM_APERIOS - the AIBO's OS
-#   PLATFORM_LOCAL - the current desktop environment (*Under development*)
+#   PLATFORM_LOCAL - the current desktop environment
 # If you need to do platform specific stuff in your code, best
 # to check #ifdef PLATFORM_APERIOS, and otherwise assume a UNIX-style
 # environment.  Note that non-Aperios implies no OPEN-R headers.
-TEKKOTSU_TARGET_PLATFORM ?= PLATFORM_APERIOS
+#
+# This default value selects PLATFORM_APERIOS if targeting an Aibo
+# model, otherwise PLATFORM_LOCAL.
+TEKKOTSU_TARGET_PLATFORM ?= $(if $(filter TGT_ERS%,$(TEKKOTSU_TARGET_MODEL)),PLATFORM_APERIOS,PLATFORM_LOCAL)
+
+# What kind of intermediary linking to perform?
+# SHARED/DYNAMIC library support is EXPERIMENTAL
+# This will setting will be ignored for PLATFORM_APERIOS
+# To use a static library, try libtekkotsu.a
+# To use a shared library, try libtekkotsu.$(if $(findstring Darwin,$(shell uname)),dylib,so)
+LIBTEKKOTSU ?= libtekkotsu.$(if $(findstring Darwin,$(shell uname)),dylib,so)
 
 # This will trigger the project's Makefile to always attempt to make
 # the framework as well.  This is useful if you are hacking the
@@ -69,14 +84,17 @@
 
 # Controls the type(s) of optimization performed, but
 # only applied if TEKKOTSU_DEBUG is empty
-TEKKOTSU_OPTIMIZE ?= -O2 -fomit-frame-pointer $(if $(findstring PLATFORM_APERIOS,$(TEKKOTSU_TARGET_PLATFORM)),-DDEBUG -DOPENR_DEBUG)
+TEKKOTSU_OPTIMIZE ?= -O2 $(if $(findstring PLATFORM_APERIOS,$(TEKKOTSU_TARGET_PLATFORM)),-DDEBUG -DOPENR_DEBUG)
 
 # This can be nice if you want to use 'more' to page through errors
 # if they occur.  Otherwise, try using 'cat' instead.  Cygwin users
 # may need to explicitly install the 'more' package
 # This default value will test for the availability of 'more', and
 # fall back to using 'cat'.
-TEKKOTSU_LOGVIEW ?= $(shell if which more > /dev/null ; then echo "more $(if $(findstring Darwin,$(shell uname)),-R)"; else echo "cat" ; fi )
+# The -r option is needed to display colors instead of control characters,
+# and -E makes it exit when the end of log is reached (without user prompt)
+# 'more' is used instead of 'less' because less doesn't leave the data on the screen after exiting
+TEKKOTSU_LOGVIEW ?= $(shell if which more > /dev/null ; then echo "more $(if $(findstring Darwin,$(shell uname)),-RE)"; else echo "cat" ; fi )
 
 # These control the location that the temporary object files will
 # be stored.
@@ -110,6 +128,7 @@
     FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) $(OPENRSDK_ROOT)
   endif
   STUBGEN=$(OPENRSDK_ROOT)/OPEN_R/bin/stubgen2
+  LIBTEKKOTSU=libtekkotsu.a
 else
   CC=gcc
   CXX=g++
@@ -120,13 +139,15 @@
   ifeq ($(TEKKOTSU_FILTERSYSWARN),cat)
     FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN)
   else
-    FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) /usr/.*/?include/
+    FILTERSYSWARN=$(TEKKOTSU_FILTERSYSWARN) "/usr/.*/?include/|$(ICE_ROOT)"
   endif
 endif
 COLORFILT=$(TEKKOTSU_COLORFILT)
 
+# Determine if precompiled header support is available...
 # This can speed up the compilation process, but is currently only
 # supported by the 3.4 branch of gcc, or 3.3 of the gcc from Apple
+ifeq ($(shell $(CXX) -v > /dev/null 2>&1 || echo "not found"),)
 TEST_CXX_MAJOR:=$(shell $(CXX) --version | sed -n 's/^.* (GCC) \([0-9]*\)\.\([0-9]*\).*/\1/p')
 TEST_CXX_MINOR:=$(shell $(CXX) --version | sed -n 's/^.* (GCC) \([0-9]*\)\.\([0-9]*\).*/\2/p')
 #Apple added support for precompiled headers early in the 3.x branch
@@ -134,12 +155,17 @@
 #Cygming apparently removes support for precompiled headers in the 3.x branch
 TEST_CXX_CYGMING:=$(findstring cygming,$(shell $(CXX) --version))
 TEKKOTSU_PCH ?= $(shell if [ $(TEST_CXX_MAJOR) -ge 4 -o $(TEST_CXX_MAJOR) -ge 3 -a -z "$(TEST_CXX_CYGMING)" -a \( $(TEST_CXX_MINOR) -ge 4 -o -n "$(TEST_CXX_APPLE)" \) ] ; then echo "common.h"; fi)
+# 'cache' result:
+TEKKOTSU_PCH:=$(TEKKOTSU_PCH)
+endif
 
 #These will be the actual build directories used for the current target
 TK_LIB_BD:=$(TEKKOTSU_BUILDDIR)/$(TEKKOTSU_TARGET_PLATFORM)
 TK_BD:=$(TEKKOTSU_BUILDDIR)/$(TEKKOTSU_TARGET_PLATFORM)/$(TEKKOTSU_TARGET_MODEL)
 PROJ_BD:=$(PROJECT_BUILDDIR)/$(TEKKOTSU_TARGET_PLATFORM)/$(TEKKOTSU_TARGET_MODEL)
-$(shell mkdir -p $(TK_BD))
+
+# will be set to non-empty if ICE_ROOT exists
+HAVE_ICE:=$(shell if [ -d "$(ICE_ROOT)" ] ; then echo true; fi)
 
 #For debugging:
 #test:=$(shell echo "TEKKOTSU_BUILDDIR: $(TEKKOTSU_BUILDDIR)" > /dev/tty)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/Make.xcodeproj/project.pbxproj ./project/Make.xcodeproj/project.pbxproj
--- ../Tekkotsu_3.0/project/Make.xcodeproj/project.pbxproj	2006-09-28 16:42:52.000000000 -0400
+++ ./project/Make.xcodeproj/project.pbxproj	2007-11-21 19:06:54.000000000 -0500
@@ -11,15 +11,706 @@
 		690065A00A4EF58800E895F9 /* PNGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6900659D0A4EF58700E895F9 /* PNGGenerator.cc */; };
 		6901D58F0AAF288500104815 /* TimerEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6901D58D0AAF288500104815 /* TimerEvent.cc */; };
 		6901D5900AAF288600104815 /* TimerEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6901D58D0AAF288500104815 /* TimerEvent.cc */; };
+		690B6C5D0B98C9CE005E6FE5 /* zignor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73230B57E27500FF5476 /* zignor.cc */; };
+		690B6C5E0B98C9CE005E6FE5 /* zigrandom.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73250B57E27500FF5476 /* zigrandom.cc */; };
+		690B6C620B98C9E7005E6FE5 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF74820B59EC7200FF5476 /* Measures.cc */; };
+		690B6C650B98C9FB005E6FE5 /* LocalizationParticleData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984730B8BF72200AB633A /* LocalizationParticleData.cc */; };
+		690B6C680B98CA03005E6FE5 /* PFShapeLocalization.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */; };
+		690B6C690B98CA03005E6FE5 /* PFShapeSLAM.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */; };
+		690B6C6D0B98CA12005E6FE5 /* Pilot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */; };
+		690B6C700B98CA23005E6FE5 /* ShapeLocalizationParticle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */; };
+		690B6C7C0B98CB61005E6FE5 /* HolonomicMotionModel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */; };
+		690B6C7D0B98CB7E005E6FE5 /* ConfigurationEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */; };
+		690B6C810B98CBAB005E6FE5 /* PilotRequest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */; };
 		691C805608255F6300E8E256 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.cc */; };
 		691C805708255F6300E8E256 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.cc */; };
+		691FC36A0B4EE68700246924 /* CameraBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C607CBD6C0008493CA /* CameraBehavior.cc */; };
+		691FC36B0B4EE6F400246924 /* FollowHeadBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */; };
+		691FC36C0B4EE72100246924 /* WallTestBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E707CBD6C0008493CA /* WallTestBehavior.cc */; };
+		691FC3790B4EF71900246924 /* LedEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83C07CBD6C0008493CA /* LedEngine.cc */; };
 		692964F80AA8CEEF00F47522 /* TestBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692964F60AA8CEEF00F47522 /* TestBehaviors.cc */; };
 		692964F90AA8CEEF00F47522 /* TestBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692964F60AA8CEEF00F47522 /* TestBehaviors.cc */; };
-		692CD63507F8C46B00604100 /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692CD63407F8C46B00604100 /* sim.cc */; };
-		692CD63607F8C46B00604100 /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692CD63407F8C46B00604100 /* sim.cc */; };
-		692CD63707F8C46B00604100 /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692CD63407F8C46B00604100 /* sim.cc */; };
+		692E739B0B9E77C100816584 /* plistBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A071B09575F41001A13D5 /* plistBase.cc */; };
+		692E739C0B9E77C100816584 /* plistCollections.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A072709575F7D001A13D5 /* plistCollections.cc */; };
+		692E739D0B9E77C100816584 /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */; };
+		692E739E0B9E77C100816584 /* StartupBehavior_SetupFileAccess.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */; };
+		692E739F0B9E77C100816584 /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
+		692E73A00B9E77C100816584 /* StartupBehavior_SetupStatusReports.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */; };
+		692E73A10B9E77C100816584 /* StartupBehavior_SetupTekkotsuMon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */; };
+		692E73A30B9E77C100816584 /* StartupBehavior_SetupWalkEdit.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */; };
+		692E73A40B9E77C100816584 /* StartupBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76007CBD4F9008493CA /* StartupBehavior.cc */; };
+		692E73AB0B9E77C100816584 /* BehaviorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78C07CBD6BF008493CA /* BehaviorBase.cc */; };
+		692E73AC0B9E77C100816584 /* Controller.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78F07CBD6BF008493CA /* Controller.cc */; };
+		692E73AD0B9E77C100816584 /* ControlBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79707CBD6BF008493CA /* ControlBase.cc */; };
+		692E73AE0B9E77C100816584 /* EventLogger.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79A07CBD6C0008493CA /* EventLogger.cc */; };
+		692E73AF0B9E77C100816584 /* FileBrowserControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79C07CBD6C0008493CA /* FileBrowserControl.cc */; };
+		692E73B00B9E77C100816584 /* FreeMemReportControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79F07CBD6C0008493CA /* FreeMemReportControl.cc */; };
+		692E73B10B9E77C100816584 /* HelpControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7A107CBD6C0008493CA /* HelpControl.cc */; };
+		692E73B20B9E77C100816584 /* PostureEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7AA07CBD6C0008493CA /* PostureEditor.cc */; };
+		692E73B30B9E77C100816584 /* RebootControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7AD07CBD6C0008493CA /* RebootControl.cc */; };
+		692E73B40B9E77C100816584 /* SensorObserverControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B207CBD6C0008493CA /* SensorObserverControl.cc */; };
+		692E73B50B9E77C100816584 /* ShutdownControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B407CBD6C0008493CA /* ShutdownControl.cc */; };
+		692E73B60B9E77C100816584 /* StringInputControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B607CBD6C0008493CA /* StringInputControl.cc */; };
+		692E73B70B9E77C100816584 /* WalkCalibration.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7BB07CBD6C0008493CA /* WalkCalibration.cc */; };
+		692E73B80B9E77C100816584 /* WaypointWalkControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7BD07CBD6C0008493CA /* WaypointWalkControl.cc */; };
+		692E73B90B9E77C100816584 /* ASCIIVisionBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C107CBD6C0008493CA /* ASCIIVisionBehavior.cc */; };
+		692E73BA0B9E77C100816584 /* CameraBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C607CBD6C0008493CA /* CameraBehavior.cc */; };
+		692E73BB0B9E77C100816584 /* ChaseBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */; };
+		692E73BC0B9E77C100816584 /* DriveMeBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CB07CBD6C0008493CA /* DriveMeBehavior.cc */; };
+		692E73BD0B9E77C100816584 /* ExploreMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */; };
+		692E73BE0B9E77C100816584 /* FollowHeadBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */; };
+		692E73BF0B9E77C100816584 /* PaceTargetsMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7DD07CBD6C0008493CA /* PaceTargetsMachine.cc */; };
+		692E73C00B9E77C100816584 /* StareAtBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E207CBD6C0008493CA /* StareAtBallBehavior.cc */; };
+		692E73C10B9E77C100816584 /* WallTestBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E707CBD6C0008493CA /* WallTestBehavior.cc */; };
+		692E73C20B9E77C100816584 /* EStopControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7EC07CBD6C0008493CA /* EStopControllerBehavior.cc */; };
+		692E73C30B9E77C100816584 /* HeadPointControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7EE07CBD6C0008493CA /* HeadPointControllerBehavior.cc */; };
+		692E73C40B9E77C100816584 /* MicrophoneServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F007CBD6C0008493CA /* MicrophoneServer.cc */; };
+		692E73C50B9E77C100816584 /* RawCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F207CBD6C0008493CA /* RawCamBehavior.cc */; };
+		692E73C60B9E77C100816584 /* SegCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F407CBD6C0008493CA /* SegCamBehavior.cc */; };
+		692E73C70B9E77C100816584 /* SpeakerServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */; };
+		692E73C80B9E77C100816584 /* WalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FB07CBD6C0008493CA /* WalkControllerBehavior.cc */; };
+		692E73C90B9E77C100816584 /* WMMonitorBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FD07CBD6C0008493CA /* WMMonitorBehavior.cc */; };
+		692E73CA0B9E77C100816584 /* WorldStateSerializerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FF07CBD6C0008493CA /* WorldStateSerializerBehavior.cc */; };
+		692E73CB0B9E77C100816584 /* WalkToTargetNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A80B07CBD6C0008493CA /* WalkToTargetNode.cc */; };
+		692E73CC0B9E77C100816584 /* StateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A80E07CBD6C0008493CA /* StateNode.cc */; };
+		692E73CD0B9E77C100816584 /* Transition.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A81007CBD6C0008493CA /* Transition.cc */; };
+		692E73CE0B9E77C100816584 /* RandomTrans.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A81807CBD6C0008493CA /* RandomTrans.cc */; };
+		692E73CF0B9E77C100816584 /* EventBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82007CBD6C0008493CA /* EventBase.cc */; };
+		692E73D00B9E77C100816584 /* EventGeneratorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82207CBD6C0008493CA /* EventGeneratorBase.cc */; };
+		692E73D10B9E77C100816584 /* EventRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82507CBD6C0008493CA /* EventRouter.cc */; };
+		692E73D20B9E77C100816584 /* EventTranslator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82707CBD6C0008493CA /* EventTranslator.cc */; };
+		692E73D30B9E77C100816584 /* LocomotionEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82B07CBD6C0008493CA /* LocomotionEvent.cc */; };
+		692E73D40B9E77C100816584 /* TextMsgEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82E07CBD6C0008493CA /* TextMsgEvent.cc */; };
+		692E73D50B9E77C100816584 /* VisionObjectEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83007CBD6C0008493CA /* VisionObjectEvent.cc */; };
+		692E73D60B9E77C100816584 /* EmergencyStopMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83407CBD6C0008493CA /* EmergencyStopMC.cc */; };
+		692E73D70B9E77C100816584 /* HeadPointerMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83807CBD6C0008493CA /* HeadPointerMC.cc */; };
+		692E73D80B9E77C100816584 /* Kinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83A07CBD6C0008493CA /* Kinematics.cc */; };
+		692E73D90B9E77C100816584 /* LedEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83C07CBD6C0008493CA /* LedEngine.cc */; };
+		692E73DA0B9E77C100816584 /* MotionCommand.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84007CBD6C0008493CA /* MotionCommand.cc */; };
+		692E73DB0B9E77C100816584 /* MotionManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84207CBD6C0008493CA /* MotionManager.cc */; };
+		692E73DC0B9E77C100816584 /* MotionSequenceEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */; };
+		692E73DE0B9E77C100816584 /* OldKinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84A07CBD6C0008493CA /* OldKinematics.cc */; };
+		692E73DF0B9E77C100816584 /* OutputCmd.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84C07CBD6C0008493CA /* OutputCmd.cc */; };
+		692E73E00B9E77C100816584 /* PostureEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85107CBD6C0008493CA /* PostureEngine.cc */; };
+		692E73E10B9E77C100816584 /* PostureMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85307CBD6C0008493CA /* PostureMC.cc */; };
+		692E73E20B9E77C100816584 /* clik.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85707CBD6C0008493CA /* clik.cpp */; };
+		692E73E30B9E77C100816584 /* comp_dq.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85907CBD6C0008493CA /* comp_dq.cpp */; };
+		692E73E40B9E77C100816584 /* comp_dqp.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85A07CBD6C0008493CA /* comp_dqp.cpp */; };
+		692E73E50B9E77C100816584 /* config.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85B07CBD6C0008493CA /* config.cpp */; };
+		692E73E60B9E77C100816584 /* control_select.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85D07CBD6C0008493CA /* control_select.cpp */; };
+		692E73E70B9E77C100816584 /* controller.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85F07CBD6C0008493CA /* controller.cpp */; };
+		692E73E80B9E77C100816584 /* delta_t.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86107CBD6C0008493CA /* delta_t.cpp */; };
+		692E73E90B9E77C100816584 /* dynamics.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86207CBD6C0008493CA /* dynamics.cpp */; };
+		692E73EA0B9E77C100816584 /* dynamics_sim.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86307CBD6C0008493CA /* dynamics_sim.cpp */; };
+		692E73EB0B9E77C100816584 /* gnugraph.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87907CBD6C0008493CA /* gnugraph.cpp */; };
+		692E73EC0B9E77C100816584 /* homogen.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87B07CBD6C0008493CA /* homogen.cpp */; };
+		692E73ED0B9E77C100816584 /* invkine.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87C07CBD6C0008493CA /* invkine.cpp */; };
+		692E73EE0B9E77C100816584 /* kinemat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87D07CBD6C0008493CA /* kinemat.cpp */; };
+		692E73EF0B9E77C100816584 /* quaternion.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87F07CBD6C0008493CA /* quaternion.cpp */; };
+		692E73F00B9E77C100816584 /* sensitiv.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88607CBD6C0008493CA /* sensitiv.cpp */; };
+		692E73F10B9E77C100816584 /* trajectory.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88707CBD6C0008493CA /* trajectory.cpp */; };
+		692E73F20B9E77C100816584 /* utils.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88907CBD6C0008493CA /* utils.cpp */; };
+		692E73F30B9E77C100816584 /* WalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88D07CBD6C0008493CA /* WalkMC.cc */; };
+		692E73F40B9E77C100816584 /* Buffer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89207CBD6C0008493CA /* Buffer.cc */; };
+		692E73F50B9E77C100816584 /* Config.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89507CBD6C0008493CA /* Config.cc */; };
+		692E73F60B9E77C100816584 /* get_time.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89D07CBD6C0008493CA /* get_time.cc */; };
+		692E73F70B9E77C100816584 /* jpeg_mem_dest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8DE07CBD6C1008493CA /* jpeg_mem_dest.cc */; };
+		692E73F80B9E77C100816584 /* LoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8F807CBD6C1008493CA /* LoadSave.cc */; };
+		692E73F90B9E77C100816584 /* bandmat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8FE07CBD6C1008493CA /* bandmat.cpp */; };
+		692E73FA0B9E77C100816584 /* cholesky.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A90007CBD6C1008493CA /* cholesky.cpp */; };
+		692E73FB0B9E77C100816584 /* evalue.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A90707CBD6C1008493CA /* evalue.cpp */; };
+		692E73FC0B9E77C100816584 /* fft.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93807CBD6C1008493CA /* fft.cpp */; };
+		692E73FD0B9E77C100816584 /* hholder.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93907CBD6C1008493CA /* hholder.cpp */; };
+		692E73FE0B9E77C100816584 /* jacobi.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93B07CBD6C1008493CA /* jacobi.cpp */; };
+		692E73FF0B9E77C100816584 /* myexcept.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93D07CBD6C1008493CA /* myexcept.cpp */; };
+		692E74000B9E77C100816584 /* newfft.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93F07CBD6C1008493CA /* newfft.cpp */; };
+		692E74010B9E77C100816584 /* newmat1.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94107CBD6C1008493CA /* newmat1.cpp */; };
+		692E74020B9E77C100816584 /* newmat2.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94207CBD6C1008493CA /* newmat2.cpp */; };
+		692E74030B9E77C100816584 /* newmat3.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94307CBD6C1008493CA /* newmat3.cpp */; };
+		692E74040B9E77C100816584 /* newmat4.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94407CBD6C1008493CA /* newmat4.cpp */; };
+		692E74050B9E77C100816584 /* newmat5.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94507CBD6C1008493CA /* newmat5.cpp */; };
+		692E74060B9E77C100816584 /* newmat6.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94607CBD6C1008493CA /* newmat6.cpp */; };
+		692E74070B9E77C100816584 /* newmat7.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94707CBD6C1008493CA /* newmat7.cpp */; };
+		692E74080B9E77C100816584 /* newmat8.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94807CBD6C1008493CA /* newmat8.cpp */; };
+		692E74090B9E77C100816584 /* newmat9.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94907CBD6C1008493CA /* newmat9.cpp */; };
+		692E740A0B9E77C100816584 /* newmatex.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94B07CBD6C1008493CA /* newmatex.cpp */; };
+		692E740B0B9E77C100816584 /* newmatnl.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94D07CBD6C1008493CA /* newmatnl.cpp */; };
+		692E740C0B9E77C100816584 /* newmatrm.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95007CBD6C1008493CA /* newmatrm.cpp */; };
+		692E740D0B9E77C100816584 /* sort.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95407CBD6C1008493CA /* sort.cpp */; };
+		692E740E0B9E77C100816584 /* submat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95507CBD6C1008493CA /* submat.cpp */; };
+		692E740F0B9E77C100816584 /* svd.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95607CBD6C1008493CA /* svd.cpp */; };
+		692E74100B9E77C100816584 /* Profiler.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95A07CBD6C1008493CA /* Profiler.cc */; };
+		692E74110B9E77C100816584 /* ProjectInterface.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95C07CBD6C1008493CA /* ProjectInterface.cc */; };
+		692E74120B9E77C100816584 /* string_util.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96507CBD6C1008493CA /* string_util.cc */; };
+		692E74130B9E77C100816584 /* TimeET.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96807CBD6C1008493CA /* TimeET.cc */; };
+		692E74140B9E77C100816584 /* WMclass.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96B07CBD6C1008493CA /* WMclass.cc */; };
+		692E74150B9E77C100816584 /* WorldState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96D07CBD6C1008493CA /* WorldState.cc */; };
+		692E74160B9E77C100816584 /* SoundManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97007CBD6C1008493CA /* SoundManager.cc */; };
+		692E74170B9E77C100816584 /* WAV.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97307CBD6C1008493CA /* WAV.cc */; };
+		692E74180B9E77C100816584 /* BallDetectionGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97607CBD6C1008493CA /* BallDetectionGenerator.cc */; };
+		692E74190B9E77C100816584 /* CDTGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97807CBD6C1008493CA /* CDTGenerator.cc */; };
+		692E741A0B9E77C100816584 /* FilterBankGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97F07CBD6C1008493CA /* FilterBankGenerator.cc */; };
+		692E741B0B9E77C100816584 /* InterleavedYUVGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98107CBD6C1008493CA /* InterleavedYUVGenerator.cc */; };
+		692E741C0B9E77C100816584 /* JPEGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98307CBD6C1008493CA /* JPEGGenerator.cc */; };
+		692E741D0B9E77C100816584 /* RawCameraGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98607CBD6C1008493CA /* RawCameraGenerator.cc */; };
+		692E741E0B9E77C100816584 /* RegionGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98807CBD6C1008493CA /* RegionGenerator.cc */; };
+		692E741F0B9E77C100816584 /* RLEGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98A07CBD6C1008493CA /* RLEGenerator.cc */; };
+		692E74200B9E77C100816584 /* SegmentedColorGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98C07CBD6C1008493CA /* SegmentedColorGenerator.cc */; };
+		692E74210B9E77C100816584 /* Socket.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99107CBD6C1008493CA /* Socket.cc */; };
+		692E74220B9E77C100816584 /* Wireless.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99307CBD6C1008493CA /* Wireless.cc */; };
+		692E74230B9E77C100816584 /* SemaphoreManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3CF07D4D35F003A7628 /* SemaphoreManager.cc */; };
+		692E74240B9E77C100816584 /* ProcessID.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D107D4D35F003A7628 /* ProcessID.cc */; };
+		692E74250B9E77C100816584 /* RCRegion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D307D4D35F003A7628 /* RCRegion.cc */; };
+		692E74260B9E77C100816584 /* SharedObject.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D607D4D35F003A7628 /* SharedObject.cc */; };
+		692E74270B9E77C100816584 /* MutexLock.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942757707E0DCDD003DE3D9 /* MutexLock.cc */; };
+		692E74280B9E77C100816584 /* Thread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942779007E164EA003DE3D9 /* Thread.cc */; };
+		692E74290B9E77C100816584 /* write_jpeg.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A323C007E35646009D94E1 /* write_jpeg.cc */; };
+		692E742A0B9E77C100816584 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E666BB07F0CE51005F4FA9 /* plist.cc */; };
+		692E742B0B9E77C100816584 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */; };
+		692E742D0B9E77C100816584 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */; };
+		692E742E0B9E77C100816584 /* EchoBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A1995E080ED8A200540970 /* EchoBehavior.cc */; };
+		692E742F0B9E77C100816584 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.cc */; };
+		692E74300B9E77C100816584 /* StewartPlatformBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69970AC0083DB2760069D95C /* StewartPlatformBehavior.cc */; };
+		692E74310B9E77C100816584 /* UPennWalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F5084C389D0003A261 /* UPennWalkMC.cc */; };
+		692E74320B9E77C100816584 /* Graphics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F9084C38E80003A261 /* Graphics.cc */; };
+		692E74330B9E77C100816584 /* UPennWalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA4901084C39230003A261 /* UPennWalkControllerBehavior.cc */; };
+		692E74340B9E77C100816584 /* MessageReceiver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA7D690860898300185BA2 /* MessageReceiver.cc */; };
+		692E74350B9E77C100816584 /* StareAtPawBehavior2.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B4E445089409D800832D58 /* StareAtPawBehavior2.cc */; };
+		692E74360B9E77C100816584 /* robot.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88407CBD6C0008493CA /* robot.cpp */; };
+		692E74370B9E77C100816584 /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.cc */; };
+		692E74380B9E77C100816584 /* CameraStreamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */; };
+		692E74390B9E77C100816584 /* MCNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6966753B0926558A00405769 /* MCNode.cc */; };
+		692E743A0B9E77C100816584 /* AgentData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6C09AA1D2000D1EC14 /* AgentData.cc */; };
+		692E743B0B9E77C100816584 /* BaseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6E09AA1D2000D1EC14 /* BaseData.cc */; };
+		692E743C0B9E77C100816584 /* BlobData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7009AA1D2000D1EC14 /* BlobData.cc */; };
+		692E743D0B9E77C100816584 /* BrickData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7209AA1D2000D1EC14 /* BrickData.cc */; };
+		692E743E0B9E77C100816584 /* EllipseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7709AA1D2000D1EC14 /* EllipseData.cc */; };
+		692E743F0B9E77C100816584 /* EndPoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7909AA1D2000D1EC14 /* EndPoint.cc */; };
+		692E74400B9E77C100816584 /* LineData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7B09AA1D2000D1EC14 /* LineData.cc */; };
+		692E74410B9E77C100816584 /* Lookout.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7F09AA1D2000D1EC14 /* Lookout.cc */; };
+		692E74420B9E77C100816584 /* MapBuilder.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8209AA1D2000D1EC14 /* MapBuilder.cc */; };
+		692E74430B9E77C100816584 /* ParticleShapes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */; };
+		692E74440B9E77C100816584 /* Point.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8E09AA1D2000D1EC14 /* Point.cc */; };
+		692E74450B9E77C100816584 /* PointData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9009AA1D2000D1EC14 /* PointData.cc */; };
+		692E74460B9E77C100816584 /* PolygonData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9209AA1D2000D1EC14 /* PolygonData.cc */; };
+		692E74470B9E77C100816584 /* Region.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9409AA1D2000D1EC14 /* Region.cc */; };
+		692E74480B9E77C100816584 /* ShapeAgent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */; };
+		692E74490B9E77C100816584 /* ShapeBlob.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */; };
+		692E744A0B9E77C100816584 /* ShapeBrick.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */; };
+		692E744B0B9E77C100816584 /* ShapeEllipse.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */; };
+		692E744C0B9E77C100816584 /* ShapeFuns.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */; };
+		692E744D0B9E77C100816584 /* ShapeLine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA009AA1D2100D1EC14 /* ShapeLine.cc */; };
+		692E744E0B9E77C100816584 /* ShapePoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA209AA1D2100D1EC14 /* ShapePoint.cc */; };
+		692E744F0B9E77C100816584 /* ShapePolygon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */; };
+		692E74500B9E77C100816584 /* ShapeRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */; };
+		692E74510B9E77C100816584 /* ShapeSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */; };
+		692E74520B9E77C100816584 /* ShapeSphere.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */; };
+		692E74540B9E77C100816584 /* Sketch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAE09AA1D2100D1EC14 /* Sketch.cc */; };
+		692E74550B9E77C100816584 /* SketchDataRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */; };
+		692E74560B9E77C100816584 /* SketchIndices.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB309AA1D2100D1EC14 /* SketchIndices.cc */; };
+		692E74570B9E77C100816584 /* SketchRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB609AA1D2100D1EC14 /* SketchRoot.cc */; };
+		692E74580B9E77C100816584 /* SketchSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB809AA1D2100D1EC14 /* SketchSpace.cc */; };
+		692E74590B9E77C100816584 /* SphereData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBB09AA1D2100D1EC14 /* SphereData.cc */; };
+		692E745A0B9E77C100816584 /* susan.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBD09AA1D2100D1EC14 /* susan.cc */; };
+		692E745B0B9E77C100816584 /* ViewerConnection.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */; };
+		692E745C0B9E77C100816584 /* visops.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC109AA1D2100D1EC14 /* visops.cc */; };
+		692E745D0B9E77C100816584 /* VisualRoutinesBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */; };
+		692E745E0B9E77C100816584 /* VRmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A109AAE1C600D1EC14 /* VRmixin.cc */; };
+		692E745F0B9E77C100816584 /* VisualRoutinesStateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */; };
+		692E74600B9E77C100816584 /* MessageQueue.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */; };
+		692E74610B9E77C100816584 /* MessageQueueStatusThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */; };
+		692E74620B9E77C100816584 /* PollThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EBE909C7162E003DDD18 /* PollThread.cc */; };
+		692E74650B9E77C100816584 /* plistPrimitives.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */; };
+		692E74660B9E77C100816584 /* StackTrace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E78D0109F6C114000385E9 /* StackTrace.cc */; };
+		692E74670B9E77C100816584 /* SketchPoolRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */; };
+		692E74680B9E77C100816584 /* jpeg_mem_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */; };
+		692E74690B9E77C100816584 /* Resource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EB5B530A41CCD700415C6B /* Resource.cc */; };
+		692E746A0B9E77C100816584 /* PNGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6900659D0A4EF58700E895F9 /* PNGGenerator.cc */; };
+		692E746B0B9E77C100816584 /* WorldStatePool.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */; };
+		692E746C0B9E77C100816584 /* PyramidData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B344670A7152900021FBE6 /* PyramidData.cc */; };
+		692E746D0B9E77C100816584 /* ShapePyramid.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */; };
+		692E746E0B9E77C100816584 /* BrickOps.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446F0A7152C30021FBE6 /* BrickOps.cc */; };
+		692E746F0B9E77C100816584 /* LookoutEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */; };
+		692E74700B9E77C100816584 /* Aibo3DControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */; };
+		692E74710B9E77C100816584 /* LookoutRequests.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */; };
+		692E74720B9E77C100816584 /* TestBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692964F60AA8CEEF00F47522 /* TestBehaviors.cc */; };
+		692E74730B9E77C100816584 /* TimerEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6901D58D0AAF288500104815 /* TimerEvent.cc */; };
+		692E74740B9E77C100816584 /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */; };
+		692E74750B9E77C100816584 /* PitchEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E67E40AC308290087EC83 /* PitchEvent.cc */; };
+		692E74760B9E77C100816584 /* PitchDetector.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E684B0AC338CF0087EC83 /* PitchDetector.cc */; };
+		692E74770B9E77C100816584 /* LGmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B8DDC00AC44735003EC54A /* LGmixin.cc */; };
+		692E747A0B9E77C100816584 /* colors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6959FAC20B08FF4D006F08BB /* colors.cc */; };
+		692E747B0B9E77C100816584 /* zignor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73230B57E27500FF5476 /* zignor.cc */; };
+		692E747C0B9E77C100816584 /* zigrandom.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73250B57E27500FF5476 /* zigrandom.cc */; };
+		692E747D0B9E77C100816584 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF74820B59EC7200FF5476 /* Measures.cc */; };
+		692E747E0B9E77C100816584 /* HolonomicMotionModel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */; };
+		692E747F0B9E77C100816584 /* ConfigurationEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */; };
+		692E74810B9E77C100816584 /* LocalizationParticleData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984730B8BF72200AB633A /* LocalizationParticleData.cc */; };
+		692E74820B9E77C100816584 /* ShapeLocalizationParticle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */; };
+		692E74830B9E77C100816584 /* Pilot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */; };
+		692E74840B9E77C100816584 /* PilotRequest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */; };
+		692E74850B9E77C100816584 /* PFShapeLocalization.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */; };
+		692E74860B9E77C100816584 /* PFShapeSLAM.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */; };
+		692E74890B9E77C100816584 /* libiconv.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9207EB57480047DA8D /* libiconv.dylib */; };
+		692E748A0B9E77C100816584 /* libxml2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9307EB57480047DA8D /* libxml2.dylib */; };
+		692E748B0B9E77C100816584 /* libz.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9407EB57480047DA8D /* libz.dylib */; };
+		692E748C0B9E77C100816584 /* libjpeg.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43507F48A860071A2AE /* libjpeg.dylib */; };
+		692E748D0B9E77C100816584 /* libpng12.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43607F48A860071A2AE /* libpng12.dylib */; };
+		692E748E0B9E77C100816584 /* libreadline.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */; };
+		692E74AD0B9E7B3A00816584 /* libIce.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74AA0B9E7B3A00816584 /* libIce.dylib */; };
+		692E74AE0B9E7B3A00816584 /* libIceUtil.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74AB0B9E7B3A00816584 /* libIceUtil.dylib */; };
+		692E74E10B9E7CDD00816584 /* ImageCache.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D10B9E7CDD00816584 /* ImageCache.cc */; };
+		692E74E20B9E7CDD00816584 /* ObjectPingThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D30B9E7CDD00816584 /* ObjectPingThread.cc */; };
+		692E74E30B9E7CDD00816584 /* PropertyManagerI.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D50B9E7CDD00816584 /* PropertyManagerI.cc */; };
+		692E74E40B9E7CDD00816584 /* QwerkBot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D70B9E7CDD00816584 /* QwerkBot.cc */; };
+		692E74E70B9E7CDD00816584 /* TerkUserI.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74DD0B9E7CDD00816584 /* TerkUserI.cc */; };
+		692E751F0B9E821800816584 /* MRPLPeer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E751D0B9E821800816584 /* MRPLPeer.cc */; };
+		692E75210B9E825700816584 /* TeRKPeerCommon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74DB0B9E7CDD00816584 /* TeRKPeerCommon.cc */; };
+		6933B7F40C6527B000A23CE9 /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */; };
+		6933B7F50C6527B000A23CE9 /* StartupBehavior_SetupFileAccess.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */; };
+		6933B7F60C6527B000A23CE9 /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
+		6933B7F70C6527B000A23CE9 /* StartupBehavior_SetupStatusReports.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */; };
+		6933B7F80C6527B000A23CE9 /* StartupBehavior_SetupTekkotsuMon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */; };
+		6933B7FA0C6527B000A23CE9 /* StartupBehavior_SetupWalkEdit.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */; };
+		6933B7FB0C6527B100A23CE9 /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */; };
+		6933B7FC0C6527B100A23CE9 /* StartupBehavior_SetupFileAccess.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */; };
+		6933B7FD0C6527B100A23CE9 /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
+		6933B7FE0C6527B100A23CE9 /* StartupBehavior_SetupStatusReports.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */; };
+		6933B7FF0C6527B100A23CE9 /* StartupBehavior_SetupTekkotsuMon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */; };
+		6933B8010C6527B100A23CE9 /* StartupBehavior_SetupWalkEdit.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */; };
+		6933B8810C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */; };
+		6933B8820C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */; };
+		6933B8830C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */; };
+		6933B8840C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */; };
+		6933B8860C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */; };
+		6933BE480C65974300A23CE9 /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */; };
+		6937766D0C17358C001E2C9E /* CameraSourceOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */; };
+		6937766E0C17358C001E2C9E /* CameraSourceOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */; };
+		6937766F0C17358C001E2C9E /* CameraSourceOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */; };
+		693776700C17358C001E2C9E /* CameraSourceOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */; };
+		693776710C17358C001E2C9E /* CameraSourceOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */; };
+		693776740C17359B001E2C9E /* CameraDriverOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693776720C17359B001E2C9E /* CameraDriverOSX.cc */; };
+		693776750C17359B001E2C9E /* CameraDriverOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693776720C17359B001E2C9E /* CameraDriverOSX.cc */; };
+		693776760C17359B001E2C9E /* CameraDriverOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693776720C17359B001E2C9E /* CameraDriverOSX.cc */; };
+		693776770C17359B001E2C9E /* CameraDriverOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693776720C17359B001E2C9E /* CameraDriverOSX.cc */; };
+		693776780C17359B001E2C9E /* CameraDriverOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693776720C17359B001E2C9E /* CameraDriverOSX.cc */; };
+		693776CC0C175812001E2C9E /* Carbon.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776B70C175811001E2C9E /* Carbon.framework */; };
+		693776CD0C175812001E2C9E /* Carbon.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776B70C175811001E2C9E /* Carbon.framework */; };
+		693776CE0C175812001E2C9E /* Carbon.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776B70C175811001E2C9E /* Carbon.framework */; };
+		693776CF0C175812001E2C9E /* Carbon.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776B70C175811001E2C9E /* Carbon.framework */; };
+		693776D00C175812001E2C9E /* Carbon.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776B70C175811001E2C9E /* Carbon.framework */; };
+		693776F50C17581F001E2C9E /* QuickTime.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776D10C17581F001E2C9E /* QuickTime.framework */; };
+		693776F60C17581F001E2C9E /* QuickTime.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776D10C17581F001E2C9E /* QuickTime.framework */; };
+		693776F70C17581F001E2C9E /* QuickTime.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776D10C17581F001E2C9E /* QuickTime.framework */; };
+		693776F80C17581F001E2C9E /* QuickTime.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776D10C17581F001E2C9E /* QuickTime.framework */; };
+		693776F90C17581F001E2C9E /* QuickTime.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776D10C17581F001E2C9E /* QuickTime.framework */; };
+		693A55ED0BE1474500509F85 /* TargetData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55EA0BE1474500509F85 /* TargetData.cc */; };
+		693A55EF0BE1474500509F85 /* TargetData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55EA0BE1474500509F85 /* TargetData.cc */; };
+		693A55F10BE1474500509F85 /* TargetData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55EA0BE1474500509F85 /* TargetData.cc */; };
+		693A55F30BE1474500509F85 /* TargetData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55EA0BE1474500509F85 /* TargetData.cc */; };
+		693A55F60BE1478100509F85 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55F40BE1478000509F85 /* ShapeTypes.cc */; };
+		693A55F70BE1478100509F85 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55F40BE1478000509F85 /* ShapeTypes.cc */; };
+		693A55F80BE1478100509F85 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55F40BE1478000509F85 /* ShapeTypes.cc */; };
+		693A55F90BE1478100509F85 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55F40BE1478000509F85 /* ShapeTypes.cc */; };
+		693A55FC0BE1479800509F85 /* ShapeTarget.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55FA0BE1479800509F85 /* ShapeTarget.cc */; };
+		693A55FD0BE1479800509F85 /* ShapeTarget.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55FA0BE1479800509F85 /* ShapeTarget.cc */; };
+		693A55FE0BE1479800509F85 /* ShapeTarget.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55FA0BE1479800509F85 /* ShapeTarget.cc */; };
+		693A55FF0BE1479800509F85 /* ShapeTarget.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55FA0BE1479800509F85 /* ShapeTarget.cc */; };
+		693AD59B0C205BE80053F7DE /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5880C205BE80053F7DE /* Main.cc */; };
+		693AD59C0C205BE80053F7DE /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58A0C205BE80053F7DE /* Motion.cc */; };
+		693AD59D0C205BE80053F7DE /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58C0C205BE80053F7DE /* MotionExecThread.cc */; };
+		693AD59E0C205BE80053F7DE /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58E0C205BE80053F7DE /* Process.cc */; };
+		693AD59F0C205BE80053F7DE /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5900C205BE80053F7DE /* SharedGlobals.cc */; };
+		693AD5A00C205BE80053F7DE /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5920C205BE80053F7DE /* sim.cc */; };
+		693AD5A10C205BE80053F7DE /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5950C205BE80053F7DE /* Simulator.cc */; };
+		693AD5A20C205BE80053F7DE /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5970C205BE80053F7DE /* SoundPlay.cc */; };
+		693AD5A30C205BE80053F7DE /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5990C205BE80053F7DE /* TimerExecThread.cc */; };
+		693AD5A40C205BE80053F7DE /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5880C205BE80053F7DE /* Main.cc */; };
+		693AD5A50C205BE80053F7DE /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58A0C205BE80053F7DE /* Motion.cc */; };
+		693AD5A60C205BE80053F7DE /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58C0C205BE80053F7DE /* MotionExecThread.cc */; };
+		693AD5A70C205BE80053F7DE /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58E0C205BE80053F7DE /* Process.cc */; };
+		693AD5A80C205BE80053F7DE /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5900C205BE80053F7DE /* SharedGlobals.cc */; };
+		693AD5A90C205BE80053F7DE /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5920C205BE80053F7DE /* sim.cc */; };
+		693AD5AA0C205BE80053F7DE /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5950C205BE80053F7DE /* Simulator.cc */; };
+		693AD5AB0C205BE80053F7DE /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5970C205BE80053F7DE /* SoundPlay.cc */; };
+		693AD5AC0C205BE80053F7DE /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5990C205BE80053F7DE /* TimerExecThread.cc */; };
+		693AD5AD0C205BE80053F7DE /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5880C205BE80053F7DE /* Main.cc */; };
+		693AD5AE0C205BE80053F7DE /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58A0C205BE80053F7DE /* Motion.cc */; };
+		693AD5AF0C205BE80053F7DE /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58C0C205BE80053F7DE /* MotionExecThread.cc */; };
+		693AD5B00C205BE80053F7DE /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58E0C205BE80053F7DE /* Process.cc */; };
+		693AD5B10C205BE80053F7DE /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5900C205BE80053F7DE /* SharedGlobals.cc */; };
+		693AD5B20C205BE80053F7DE /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5920C205BE80053F7DE /* sim.cc */; };
+		693AD5B30C205BE80053F7DE /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5950C205BE80053F7DE /* Simulator.cc */; };
+		693AD5B40C205BE80053F7DE /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5970C205BE80053F7DE /* SoundPlay.cc */; };
+		693AD5B50C205BE80053F7DE /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5990C205BE80053F7DE /* TimerExecThread.cc */; };
+		693AD5B60C205BE80053F7DE /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5880C205BE80053F7DE /* Main.cc */; };
+		693AD5B70C205BE80053F7DE /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58A0C205BE80053F7DE /* Motion.cc */; };
+		693AD5B80C205BE80053F7DE /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58C0C205BE80053F7DE /* MotionExecThread.cc */; };
+		693AD5B90C205BE80053F7DE /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58E0C205BE80053F7DE /* Process.cc */; };
+		693AD5BA0C205BE80053F7DE /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5900C205BE80053F7DE /* SharedGlobals.cc */; };
+		693AD5BB0C205BE80053F7DE /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5920C205BE80053F7DE /* sim.cc */; };
+		693AD5BC0C205BE80053F7DE /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5950C205BE80053F7DE /* Simulator.cc */; };
+		693AD5BD0C205BE80053F7DE /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5970C205BE80053F7DE /* SoundPlay.cc */; };
+		693AD5BE0C205BE80053F7DE /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5990C205BE80053F7DE /* TimerExecThread.cc */; };
+		693AD5BF0C205BE80053F7DE /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5880C205BE80053F7DE /* Main.cc */; };
+		693AD5C00C205BE80053F7DE /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58A0C205BE80053F7DE /* Motion.cc */; };
+		693AD5C10C205BE80053F7DE /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58C0C205BE80053F7DE /* MotionExecThread.cc */; };
+		693AD5C20C205BE80053F7DE /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58E0C205BE80053F7DE /* Process.cc */; };
+		693AD5C30C205BE80053F7DE /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5900C205BE80053F7DE /* SharedGlobals.cc */; };
+		693AD5C40C205BE80053F7DE /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5920C205BE80053F7DE /* sim.cc */; };
+		693AD5C50C205BE80053F7DE /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5950C205BE80053F7DE /* Simulator.cc */; };
+		693AD5C60C205BE80053F7DE /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5970C205BE80053F7DE /* SoundPlay.cc */; };
+		693AD5C70C205BE80053F7DE /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5990C205BE80053F7DE /* TimerExecThread.cc */; };
+		693D09C90C525F7E00A56175 /* jpeg_istream_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */; };
+		693D09CA0C525F7E00A56175 /* jpeg_istream_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */; };
+		693D09CB0C525F7E00A56175 /* jpeg_istream_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */; };
+		693D09CC0C525F7E00A56175 /* jpeg_istream_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */; };
+		693D09E70C52643E00A56175 /* plistBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A071B09575F41001A13D5 /* plistBase.cc */; };
+		693D09E80C52643E00A56175 /* plistCollections.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A072709575F7D001A13D5 /* plistCollections.cc */; };
+		693D09E90C52643E00A56175 /* StartupBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76007CBD4F9008493CA /* StartupBehavior.cc */; };
+		693D09EA0C52643E00A56175 /* BehaviorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78C07CBD6BF008493CA /* BehaviorBase.cc */; };
+		693D09EB0C52643E00A56175 /* Controller.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78F07CBD6BF008493CA /* Controller.cc */; };
+		693D09EC0C52643E00A56175 /* ControlBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79707CBD6BF008493CA /* ControlBase.cc */; };
+		693D09ED0C52643E00A56175 /* EventLogger.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79A07CBD6C0008493CA /* EventLogger.cc */; };
+		693D09EE0C52643E00A56175 /* FileBrowserControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79C07CBD6C0008493CA /* FileBrowserControl.cc */; };
+		693D09EF0C52643E00A56175 /* FreeMemReportControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79F07CBD6C0008493CA /* FreeMemReportControl.cc */; };
+		693D09F00C52643E00A56175 /* HelpControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7A107CBD6C0008493CA /* HelpControl.cc */; };
+		693D09F10C52643E00A56175 /* PostureEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7AA07CBD6C0008493CA /* PostureEditor.cc */; };
+		693D09F20C52643E00A56175 /* RebootControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7AD07CBD6C0008493CA /* RebootControl.cc */; };
+		693D09F30C52643E00A56175 /* SensorObserverControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B207CBD6C0008493CA /* SensorObserverControl.cc */; };
+		693D09F40C52643E00A56175 /* ShutdownControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B407CBD6C0008493CA /* ShutdownControl.cc */; };
+		693D09F50C52643E00A56175 /* StringInputControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B607CBD6C0008493CA /* StringInputControl.cc */; };
+		693D09F60C52643E00A56175 /* WalkCalibration.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7BB07CBD6C0008493CA /* WalkCalibration.cc */; };
+		693D09F70C52643E00A56175 /* WaypointWalkControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7BD07CBD6C0008493CA /* WaypointWalkControl.cc */; };
+		693D09F80C52643E00A56175 /* ASCIIVisionBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C107CBD6C0008493CA /* ASCIIVisionBehavior.cc */; };
+		693D09F90C52643E00A56175 /* ChaseBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */; };
+		693D09FA0C52643E00A56175 /* DriveMeBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CB07CBD6C0008493CA /* DriveMeBehavior.cc */; };
+		693D09FB0C52643E00A56175 /* ExploreMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */; };
+		693D09FC0C52643E00A56175 /* PaceTargetsMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7DD07CBD6C0008493CA /* PaceTargetsMachine.cc */; };
+		693D09FD0C52643E00A56175 /* StareAtBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E207CBD6C0008493CA /* StareAtBallBehavior.cc */; };
+		693D09FE0C52643E00A56175 /* EStopControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7EC07CBD6C0008493CA /* EStopControllerBehavior.cc */; };
+		693D09FF0C52643E00A56175 /* HeadPointControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7EE07CBD6C0008493CA /* HeadPointControllerBehavior.cc */; };
+		693D0A000C52643E00A56175 /* MicrophoneServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F007CBD6C0008493CA /* MicrophoneServer.cc */; };
+		693D0A010C52643E00A56175 /* RawCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F207CBD6C0008493CA /* RawCamBehavior.cc */; };
+		693D0A020C52643E00A56175 /* SegCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F407CBD6C0008493CA /* SegCamBehavior.cc */; };
+		693D0A030C52643E00A56175 /* SpeakerServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */; };
+		693D0A040C52643E00A56175 /* WalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FB07CBD6C0008493CA /* WalkControllerBehavior.cc */; };
+		693D0A050C52643E00A56175 /* WMMonitorBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FD07CBD6C0008493CA /* WMMonitorBehavior.cc */; };
+		693D0A060C52643E00A56175 /* WorldStateSerializerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FF07CBD6C0008493CA /* WorldStateSerializerBehavior.cc */; };
+		693D0A070C52643E00A56175 /* WalkToTargetNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A80B07CBD6C0008493CA /* WalkToTargetNode.cc */; };
+		693D0A080C52643E00A56175 /* StateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A80E07CBD6C0008493CA /* StateNode.cc */; };
+		693D0A090C52643E00A56175 /* Transition.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A81007CBD6C0008493CA /* Transition.cc */; };
+		693D0A0A0C52643E00A56175 /* RandomTrans.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A81807CBD6C0008493CA /* RandomTrans.cc */; };
+		693D0A0B0C52643E00A56175 /* EventBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82007CBD6C0008493CA /* EventBase.cc */; };
+		693D0A0C0C52643E00A56175 /* EventGeneratorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82207CBD6C0008493CA /* EventGeneratorBase.cc */; };
+		693D0A0D0C52643E00A56175 /* EventRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82507CBD6C0008493CA /* EventRouter.cc */; };
+		693D0A0E0C52643E00A56175 /* EventTranslator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82707CBD6C0008493CA /* EventTranslator.cc */; };
+		693D0A0F0C52643E00A56175 /* LocomotionEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82B07CBD6C0008493CA /* LocomotionEvent.cc */; };
+		693D0A100C52643E00A56175 /* TextMsgEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82E07CBD6C0008493CA /* TextMsgEvent.cc */; };
+		693D0A110C52643E00A56175 /* VisionObjectEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83007CBD6C0008493CA /* VisionObjectEvent.cc */; };
+		693D0A120C52643E00A56175 /* EmergencyStopMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83407CBD6C0008493CA /* EmergencyStopMC.cc */; };
+		693D0A130C52643E00A56175 /* HeadPointerMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83807CBD6C0008493CA /* HeadPointerMC.cc */; };
+		693D0A140C52643E00A56175 /* Kinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83A07CBD6C0008493CA /* Kinematics.cc */; };
+		693D0A150C52643E00A56175 /* MotionCommand.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84007CBD6C0008493CA /* MotionCommand.cc */; };
+		693D0A160C52643E00A56175 /* MotionManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84207CBD6C0008493CA /* MotionManager.cc */; };
+		693D0A170C52643E00A56175 /* MotionSequenceEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */; };
+		693D0A180C52643E00A56175 /* OldKinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84A07CBD6C0008493CA /* OldKinematics.cc */; };
+		693D0A190C52643E00A56175 /* OutputCmd.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84C07CBD6C0008493CA /* OutputCmd.cc */; };
+		693D0A1A0C52643E00A56175 /* PostureEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85107CBD6C0008493CA /* PostureEngine.cc */; };
+		693D0A1B0C52643E00A56175 /* PostureMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85307CBD6C0008493CA /* PostureMC.cc */; };
+		693D0A1C0C52643E00A56175 /* clik.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85707CBD6C0008493CA /* clik.cpp */; };
+		693D0A1D0C52643E00A56175 /* comp_dq.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85907CBD6C0008493CA /* comp_dq.cpp */; };
+		693D0A1E0C52643E00A56175 /* comp_dqp.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85A07CBD6C0008493CA /* comp_dqp.cpp */; };
+		693D0A1F0C52643E00A56175 /* config.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85B07CBD6C0008493CA /* config.cpp */; };
+		693D0A200C52643E00A56175 /* control_select.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85D07CBD6C0008493CA /* control_select.cpp */; };
+		693D0A210C52643E00A56175 /* controller.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85F07CBD6C0008493CA /* controller.cpp */; };
+		693D0A220C52643E00A56175 /* delta_t.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86107CBD6C0008493CA /* delta_t.cpp */; };
+		693D0A230C52643E00A56175 /* dynamics.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86207CBD6C0008493CA /* dynamics.cpp */; };
+		693D0A240C52643E00A56175 /* dynamics_sim.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86307CBD6C0008493CA /* dynamics_sim.cpp */; };
+		693D0A250C52643E00A56175 /* gnugraph.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87907CBD6C0008493CA /* gnugraph.cpp */; };
+		693D0A260C52643E00A56175 /* homogen.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87B07CBD6C0008493CA /* homogen.cpp */; };
+		693D0A270C52643E00A56175 /* invkine.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87C07CBD6C0008493CA /* invkine.cpp */; };
+		693D0A280C52643E00A56175 /* kinemat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87D07CBD6C0008493CA /* kinemat.cpp */; };
+		693D0A290C52643E00A56175 /* quaternion.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87F07CBD6C0008493CA /* quaternion.cpp */; };
+		693D0A2A0C52643E00A56175 /* sensitiv.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88607CBD6C0008493CA /* sensitiv.cpp */; };
+		693D0A2B0C52643E00A56175 /* trajectory.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88707CBD6C0008493CA /* trajectory.cpp */; };
+		693D0A2C0C52643E00A56175 /* utils.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88907CBD6C0008493CA /* utils.cpp */; };
+		693D0A2D0C52643E00A56175 /* WalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88D07CBD6C0008493CA /* WalkMC.cc */; };
+		693D0A2E0C52643E00A56175 /* Buffer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89207CBD6C0008493CA /* Buffer.cc */; };
+		693D0A2F0C52643E00A56175 /* Config.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89507CBD6C0008493CA /* Config.cc */; };
+		693D0A300C52643E00A56175 /* get_time.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89D07CBD6C0008493CA /* get_time.cc */; };
+		693D0A310C52643E00A56175 /* jpeg_mem_dest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8DE07CBD6C1008493CA /* jpeg_mem_dest.cc */; };
+		693D0A320C52643E00A56175 /* LoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8F807CBD6C1008493CA /* LoadSave.cc */; };
+		693D0A330C52643E00A56175 /* bandmat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8FE07CBD6C1008493CA /* bandmat.cpp */; };
+		693D0A340C52643E00A56175 /* cholesky.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A90007CBD6C1008493CA /* cholesky.cpp */; };
+		693D0A350C52643E00A56175 /* evalue.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A90707CBD6C1008493CA /* evalue.cpp */; };
+		693D0A360C52643E00A56175 /* fft.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93807CBD6C1008493CA /* fft.cpp */; };
+		693D0A370C52643E00A56175 /* hholder.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93907CBD6C1008493CA /* hholder.cpp */; };
+		693D0A380C52643E00A56175 /* jacobi.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93B07CBD6C1008493CA /* jacobi.cpp */; };
+		693D0A390C52643E00A56175 /* myexcept.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93D07CBD6C1008493CA /* myexcept.cpp */; };
+		693D0A3A0C52643E00A56175 /* newfft.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93F07CBD6C1008493CA /* newfft.cpp */; };
+		693D0A3B0C52643E00A56175 /* newmat1.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94107CBD6C1008493CA /* newmat1.cpp */; };
+		693D0A3C0C52643E00A56175 /* newmat2.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94207CBD6C1008493CA /* newmat2.cpp */; };
+		693D0A3D0C52643E00A56175 /* newmat3.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94307CBD6C1008493CA /* newmat3.cpp */; };
+		693D0A3E0C52643E00A56175 /* newmat4.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94407CBD6C1008493CA /* newmat4.cpp */; };
+		693D0A3F0C52643E00A56175 /* newmat5.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94507CBD6C1008493CA /* newmat5.cpp */; };
+		693D0A400C52643E00A56175 /* newmat6.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94607CBD6C1008493CA /* newmat6.cpp */; };
+		693D0A410C52643E00A56175 /* newmat7.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94707CBD6C1008493CA /* newmat7.cpp */; };
+		693D0A420C52643E00A56175 /* newmat8.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94807CBD6C1008493CA /* newmat8.cpp */; };
+		693D0A430C52643E00A56175 /* newmat9.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94907CBD6C1008493CA /* newmat9.cpp */; };
+		693D0A440C52643E00A56175 /* newmatex.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94B07CBD6C1008493CA /* newmatex.cpp */; };
+		693D0A450C52643E00A56175 /* newmatnl.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94D07CBD6C1008493CA /* newmatnl.cpp */; };
+		693D0A460C52643E00A56175 /* newmatrm.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95007CBD6C1008493CA /* newmatrm.cpp */; };
+		693D0A470C52643E00A56175 /* sort.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95407CBD6C1008493CA /* sort.cpp */; };
+		693D0A480C52643E00A56175 /* submat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95507CBD6C1008493CA /* submat.cpp */; };
+		693D0A490C52643E00A56175 /* svd.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95607CBD6C1008493CA /* svd.cpp */; };
+		693D0A4A0C52643E00A56175 /* Profiler.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95A07CBD6C1008493CA /* Profiler.cc */; };
+		693D0A4B0C52643E00A56175 /* ProjectInterface.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95C07CBD6C1008493CA /* ProjectInterface.cc */; };
+		693D0A4C0C52643E00A56175 /* string_util.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96507CBD6C1008493CA /* string_util.cc */; };
+		693D0A4D0C52643E00A56175 /* TimeET.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96807CBD6C1008493CA /* TimeET.cc */; };
+		693D0A4E0C52643E00A56175 /* WMclass.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96B07CBD6C1008493CA /* WMclass.cc */; };
+		693D0A4F0C52643E00A56175 /* WorldState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96D07CBD6C1008493CA /* WorldState.cc */; };
+		693D0A500C52643E00A56175 /* SoundManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97007CBD6C1008493CA /* SoundManager.cc */; };
+		693D0A510C52643E00A56175 /* WAV.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97307CBD6C1008493CA /* WAV.cc */; };
+		693D0A520C52643E00A56175 /* BallDetectionGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97607CBD6C1008493CA /* BallDetectionGenerator.cc */; };
+		693D0A530C52643E00A56175 /* CDTGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97807CBD6C1008493CA /* CDTGenerator.cc */; };
+		693D0A540C52643E00A56175 /* FilterBankGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97F07CBD6C1008493CA /* FilterBankGenerator.cc */; };
+		693D0A550C52643E00A56175 /* InterleavedYUVGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98107CBD6C1008493CA /* InterleavedYUVGenerator.cc */; };
+		693D0A560C52643E00A56175 /* JPEGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98307CBD6C1008493CA /* JPEGGenerator.cc */; };
+		693D0A570C52643E00A56175 /* RawCameraGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98607CBD6C1008493CA /* RawCameraGenerator.cc */; };
+		693D0A580C52643E00A56175 /* RegionGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98807CBD6C1008493CA /* RegionGenerator.cc */; };
+		693D0A590C52643E00A56175 /* RLEGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98A07CBD6C1008493CA /* RLEGenerator.cc */; };
+		693D0A5A0C52643E00A56175 /* SegmentedColorGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98C07CBD6C1008493CA /* SegmentedColorGenerator.cc */; };
+		693D0A5B0C52643E00A56175 /* Socket.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99107CBD6C1008493CA /* Socket.cc */; };
+		693D0A5C0C52643E00A56175 /* Wireless.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99307CBD6C1008493CA /* Wireless.cc */; };
+		693D0A5D0C52643E00A56175 /* SemaphoreManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3CF07D4D35F003A7628 /* SemaphoreManager.cc */; };
+		693D0A5E0C52643E00A56175 /* ProcessID.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D107D4D35F003A7628 /* ProcessID.cc */; };
+		693D0A5F0C52643E00A56175 /* RCRegion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D307D4D35F003A7628 /* RCRegion.cc */; };
+		693D0A600C52643E00A56175 /* SharedObject.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D607D4D35F003A7628 /* SharedObject.cc */; };
+		693D0A610C52643E00A56175 /* MutexLock.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942757707E0DCDD003DE3D9 /* MutexLock.cc */; };
+		693D0A620C52643E00A56175 /* Thread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942779007E164EA003DE3D9 /* Thread.cc */; };
+		693D0A630C52643E00A56175 /* write_jpeg.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A323C007E35646009D94E1 /* write_jpeg.cc */; };
+		693D0A640C52643E00A56175 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E666BB07F0CE51005F4FA9 /* plist.cc */; };
+		693D0A650C52643E00A56175 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */; };
+		693D0A660C52643E00A56175 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */; };
+		693D0A670C52643E00A56175 /* EchoBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A1995E080ED8A200540970 /* EchoBehavior.cc */; };
+		693D0A680C52643E00A56175 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.cc */; };
+		693D0A690C52643E00A56175 /* StewartPlatformBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69970AC0083DB2760069D95C /* StewartPlatformBehavior.cc */; };
+		693D0A6A0C52643E00A56175 /* UPennWalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F5084C389D0003A261 /* UPennWalkMC.cc */; };
+		693D0A6B0C52643E00A56175 /* Graphics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F9084C38E80003A261 /* Graphics.cc */; };
+		693D0A6C0C52643E00A56175 /* UPennWalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA4901084C39230003A261 /* UPennWalkControllerBehavior.cc */; };
+		693D0A6D0C52643E00A56175 /* MessageReceiver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA7D690860898300185BA2 /* MessageReceiver.cc */; };
+		693D0A6E0C52643E00A56175 /* robot.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88407CBD6C0008493CA /* robot.cpp */; };
+		693D0A6F0C52643E00A56175 /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.cc */; };
+		693D0A700C52643E00A56175 /* CameraStreamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */; };
+		693D0A710C52643E00A56175 /* MCNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6966753B0926558A00405769 /* MCNode.cc */; };
+		693D0A720C52643E00A56175 /* AgentData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6C09AA1D2000D1EC14 /* AgentData.cc */; };
+		693D0A730C52643E00A56175 /* BaseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6E09AA1D2000D1EC14 /* BaseData.cc */; };
+		693D0A740C52643E00A56175 /* BlobData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7009AA1D2000D1EC14 /* BlobData.cc */; };
+		693D0A750C52643E00A56175 /* BrickData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7209AA1D2000D1EC14 /* BrickData.cc */; };
+		693D0A760C52643E00A56175 /* EllipseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7709AA1D2000D1EC14 /* EllipseData.cc */; };
+		693D0A770C52643E00A56175 /* EndPoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7909AA1D2000D1EC14 /* EndPoint.cc */; };
+		693D0A780C52643E00A56175 /* LineData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7B09AA1D2000D1EC14 /* LineData.cc */; };
+		693D0A790C52643E00A56175 /* Lookout.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7F09AA1D2000D1EC14 /* Lookout.cc */; };
+		693D0A7A0C52643E00A56175 /* MapBuilder.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8209AA1D2000D1EC14 /* MapBuilder.cc */; };
+		693D0A7B0C52643E00A56175 /* ParticleShapes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */; };
+		693D0A7C0C52643E00A56175 /* Point.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8E09AA1D2000D1EC14 /* Point.cc */; };
+		693D0A7D0C52643E00A56175 /* PointData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9009AA1D2000D1EC14 /* PointData.cc */; };
+		693D0A7E0C52643E00A56175 /* PolygonData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9209AA1D2000D1EC14 /* PolygonData.cc */; };
+		693D0A7F0C52643E00A56175 /* Region.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9409AA1D2000D1EC14 /* Region.cc */; };
+		693D0A800C52643E00A56175 /* ShapeAgent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */; };
+		693D0A810C52643E00A56175 /* ShapeBlob.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */; };
+		693D0A820C52643E00A56175 /* ShapeBrick.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */; };
+		693D0A830C52643E00A56175 /* ShapeEllipse.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */; };
+		693D0A840C52643E00A56175 /* ShapeFuns.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */; };
+		693D0A850C52643E00A56175 /* ShapeLine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA009AA1D2100D1EC14 /* ShapeLine.cc */; };
+		693D0A860C52643E00A56175 /* ShapePoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA209AA1D2100D1EC14 /* ShapePoint.cc */; };
+		693D0A870C52643E00A56175 /* ShapePolygon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */; };
+		693D0A880C52643E00A56175 /* ShapeRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */; };
+		693D0A890C52643E00A56175 /* ShapeSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */; };
+		693D0A8A0C52643E00A56175 /* ShapeSphere.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */; };
+		693D0A8B0C52643E00A56175 /* Sketch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAE09AA1D2100D1EC14 /* Sketch.cc */; };
+		693D0A8C0C52643E00A56175 /* SketchDataRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */; };
+		693D0A8D0C52643E00A56175 /* SketchIndices.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB309AA1D2100D1EC14 /* SketchIndices.cc */; };
+		693D0A8E0C52643E00A56175 /* SketchRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB609AA1D2100D1EC14 /* SketchRoot.cc */; };
+		693D0A8F0C52643E00A56175 /* SketchSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB809AA1D2100D1EC14 /* SketchSpace.cc */; };
+		693D0A900C52643E00A56175 /* SphereData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBB09AA1D2100D1EC14 /* SphereData.cc */; };
+		693D0A910C52643E00A56175 /* susan.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBD09AA1D2100D1EC14 /* susan.cc */; };
+		693D0A920C52643E00A56175 /* ViewerConnection.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */; };
+		693D0A930C52643E00A56175 /* visops.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC109AA1D2100D1EC14 /* visops.cc */; };
+		693D0A940C52643E00A56175 /* VisualRoutinesBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */; };
+		693D0A950C52643E00A56175 /* VRmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A109AAE1C600D1EC14 /* VRmixin.cc */; };
+		693D0A960C52643E00A56175 /* VisualRoutinesStateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */; };
+		693D0A970C52643E00A56175 /* MessageQueue.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */; };
+		693D0A980C52643E00A56175 /* MessageQueueStatusThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */; };
+		693D0A990C52643E00A56175 /* PollThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EBE909C7162E003DDD18 /* PollThread.cc */; };
+		693D0A9A0C52643E00A56175 /* plistPrimitives.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */; };
+		693D0A9B0C52643E00A56175 /* StackTrace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E78D0109F6C114000385E9 /* StackTrace.cc */; };
+		693D0A9C0C52643E00A56175 /* SketchPoolRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */; };
+		693D0A9D0C52643E00A56175 /* jpeg_mem_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */; };
+		693D0A9E0C52643E00A56175 /* Resource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EB5B530A41CCD700415C6B /* Resource.cc */; };
+		693D0A9F0C52643E00A56175 /* PNGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6900659D0A4EF58700E895F9 /* PNGGenerator.cc */; };
+		693D0AA00C52643E00A56175 /* WorldStatePool.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */; };
+		693D0AA10C52643E00A56175 /* PyramidData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B344670A7152900021FBE6 /* PyramidData.cc */; };
+		693D0AA20C52643E00A56175 /* ShapePyramid.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */; };
+		693D0AA30C52643E00A56175 /* BrickOps.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446F0A7152C30021FBE6 /* BrickOps.cc */; };
+		693D0AA40C52643E00A56175 /* LookoutEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */; };
+		693D0AA50C52643E00A56175 /* Aibo3DControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */; };
+		693D0AA60C52643E00A56175 /* LookoutRequests.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */; };
+		693D0AA70C52643E00A56175 /* TestBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692964F60AA8CEEF00F47522 /* TestBehaviors.cc */; };
+		693D0AA80C52643E00A56175 /* TimerEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6901D58D0AAF288500104815 /* TimerEvent.cc */; };
+		693D0AA90C52643E00A56175 /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */; };
+		693D0AAA0C52643E00A56175 /* PitchEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E67E40AC308290087EC83 /* PitchEvent.cc */; };
+		693D0AAB0C52643E00A56175 /* PitchDetector.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E684B0AC338CF0087EC83 /* PitchDetector.cc */; };
+		693D0AAC0C52643E00A56175 /* LGmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B8DDC00AC44735003EC54A /* LGmixin.cc */; };
+		693D0AAD0C52643E00A56175 /* colors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6959FAC20B08FF4D006F08BB /* colors.cc */; };
+		693D0AAE0C52643E00A56175 /* CameraBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C607CBD6C0008493CA /* CameraBehavior.cc */; };
+		693D0AAF0C52643E00A56175 /* FollowHeadBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7D107CBD6C0008493CA /* FollowHeadBehavior.cc */; };
+		693D0AB00C52643E00A56175 /* WallTestBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E707CBD6C0008493CA /* WallTestBehavior.cc */; };
+		693D0AB20C52643E00A56175 /* LedEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83C07CBD6C0008493CA /* LedEngine.cc */; };
+		693D0AB30C52643E00A56175 /* zignor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73230B57E27500FF5476 /* zignor.cc */; };
+		693D0AB40C52643E00A56175 /* zigrandom.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73250B57E27500FF5476 /* zigrandom.cc */; };
+		693D0AB50C52643E00A56175 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF74820B59EC7200FF5476 /* Measures.cc */; };
+		693D0AB60C52643E00A56175 /* LocalizationParticleData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984730B8BF72200AB633A /* LocalizationParticleData.cc */; };
+		693D0AB70C52643E00A56175 /* PFShapeLocalization.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */; };
+		693D0AB80C52643E00A56175 /* PFShapeSLAM.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */; };
+		693D0AB90C52643E00A56175 /* Pilot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */; };
+		693D0ABA0C52643E00A56175 /* ShapeLocalizationParticle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */; };
+		693D0ABB0C52643E00A56175 /* HolonomicMotionModel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */; };
+		693D0ABC0C52643E00A56175 /* ConfigurationEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */; };
+		693D0ABD0C52643E00A56175 /* PilotRequest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */; };
+		693D0ABF0C52643E00A56175 /* TorqueCalibrate.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */; };
+		693D0AC00C52643E00A56175 /* ImageUtil.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */; };
+		693D0AC10C52643E00A56175 /* LoadDataThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */; };
+		693D0AC20C52643E00A56175 /* SoundPlayThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */; };
+		693D0AC30C52643E00A56175 /* TargetData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55EA0BE1474500509F85 /* TargetData.cc */; };
+		693D0AC40C52643E00A56175 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55F40BE1478000509F85 /* ShapeTypes.cc */; };
+		693D0AC50C52643E00A56175 /* ShapeTarget.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693A55FA0BE1479800509F85 /* ShapeTarget.cc */; };
+		693D0AC60C52643E00A56175 /* netstream.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE64950BF979A800BC9A15 /* netstream.cc */; };
+		693D0AC70C52643E00A56175 /* ExecutableCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C870C1291F000FE900C /* ExecutableCommPort.cc */; };
+		693D0AC80C52643E00A56175 /* FileSystemCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C890C1291F000FE900C /* FileSystemCommPort.cc */; };
+		693D0AC90C52643E00A56175 /* NetworkCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8B0C1291F000FE900C /* NetworkCommPort.cc */; };
+		693D0ACA0C52643E00A56175 /* RedirectionCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */; };
+		693D0ACB0C52643E00A56175 /* SerialCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8F0C1291F000FE900C /* SerialCommPort.cc */; };
+		693D0ACC0C52643E00A56175 /* FileSystemDataSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA60C12922400FE900C /* FileSystemDataSource.cc */; };
+		693D0ACD0C52643E00A56175 /* FileSystemImageSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA80C12922400FE900C /* FileSystemImageSource.cc */; };
+		693D0ACE0C52643E00A56175 /* LoggedDataDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAB0C12922400FE900C /* LoggedDataDriver.cc */; };
+		693D0ACF0C52643E00A56175 /* SSC32Driver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAD0C12922400FE900C /* SSC32Driver.cc */; };
+		693D0AD00C52643E00A56175 /* IPCMotionHook.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CB00C12922400FE900C /* IPCMotionHook.cc */; };
+		693D0AD20C52643E00A56175 /* ImageCache.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D10B9E7CDD00816584 /* ImageCache.cc */; };
+		693D0AD30C52643E00A56175 /* ObjectPingThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D30B9E7CDD00816584 /* ObjectPingThread.cc */; };
+		693D0AD40C52643E00A56175 /* PropertyManagerI.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D50B9E7CDD00816584 /* PropertyManagerI.cc */; };
+		693D0AD50C52643E00A56175 /* QwerkBot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D70B9E7CDD00816584 /* QwerkBot.cc */; };
+		693D0AD60C52643E00A56175 /* SerialIO.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69CB303D0BCED185002F46DC /* SerialIO.cc */; };
+		693D0AD70C52643E00A56175 /* TeRKPeerCommon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74DB0B9E7CDD00816584 /* TeRKPeerCommon.cc */; };
+		693D0AD80C52643E00A56175 /* TerkUserI.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74DD0B9E7CDD00816584 /* TerkUserI.cc */; };
+		693D0AD90C52643E00A56175 /* CameraSourceOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */; };
+		693D0ADA0C52643E00A56175 /* CameraDriverOSX.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693776720C17359B001E2C9E /* CameraDriverOSX.cc */; };
+		693D0ADB0C52643E00A56175 /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5880C205BE80053F7DE /* Main.cc */; };
+		693D0ADC0C52643E00A56175 /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58A0C205BE80053F7DE /* Motion.cc */; };
+		693D0ADD0C52643E00A56175 /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58C0C205BE80053F7DE /* MotionExecThread.cc */; };
+		693D0ADE0C52643E00A56175 /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD58E0C205BE80053F7DE /* Process.cc */; };
+		693D0ADF0C52643E00A56175 /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5900C205BE80053F7DE /* SharedGlobals.cc */; };
+		693D0AE00C52643E00A56175 /* sim.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5920C205BE80053F7DE /* sim.cc */; };
+		693D0AE10C52643E00A56175 /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5950C205BE80053F7DE /* Simulator.cc */; };
+		693D0AE20C52643E00A56175 /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5970C205BE80053F7DE /* SoundPlay.cc */; };
+		693D0AE30C52643E00A56175 /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693AD5990C205BE80053F7DE /* TimerExecThread.cc */; };
+		693D0AE40C52643E00A56175 /* RobotInfo.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE86B00C2F72440046EEAD /* RobotInfo.cc */; };
+		693D0AE50C52643E00A56175 /* jpeg_istream_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */; };
+		693D0AE70C52643E00A56175 /* libiconv.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9207EB57480047DA8D /* libiconv.dylib */; };
+		693D0AE80C52643E00A56175 /* libxml2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9307EB57480047DA8D /* libxml2.dylib */; };
+		693D0AE90C52643E00A56175 /* libz.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9407EB57480047DA8D /* libz.dylib */; };
+		693D0AEA0C52643E00A56175 /* libjpeg.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43507F48A860071A2AE /* libjpeg.dylib */; };
+		693D0AEB0C52643E00A56175 /* libpng12.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43607F48A860071A2AE /* libpng12.dylib */; };
+		693D0AEC0C52643E00A56175 /* libreadline.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */; };
+		693D0AED0C52643E00A56175 /* libGlacier2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74A90B9E7B3A00816584 /* libGlacier2.dylib */; };
+		693D0AEE0C52643E00A56175 /* libIce.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74AA0B9E7B3A00816584 /* libIce.dylib */; };
+		693D0AEF0C52643E00A56175 /* libIceUtil.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74AB0B9E7B3A00816584 /* libIceUtil.dylib */; };
+		693D0AF00C52643E00A56175 /* Carbon.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776B70C175811001E2C9E /* Carbon.framework */; };
+		693D0AF10C52643E00A56175 /* QuickTime.framework in Frameworks */ = {isa = PBXBuildFile; fileRef = 693776D10C17581F001E2C9E /* QuickTime.framework */; };
+		693D0B1C0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */; };
+		693D0B1D0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */; };
+		693D0B1E0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */; };
+		693D0B1F0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */; };
+		693D0C6A0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */; };
+		693D0C6B0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */; };
+		693D0C6C0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */; };
+		693D0C6D0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */; };
+		693D0C790C53036300A56175 /* RoverControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */; };
+		693D0C990C5304CA00A56175 /* ImageStreamDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */; };
+		693D0E560C56632100A56175 /* TeRKDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E540C56632100A56175 /* TeRKDriver.cc */; };
+		693D0E570C56632100A56175 /* TeRKDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E540C56632100A56175 /* TeRKDriver.cc */; };
+		693D0E580C56632100A56175 /* TeRKDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E540C56632100A56175 /* TeRKDriver.cc */; };
+		693D0E590C56632100A56175 /* TeRKDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E540C56632100A56175 /* TeRKDriver.cc */; };
+		693D0E5A0C56632100A56175 /* TeRKDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E540C56632100A56175 /* TeRKDriver.cc */; };
+		693D0E7C0C572C4C00A56175 /* DataCache.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E7A0C572C4C00A56175 /* DataCache.cc */; };
+		693D0E7D0C572C4C00A56175 /* DataCache.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E7A0C572C4C00A56175 /* DataCache.cc */; };
+		693D0E800C572C4C00A56175 /* DataCache.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D0E7A0C572C4C00A56175 /* DataCache.cc */; };
+		693D23ED0C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */; };
+		693D23EE0C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */; };
+		693D23EF0C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */; };
+		693D23F00C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */; };
+		693D23F10C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */; };
 		693D801408ABF46D00AC993E /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.cc */; };
 		693D801508ABF46D00AC993E /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.cc */; };
+		69401C910C1291F000FE900C /* ExecutableCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C870C1291F000FE900C /* ExecutableCommPort.cc */; };
+		69401C920C1291F000FE900C /* FileSystemCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C890C1291F000FE900C /* FileSystemCommPort.cc */; };
+		69401C930C1291F000FE900C /* NetworkCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8B0C1291F000FE900C /* NetworkCommPort.cc */; };
+		69401C940C1291F000FE900C /* RedirectionCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */; };
+		69401C950C1291F000FE900C /* SerialCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8F0C1291F000FE900C /* SerialCommPort.cc */; };
+		69401C960C1291F000FE900C /* ExecutableCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C870C1291F000FE900C /* ExecutableCommPort.cc */; };
+		69401C970C1291F000FE900C /* FileSystemCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C890C1291F000FE900C /* FileSystemCommPort.cc */; };
+		69401C980C1291F000FE900C /* NetworkCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8B0C1291F000FE900C /* NetworkCommPort.cc */; };
+		69401C990C1291F000FE900C /* RedirectionCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */; };
+		69401C9A0C1291F000FE900C /* SerialCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8F0C1291F000FE900C /* SerialCommPort.cc */; };
+		69401C9B0C1291F000FE900C /* ExecutableCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C870C1291F000FE900C /* ExecutableCommPort.cc */; };
+		69401C9C0C1291F000FE900C /* FileSystemCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C890C1291F000FE900C /* FileSystemCommPort.cc */; };
+		69401C9D0C1291F000FE900C /* NetworkCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8B0C1291F000FE900C /* NetworkCommPort.cc */; };
+		69401C9E0C1291F000FE900C /* RedirectionCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */; };
+		69401C9F0C1291F000FE900C /* SerialCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8F0C1291F000FE900C /* SerialCommPort.cc */; };
+		69401CA00C1291F000FE900C /* ExecutableCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C870C1291F000FE900C /* ExecutableCommPort.cc */; };
+		69401CA10C1291F000FE900C /* FileSystemCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C890C1291F000FE900C /* FileSystemCommPort.cc */; };
+		69401CA20C1291F000FE900C /* NetworkCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8B0C1291F000FE900C /* NetworkCommPort.cc */; };
+		69401CA30C1291F000FE900C /* RedirectionCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */; };
+		69401CA40C1291F000FE900C /* SerialCommPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401C8F0C1291F000FE900C /* SerialCommPort.cc */; };
+		69401CB20C12922400FE900C /* FileSystemDataSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA60C12922400FE900C /* FileSystemDataSource.cc */; };
+		69401CB30C12922400FE900C /* FileSystemImageSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA80C12922400FE900C /* FileSystemImageSource.cc */; };
+		69401CB40C12922400FE900C /* LoggedDataDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAB0C12922400FE900C /* LoggedDataDriver.cc */; };
+		69401CB50C12922400FE900C /* SSC32Driver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAD0C12922400FE900C /* SSC32Driver.cc */; };
+		69401CB60C12922400FE900C /* IPCMotionHook.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CB00C12922400FE900C /* IPCMotionHook.cc */; };
+		69401CB70C12922400FE900C /* FileSystemDataSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA60C12922400FE900C /* FileSystemDataSource.cc */; };
+		69401CB80C12922400FE900C /* FileSystemImageSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA80C12922400FE900C /* FileSystemImageSource.cc */; };
+		69401CB90C12922400FE900C /* LoggedDataDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAB0C12922400FE900C /* LoggedDataDriver.cc */; };
+		69401CBA0C12922400FE900C /* SSC32Driver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAD0C12922400FE900C /* SSC32Driver.cc */; };
+		69401CBB0C12922400FE900C /* IPCMotionHook.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CB00C12922400FE900C /* IPCMotionHook.cc */; };
+		69401CBC0C12922400FE900C /* FileSystemDataSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA60C12922400FE900C /* FileSystemDataSource.cc */; };
+		69401CBD0C12922400FE900C /* FileSystemImageSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA80C12922400FE900C /* FileSystemImageSource.cc */; };
+		69401CBE0C12922400FE900C /* LoggedDataDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAB0C12922400FE900C /* LoggedDataDriver.cc */; };
+		69401CBF0C12922400FE900C /* SSC32Driver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAD0C12922400FE900C /* SSC32Driver.cc */; };
+		69401CC00C12922400FE900C /* IPCMotionHook.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CB00C12922400FE900C /* IPCMotionHook.cc */; };
+		69401CC10C12922400FE900C /* FileSystemDataSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA60C12922400FE900C /* FileSystemDataSource.cc */; };
+		69401CC20C12922400FE900C /* FileSystemImageSource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CA80C12922400FE900C /* FileSystemImageSource.cc */; };
+		69401CC30C12922400FE900C /* LoggedDataDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAB0C12922400FE900C /* LoggedDataDriver.cc */; };
+		69401CC40C12922400FE900C /* SSC32Driver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CAD0C12922400FE900C /* SSC32Driver.cc */; };
+		69401CC50C12922400FE900C /* IPCMotionHook.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69401CB00C12922400FE900C /* IPCMotionHook.cc */; };
+		69401DBD0C131EBD00FE900C /* libGlacier2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74A90B9E7B3A00816584 /* libGlacier2.dylib */; };
+		69401DC00C131EC600FE900C /* libIce.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74AA0B9E7B3A00816584 /* libIce.dylib */; };
+		69401DC10C131EC600FE900C /* libIceUtil.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74AB0B9E7B3A00816584 /* libIceUtil.dylib */; };
+		69401DCD0C131F0400FE900C /* ImageCache.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D10B9E7CDD00816584 /* ImageCache.cc */; };
+		69401DCE0C131F0400FE900C /* ObjectPingThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D30B9E7CDD00816584 /* ObjectPingThread.cc */; };
+		69401DCF0C131F0400FE900C /* PropertyManagerI.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D50B9E7CDD00816584 /* PropertyManagerI.cc */; };
+		69401DD00C131F0400FE900C /* QwerkBot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74D70B9E7CDD00816584 /* QwerkBot.cc */; };
+		69401DD10C131F0400FE900C /* SerialIO.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69CB303D0BCED185002F46DC /* SerialIO.cc */; };
+		69401DD20C131F0400FE900C /* TeRKPeerCommon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74DB0B9E7CDD00816584 /* TeRKPeerCommon.cc */; };
+		69401DD30C131F0400FE900C /* TerkUserI.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692E74DD0B9E7CDD00816584 /* TerkUserI.cc */; };
+		694252170CC7E65B00129C8D /* Dynamixel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694252150CC7E65B00129C8D /* Dynamixel.cc */; };
+		694252180CC7E65B00129C8D /* Dynamixel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694252150CC7E65B00129C8D /* Dynamixel.cc */; };
+		694252190CC7E65B00129C8D /* Dynamixel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694252150CC7E65B00129C8D /* Dynamixel.cc */; };
+		6942521A0CC7E65B00129C8D /* Dynamixel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694252150CC7E65B00129C8D /* Dynamixel.cc */; };
+		6942521B0CC7E65B00129C8D /* Dynamixel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694252150CC7E65B00129C8D /* Dynamixel.cc */; };
+		6942525F0CC7EB2300129C8D /* SerialPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942525C0CC7EB2300129C8D /* SerialPort.cc */; };
+		694252610CC7EB2300129C8D /* SerialPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942525C0CC7EB2300129C8D /* SerialPort.cc */; };
+		694252630CC7EB2300129C8D /* SerialPort.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942525C0CC7EB2300129C8D /* SerialPort.cc */; };
 		6942757807E0DCDD003DE3D9 /* MutexLock.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942757707E0DCDD003DE3D9 /* MutexLock.cc */; };
 		6942757907E0DCDD003DE3D9 /* MutexLock.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942757707E0DCDD003DE3D9 /* MutexLock.cc */; };
 		6942779107E164EA003DE3D9 /* Thread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942779007E164EA003DE3D9 /* Thread.cc */; };
@@ -33,9 +724,6 @@
 		69469FCF09AA1D2100D1EC14 /* LineData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7B09AA1D2000D1EC14 /* LineData.cc */; };
 		69469FD109AA1D2100D1EC14 /* Lookout.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7F09AA1D2000D1EC14 /* Lookout.cc */; };
 		69469FD209AA1D2100D1EC14 /* MapBuilder.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8209AA1D2000D1EC14 /* MapBuilder.cc */; };
-		69469FD309AA1D2100D1EC14 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8409AA1D2000D1EC14 /* Measures.cc */; };
-		69469FD409AA1D2100D1EC14 /* Particle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8609AA1D2000D1EC14 /* Particle.cc */; };
-		69469FD509AA1D2100D1EC14 /* ParticleFilter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8809AA1D2000D1EC14 /* ParticleFilter.cc */; };
 		69469FD609AA1D2100D1EC14 /* ParticleShapes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */; };
 		69469FD809AA1D2100D1EC14 /* Point.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8E09AA1D2000D1EC14 /* Point.cc */; };
 		69469FD909AA1D2100D1EC14 /* PointData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9009AA1D2000D1EC14 /* PointData.cc */; };
@@ -52,7 +740,6 @@
 		69469FE409AA1D2100D1EC14 /* ShapeRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */; };
 		69469FE509AA1D2100D1EC14 /* ShapeSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */; };
 		69469FE609AA1D2100D1EC14 /* ShapeSphere.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */; };
-		69469FE709AA1D2100D1EC14 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAC09AA1D2100D1EC14 /* ShapeTypes.cc */; };
 		69469FE809AA1D2100D1EC14 /* Sketch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAE09AA1D2100D1EC14 /* Sketch.cc */; };
 		69469FE909AA1D2100D1EC14 /* SketchDataRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */; };
 		69469FEA09AA1D2100D1EC14 /* SketchIndices.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB309AA1D2100D1EC14 /* SketchIndices.cc */; };
@@ -72,9 +759,6 @@
 		69469FFA09AA1D2100D1EC14 /* LineData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7B09AA1D2000D1EC14 /* LineData.cc */; };
 		69469FFC09AA1D2100D1EC14 /* Lookout.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7F09AA1D2000D1EC14 /* Lookout.cc */; };
 		69469FFD09AA1D2100D1EC14 /* MapBuilder.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8209AA1D2000D1EC14 /* MapBuilder.cc */; };
-		69469FFE09AA1D2100D1EC14 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8409AA1D2000D1EC14 /* Measures.cc */; };
-		69469FFF09AA1D2100D1EC14 /* Particle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8609AA1D2000D1EC14 /* Particle.cc */; };
-		6946A00009AA1D2100D1EC14 /* ParticleFilter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8809AA1D2000D1EC14 /* ParticleFilter.cc */; };
 		6946A00109AA1D2100D1EC14 /* ParticleShapes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */; };
 		6946A00309AA1D2100D1EC14 /* Point.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8E09AA1D2000D1EC14 /* Point.cc */; };
 		6946A00409AA1D2100D1EC14 /* PointData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9009AA1D2000D1EC14 /* PointData.cc */; };
@@ -91,7 +775,6 @@
 		6946A00F09AA1D2100D1EC14 /* ShapeRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */; };
 		6946A01009AA1D2100D1EC14 /* ShapeSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */; };
 		6946A01109AA1D2100D1EC14 /* ShapeSphere.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */; };
-		6946A01209AA1D2100D1EC14 /* ShapeTypes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAC09AA1D2100D1EC14 /* ShapeTypes.cc */; };
 		6946A01309AA1D2100D1EC14 /* Sketch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAE09AA1D2100D1EC14 /* Sketch.cc */; };
 		6946A01409AA1D2100D1EC14 /* SketchDataRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */; };
 		6946A01509AA1D2100D1EC14 /* SketchIndices.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB309AA1D2100D1EC14 /* SketchIndices.cc */; };
@@ -122,8 +805,19 @@
 		694E68580AC33A130087EC83 /* PitchDetector.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E684B0AC338CF0087EC83 /* PitchDetector.cc */; };
 		6958D68B0A5EE5AB00D46050 /* WorldStatePool.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */; };
 		6958D68C0A5EE5AB00D46050 /* WorldStatePool.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */; };
+		695984750B8BF72200AB633A /* LocalizationParticleData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984730B8BF72200AB633A /* LocalizationParticleData.cc */; };
+		695984760B8BF72200AB633A /* LocalizationParticleData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984730B8BF72200AB633A /* LocalizationParticleData.cc */; };
+		6959847A0B8BF76800AB633A /* ShapeLocalizationParticle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */; };
+		6959847B0B8BF76800AB633A /* ShapeLocalizationParticle.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */; };
+		6959FAC30B08FF4D006F08BB /* colors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6959FAC20B08FF4D006F08BB /* colors.cc */; };
+		6959FAC40B08FF4D006F08BB /* colors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6959FAC20B08FF4D006F08BB /* colors.cc */; };
 		695F1ACA0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */; };
 		695F1ACB0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */; };
+		695FCB330CE8BFBD00069A68 /* PathPlanner.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695FCB310CE8BFBD00069A68 /* PathPlanner.cc */; };
+		695FCB340CE8BFBD00069A68 /* PathPlanner.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695FCB310CE8BFBD00069A68 /* PathPlanner.cc */; };
+		695FCB350CE8BFBD00069A68 /* PathPlanner.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695FCB310CE8BFBD00069A68 /* PathPlanner.cc */; };
+		695FCB360CE8BFBD00069A68 /* PathPlanner.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695FCB310CE8BFBD00069A68 /* PathPlanner.cc */; };
+		695FCB370CE8BFBD00069A68 /* PathPlanner.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695FCB310CE8BFBD00069A68 /* PathPlanner.cc */; };
 		6962F2EB0A917E33002DDEC9 /* LookoutEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */; };
 		6962F2EC0A917E33002DDEC9 /* LookoutEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */; };
 		6962F2EF0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */; };
@@ -134,10 +828,8 @@
 		6966753D0926558A00405769 /* MCNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6966753B0926558A00405769 /* MCNode.cc */; };
 		69750F080AC03FFE004FE3CF /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */; };
 		69750F090AC03FFE004FE3CF /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */; };
-		6976B2130ACC669F00BA657B /* LoadFileThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6976B20F0ACC669F00BA657B /* LoadFileThread.cc */; };
-		6976B2140ACC66A000BA657B /* LoadImageThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6976B2110ACC669F00BA657B /* LoadImageThread.cc */; };
-		6976B2150ACC66A000BA657B /* LoadFileThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6976B20F0ACC669F00BA657B /* LoadFileThread.cc */; };
-		6976B2160ACC66A000BA657B /* LoadImageThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6976B2110ACC669F00BA657B /* LoadImageThread.cc */; };
+		6975CDD00B6D67B800B2FAC9 /* ConfigurationEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */; };
+		6975CDD10B6D67B800B2FAC9 /* ConfigurationEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */; };
 		69844A2C08CE5F7F00BCDD5C /* CameraStreamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */; };
 		69844A2D08CE5F7F00BCDD5C /* CameraStreamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */; };
 		698A071D09575F41001A13D5 /* plistBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A071B09575F41001A13D5 /* plistBase.cc */; };
@@ -158,15 +850,25 @@
 		69A19960080ED8A200540970 /* EchoBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A1995E080ED8A200540970 /* EchoBehavior.cc */; };
 		69A323C207E3564F009D94E1 /* write_jpeg.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A323C007E35646009D94E1 /* write_jpeg.cc */; };
 		69A323C507E35665009D94E1 /* write_jpeg.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A323C007E35646009D94E1 /* write_jpeg.cc */; };
-		69A6D6DB07CD7C9500CB4720 /* libstdc++.a in Frameworks */ = {isa = PBXBuildFile; fileRef = 0249A663FF388D9811CA2CEA /* libstdc++.a */; };
+		69A5E2370BBD6CC8006D6EED /* ImageUtil.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */; };
+		69A5E2380BBD6CC8006D6EED /* ImageUtil.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */; };
+		69A5E2390BBD6CC8006D6EED /* ImageUtil.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */; };
+		69A5E23A0BBD6CC8006D6EED /* ImageUtil.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */; };
+		69A5E2FE0BBD9C37006D6EED /* LoadDataThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */; };
+		69A5E3010BBD9C37006D6EED /* SoundPlayThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */; };
+		69A5E3060BBD9C37006D6EED /* LoadDataThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */; };
+		69A5E3090BBD9C37006D6EED /* SoundPlayThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */; };
+		69A5E30E0BBD9C37006D6EED /* LoadDataThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */; };
+		69A5E3110BBD9C37006D6EED /* SoundPlayThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */; };
+		69A5E3160BBD9C37006D6EED /* LoadDataThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */; };
+		69A5E3190BBD9C37006D6EED /* SoundPlayThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */; };
+		69A6E5DD0CDA51BE00039162 /* CreateDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */; };
+		69A6E5DE0CDA51BE00039162 /* CreateDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */; };
+		69A6E5DF0CDA51BE00039162 /* CreateDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */; };
+		69A6E5E00CDA51BE00039162 /* CreateDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */; };
+		69A6E5E10CDA51BE00039162 /* CreateDriver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */; };
 		69A7EBEB09C7162E003DDD18 /* PollThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EBE909C7162E003DDD18 /* PollThread.cc */; };
 		69A7EBEC09C7162E003DDD18 /* PollThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EBE909C7162E003DDD18 /* PollThread.cc */; };
-		69A7EC7B09C79817003DDD18 /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EC7909C79817003DDD18 /* TimerExecThread.cc */; };
-		69A7EC7C09C79818003DDD18 /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EC7909C79817003DDD18 /* TimerExecThread.cc */; };
-		69A7EC7D09C79818003DDD18 /* TimerExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EC7909C79817003DDD18 /* TimerExecThread.cc */; };
-		69A7ED9B09C88623003DDD18 /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7ED9909C88622003DDD18 /* MotionExecThread.cc */; };
-		69A7ED9C09C88623003DDD18 /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7ED9909C88622003DDD18 /* MotionExecThread.cc */; };
-		69A7ED9D09C88623003DDD18 /* MotionExecThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7ED9909C88622003DDD18 /* MotionExecThread.cc */; };
 		69A7EE7009C8F70C003DDD18 /* libreadline.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */; };
 		69A7EE7109C8F70C003DDD18 /* libreadline.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */; };
 		69A7EE7209C8F70C003DDD18 /* libreadline.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */; };
@@ -174,6 +876,26 @@
 		69A7EF2909C9EA77003DDD18 /* plistPrimitives.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */; };
 		69AA7D6B0860898300185BA2 /* MessageReceiver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA7D690860898300185BA2 /* MessageReceiver.cc */; };
 		69AA7D6C0860898300185BA2 /* MessageReceiver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA7D690860898300185BA2 /* MessageReceiver.cc */; };
+		69AA822C0CC19CEE00DD162A /* RemoteEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82280CC19CEE00DD162A /* RemoteEvents.cc */; };
+		69AA822D0CC19CEE00DD162A /* RemoteRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */; };
+		69AA822E0CC19CEE00DD162A /* RemoteEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82280CC19CEE00DD162A /* RemoteEvents.cc */; };
+		69AA822F0CC19CEE00DD162A /* RemoteRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */; };
+		69AA82300CC19CEE00DD162A /* RemoteEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82280CC19CEE00DD162A /* RemoteEvents.cc */; };
+		69AA82310CC19CEE00DD162A /* RemoteRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */; };
+		69AA82320CC19CEE00DD162A /* RemoteEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82280CC19CEE00DD162A /* RemoteEvents.cc */; };
+		69AA82330CC19CEE00DD162A /* RemoteRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */; };
+		69AA82340CC19CEE00DD162A /* RemoteEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82280CC19CEE00DD162A /* RemoteEvents.cc */; };
+		69AA82350CC19CEE00DD162A /* RemoteRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */; };
+		69AA824D0CC19D3E00DD162A /* EventProxy.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA824B0CC19D3E00DD162A /* EventProxy.cc */; };
+		69AA824E0CC19D3E00DD162A /* EventProxy.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA824B0CC19D3E00DD162A /* EventProxy.cc */; };
+		69AA824F0CC19D3E00DD162A /* EventProxy.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA824B0CC19D3E00DD162A /* EventProxy.cc */; };
+		69AA82500CC19D3E00DD162A /* EventProxy.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA824B0CC19D3E00DD162A /* EventProxy.cc */; };
+		69AA82510CC19D3E00DD162A /* EventProxy.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA824B0CC19D3E00DD162A /* EventProxy.cc */; };
+		69AA82670CC19D8600DD162A /* RemoteState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82650CC19D8600DD162A /* RemoteState.cc */; };
+		69AA82680CC19D8600DD162A /* RemoteState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82650CC19D8600DD162A /* RemoteState.cc */; };
+		69AA82690CC19D8600DD162A /* RemoteState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82650CC19D8600DD162A /* RemoteState.cc */; };
+		69AA826A0CC19D8600DD162A /* RemoteState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82650CC19D8600DD162A /* RemoteState.cc */; };
+		69AA826B0CC19D8600DD162A /* RemoteState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA82650CC19D8600DD162A /* RemoteState.cc */; };
 		69B344690A7152900021FBE6 /* PyramidData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B344670A7152900021FBE6 /* PyramidData.cc */; };
 		69B3446A0A7152900021FBE6 /* PyramidData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B344670A7152900021FBE6 /* PyramidData.cc */; };
 		69B3446D0A7152AC0021FBE6 /* ShapePyramid.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */; };
@@ -185,6 +907,20 @@
 		69B4E6D50895E34F00832D58 /* robot.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88407CBD6C0008493CA /* robot.cpp */; };
 		69B8DDC20AC44735003EC54A /* LGmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B8DDC00AC44735003EC54A /* LGmixin.cc */; };
 		69B8DDC30AC44736003EC54A /* LGmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B8DDC00AC44735003EC54A /* LGmixin.cc */; };
+		69BE64970BF979A800BC9A15 /* netstream.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE64950BF979A800BC9A15 /* netstream.cc */; };
+		69BE64980BF979A800BC9A15 /* netstream.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE64950BF979A800BC9A15 /* netstream.cc */; };
+		69BE64990BF979A800BC9A15 /* netstream.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE64950BF979A800BC9A15 /* netstream.cc */; };
+		69BE649A0BF979A800BC9A15 /* netstream.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE64950BF979A800BC9A15 /* netstream.cc */; };
+		69BE86B10C2F72440046EEAD /* RobotInfo.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE86B00C2F72440046EEAD /* RobotInfo.cc */; };
+		69BE87820C30215B0046EEAD /* RobotInfo.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE86B00C2F72440046EEAD /* RobotInfo.cc */; };
+		69BE87830C30215C0046EEAD /* RobotInfo.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE86B00C2F72440046EEAD /* RobotInfo.cc */; };
+		69BE87840C30215E0046EEAD /* RobotInfo.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69BE86B00C2F72440046EEAD /* RobotInfo.cc */; };
+		69CB30400BCED185002F46DC /* SerialIO.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69CB303D0BCED185002F46DC /* SerialIO.cc */; };
+		69CB31030BCFD575002F46DC /* libGlacier2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 692E74A90B9E7B3A00816584 /* libGlacier2.dylib */; };
+		69D0FBA00B8F82C900CC1DF1 /* Pilot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */; };
+		69D0FBA10B8F82C900CC1DF1 /* Pilot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */; };
+		69D0FBAE0B8F9B3500CC1DF1 /* PilotRequest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */; };
+		69D0FBAF0B8F9B3500CC1DF1 /* PilotRequest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */; };
 		69D5F7BD09BB4DC9000602D2 /* MessageQueue.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */; };
 		69D5F7BE09BB4DC9000602D2 /* MessageQueue.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */; };
 		69D5F82909BBDF0C000602D2 /* MessageQueueStatusThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */; };
@@ -194,15 +930,8 @@
 		69E0A76607CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
 		69E0A76707CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */; };
 		69E0A76807CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */; };
-		69E0A76907CBD4F9008493CA /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75E07CBD4F9008493CA /* StartupBehavior_SetupVision.cc */; };
 		69E0A76A07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */; };
 		69E0A76B07CBD4F9008493CA /* StartupBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76007CBD4F9008493CA /* StartupBehavior.cc */; };
-		69E0A77D07CBD52D008493CA /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76F07CBD52D008493CA /* Main.cc */; };
-		69E0A77F07CBD52D008493CA /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77107CBD52D008493CA /* Motion.cc */; };
-		69E0A78107CBD52D008493CA /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77307CBD52D008493CA /* Process.cc */; };
-		69E0A78407CBD52D008493CA /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77607CBD52D008493CA /* SharedGlobals.cc */; };
-		69E0A78607CBD52D008493CA /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77807CBD52D008493CA /* Simulator.cc */; };
-		69E0A78807CBD52D008493CA /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77A07CBD52D008493CA /* SoundPlay.cc */; };
 		69E0A99507CBD6C1008493CA /* BehaviorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78C07CBD6BF008493CA /* BehaviorBase.cc */; };
 		69E0A99807CBD6C1008493CA /* Controller.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78F07CBD6BF008493CA /* Controller.cc */; };
 		69E0A99F07CBD6C1008493CA /* ControlBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79707CBD6BF008493CA /* ControlBase.cc */; };
@@ -232,7 +961,6 @@
 		69E0A9F807CBD6C1008493CA /* RawCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F207CBD6C0008493CA /* RawCamBehavior.cc */; };
 		69E0A9FA07CBD6C1008493CA /* SegCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F407CBD6C0008493CA /* SegCamBehavior.cc */; };
 		69E0A9FC07CBD6C1008493CA /* SpeakerServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */; };
-		69E0A9FE07CBD6C1008493CA /* SpiderMachineBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F807CBD6C0008493CA /* SpiderMachineBehavior.cc */; };
 		69E0AA0107CBD6C2008493CA /* WalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FB07CBD6C0008493CA /* WalkControllerBehavior.cc */; };
 		69E0AA0307CBD6C2008493CA /* WMMonitorBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FD07CBD6C0008493CA /* WMMonitorBehavior.cc */; };
 		69E0AA0507CBD6C2008493CA /* WorldStateSerializerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FF07CBD6C0008493CA /* WorldStateSerializerBehavior.cc */; };
@@ -254,7 +982,6 @@
 		69E0AA4207CBD6C2008493CA /* MotionCommand.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84007CBD6C0008493CA /* MotionCommand.cc */; };
 		69E0AA4407CBD6C2008493CA /* MotionManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84207CBD6C0008493CA /* MotionManager.cc */; };
 		69E0AA4707CBD6C2008493CA /* MotionSequenceEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */; };
-		69E0AA4A07CBD6C2008493CA /* OldHeadPointerMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84807CBD6C0008493CA /* OldHeadPointerMC.cc */; };
 		69E0AA4C07CBD6C2008493CA /* OldKinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84A07CBD6C0008493CA /* OldKinematics.cc */; };
 		69E0AA4E07CBD6C2008493CA /* OutputCmd.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84C07CBD6C0008493CA /* OutputCmd.cc */; };
 		69E0AA5307CBD6C2008493CA /* PostureEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85107CBD6C0008493CA /* PostureEngine.cc */; };
@@ -329,15 +1056,8 @@
 		69E0AB9E07CBDE11008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
 		69E0AB9F07CBDE11008493CA /* StartupBehavior_SetupStatusReports.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */; };
 		69E0ABA007CBDE11008493CA /* StartupBehavior_SetupTekkotsuMon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */; };
-		69E0ABA107CBDE11008493CA /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75E07CBD4F9008493CA /* StartupBehavior_SetupVision.cc */; };
 		69E0ABA207CBDE11008493CA /* StartupBehavior_SetupWalkEdit.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */; };
 		69E0ABA307CBDE11008493CA /* StartupBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76007CBD4F9008493CA /* StartupBehavior.cc */; };
-		69E0ABA507CBDE11008493CA /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76F07CBD52D008493CA /* Main.cc */; };
-		69E0ABA607CBDE11008493CA /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77107CBD52D008493CA /* Motion.cc */; };
-		69E0ABA707CBDE11008493CA /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77307CBD52D008493CA /* Process.cc */; };
-		69E0ABA807CBDE11008493CA /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77607CBD52D008493CA /* SharedGlobals.cc */; };
-		69E0ABA907CBDE11008493CA /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77807CBD52D008493CA /* Simulator.cc */; };
-		69E0ABAA07CBDE11008493CA /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77A07CBD52D008493CA /* SoundPlay.cc */; };
 		69E0ABAB07CBDE11008493CA /* BehaviorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78C07CBD6BF008493CA /* BehaviorBase.cc */; };
 		69E0ABAC07CBDE11008493CA /* Controller.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78F07CBD6BF008493CA /* Controller.cc */; };
 		69E0ABAD07CBDE11008493CA /* ControlBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79707CBD6BF008493CA /* ControlBase.cc */; };
@@ -367,7 +1087,6 @@
 		69E0ABC607CBDE11008493CA /* RawCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F207CBD6C0008493CA /* RawCamBehavior.cc */; };
 		69E0ABC707CBDE11008493CA /* SegCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F407CBD6C0008493CA /* SegCamBehavior.cc */; };
 		69E0ABC807CBDE11008493CA /* SpeakerServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */; };
-		69E0ABC907CBDE11008493CA /* SpiderMachineBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F807CBD6C0008493CA /* SpiderMachineBehavior.cc */; };
 		69E0ABCA07CBDE11008493CA /* WalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FB07CBD6C0008493CA /* WalkControllerBehavior.cc */; };
 		69E0ABCB07CBDE11008493CA /* WMMonitorBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FD07CBD6C0008493CA /* WMMonitorBehavior.cc */; };
 		69E0ABCC07CBDE11008493CA /* WorldStateSerializerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FF07CBD6C0008493CA /* WorldStateSerializerBehavior.cc */; };
@@ -389,7 +1108,6 @@
 		69E0ABDC07CBDE11008493CA /* MotionCommand.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84007CBD6C0008493CA /* MotionCommand.cc */; };
 		69E0ABDD07CBDE11008493CA /* MotionManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84207CBD6C0008493CA /* MotionManager.cc */; };
 		69E0ABDE07CBDE11008493CA /* MotionSequenceEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */; };
-		69E0ABDF07CBDE11008493CA /* OldHeadPointerMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84807CBD6C0008493CA /* OldHeadPointerMC.cc */; };
 		69E0ABE007CBDE11008493CA /* OldKinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84A07CBD6C0008493CA /* OldKinematics.cc */; };
 		69E0ABE107CBDE11008493CA /* OutputCmd.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84C07CBD6C0008493CA /* OutputCmd.cc */; };
 		69E0ABE207CBDE11008493CA /* PostureEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85107CBD6C0008493CA /* PostureEngine.cc */; };
@@ -460,24 +1178,225 @@
 		69E0AC5707CBDE11008493CA /* SegmentedColorGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98C07CBD6C1008493CA /* SegmentedColorGenerator.cc */; };
 		69E0AC5807CBDE11008493CA /* Socket.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99107CBD6C1008493CA /* Socket.cc */; };
 		69E0AC5907CBDE11008493CA /* Wireless.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99307CBD6C1008493CA /* Wireless.cc */; };
-		69E0AC5B07CBDE11008493CA /* libstdc++.a in Frameworks */ = {isa = PBXBuildFile; fileRef = 0249A663FF388D9811CA2CEA /* libstdc++.a */; };
 		69E0AFAA07CBF84A008493CA /* StartupBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76007CBD4F9008493CA /* StartupBehavior.cc */; };
 		69E0AFAB07CBF84B008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */; };
 		69E0AFAC07CBF84C008493CA /* StartupBehavior_SetupFileAccess.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */; };
 		69E0AFAD07CBF84D008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */; };
 		69E0AFAE07CBF84E008493CA /* StartupBehavior_SetupStatusReports.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */; };
 		69E0AFAF07CBF84E008493CA /* StartupBehavior_SetupTekkotsuMon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */; };
-		69E0AFB007CBF84F008493CA /* StartupBehavior_SetupVision.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75E07CBD4F9008493CA /* StartupBehavior_SetupVision.cc */; };
 		69E0AFB107CBF850008493CA /* StartupBehavior_SetupWalkEdit.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */; };
-		69E0AFB307CBF85E008493CA /* Main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76F07CBD52D008493CA /* Main.cc */; };
-		69E0AFB407CBF85F008493CA /* Motion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77107CBD52D008493CA /* Motion.cc */; };
-		69E0AFB507CBF860008493CA /* Process.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77307CBD52D008493CA /* Process.cc */; };
-		69E0AFB607CBF862008493CA /* SharedGlobals.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77607CBD52D008493CA /* SharedGlobals.cc */; };
-		69E0AFB707CBF862008493CA /* Simulator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77807CBD52D008493CA /* Simulator.cc */; };
-		69E0AFB807CBF863008493CA /* SoundPlay.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A77A07CBD52D008493CA /* SoundPlay.cc */; };
 		69E0AFB907CBF881008493CA /* libtekkotsu.a in Frameworks */ = {isa = PBXBuildFile; fileRef = 69E0ADC407CBF382008493CA /* libtekkotsu.a */; };
 		69E0AFBA07CBF881008493CA /* libroboop.a in Frameworks */ = {isa = PBXBuildFile; fileRef = 69E0ADB607CBF0AB008493CA /* libroboop.a */; };
 		69E0AFBB07CBF881008493CA /* libnewmat.a in Frameworks */ = {isa = PBXBuildFile; fileRef = 69E0ADBD07CBF0F8008493CA /* libnewmat.a */; };
+		69E62FE60BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */; };
+		69E62FE70BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */; };
+		69E62FE80BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */; };
+		69E62FE90BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */; };
+		69E665400B4D822A00575707 /* plistBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A071B09575F41001A13D5 /* plistBase.cc */; };
+		69E665410B4D822A00575707 /* plistCollections.cc in Sources */ = {isa = PBXBuildFile; fileRef = 698A072709575F7D001A13D5 /* plistCollections.cc */; };
+		69E665490B4D822A00575707 /* StartupBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A76007CBD4F9008493CA /* StartupBehavior.cc */; };
+		69E665500B4D822A00575707 /* BehaviorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78C07CBD6BF008493CA /* BehaviorBase.cc */; };
+		69E665510B4D822A00575707 /* Controller.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A78F07CBD6BF008493CA /* Controller.cc */; };
+		69E665520B4D822A00575707 /* ControlBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79707CBD6BF008493CA /* ControlBase.cc */; };
+		69E665530B4D822A00575707 /* EventLogger.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79A07CBD6C0008493CA /* EventLogger.cc */; };
+		69E665540B4D822A00575707 /* FileBrowserControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79C07CBD6C0008493CA /* FileBrowserControl.cc */; };
+		69E665550B4D822A00575707 /* FreeMemReportControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A79F07CBD6C0008493CA /* FreeMemReportControl.cc */; };
+		69E665560B4D822A00575707 /* HelpControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7A107CBD6C0008493CA /* HelpControl.cc */; };
+		69E665570B4D822A00575707 /* PostureEditor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7AA07CBD6C0008493CA /* PostureEditor.cc */; };
+		69E665580B4D822A00575707 /* RebootControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7AD07CBD6C0008493CA /* RebootControl.cc */; };
+		69E665590B4D822A00575707 /* SensorObserverControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B207CBD6C0008493CA /* SensorObserverControl.cc */; };
+		69E6655A0B4D822A00575707 /* ShutdownControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B407CBD6C0008493CA /* ShutdownControl.cc */; };
+		69E6655B0B4D822A00575707 /* StringInputControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7B607CBD6C0008493CA /* StringInputControl.cc */; };
+		69E6655C0B4D822A00575707 /* WalkCalibration.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7BB07CBD6C0008493CA /* WalkCalibration.cc */; };
+		69E6655D0B4D822A00575707 /* WaypointWalkControl.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7BD07CBD6C0008493CA /* WaypointWalkControl.cc */; };
+		69E6655E0B4D822A00575707 /* ASCIIVisionBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C107CBD6C0008493CA /* ASCIIVisionBehavior.cc */; };
+		69E665600B4D822A00575707 /* ChaseBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7C807CBD6C0008493CA /* ChaseBallBehavior.cc */; };
+		69E665610B4D822A00575707 /* DriveMeBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CB07CBD6C0008493CA /* DriveMeBehavior.cc */; };
+		69E665620B4D822A00575707 /* ExploreMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7CD07CBD6C0008493CA /* ExploreMachine.cc */; };
+		69E665640B4D822A00575707 /* PaceTargetsMachine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7DD07CBD6C0008493CA /* PaceTargetsMachine.cc */; };
+		69E665650B4D822A00575707 /* StareAtBallBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7E207CBD6C0008493CA /* StareAtBallBehavior.cc */; };
+		69E665670B4D822A00575707 /* EStopControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7EC07CBD6C0008493CA /* EStopControllerBehavior.cc */; };
+		69E665680B4D822A00575707 /* HeadPointControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7EE07CBD6C0008493CA /* HeadPointControllerBehavior.cc */; };
+		69E665690B4D822A00575707 /* MicrophoneServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F007CBD6C0008493CA /* MicrophoneServer.cc */; };
+		69E6656A0B4D822A00575707 /* RawCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F207CBD6C0008493CA /* RawCamBehavior.cc */; };
+		69E6656B0B4D822A00575707 /* SegCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F407CBD6C0008493CA /* SegCamBehavior.cc */; };
+		69E6656C0B4D822A00575707 /* SpeakerServer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */; };
+		69E6656E0B4D822A00575707 /* WalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FB07CBD6C0008493CA /* WalkControllerBehavior.cc */; };
+		69E6656F0B4D822A00575707 /* WMMonitorBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FD07CBD6C0008493CA /* WMMonitorBehavior.cc */; };
+		69E665700B4D822A00575707 /* WorldStateSerializerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A7FF07CBD6C0008493CA /* WorldStateSerializerBehavior.cc */; };
+		69E665710B4D822A00575707 /* WalkToTargetNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A80B07CBD6C0008493CA /* WalkToTargetNode.cc */; };
+		69E665720B4D822A00575707 /* StateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A80E07CBD6C0008493CA /* StateNode.cc */; };
+		69E665730B4D822A00575707 /* Transition.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A81007CBD6C0008493CA /* Transition.cc */; };
+		69E665740B4D822A00575707 /* RandomTrans.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A81807CBD6C0008493CA /* RandomTrans.cc */; };
+		69E665750B4D822A00575707 /* EventBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82007CBD6C0008493CA /* EventBase.cc */; };
+		69E665760B4D822A00575707 /* EventGeneratorBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82207CBD6C0008493CA /* EventGeneratorBase.cc */; };
+		69E665770B4D822A00575707 /* EventRouter.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82507CBD6C0008493CA /* EventRouter.cc */; };
+		69E665780B4D822A00575707 /* EventTranslator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82707CBD6C0008493CA /* EventTranslator.cc */; };
+		69E665790B4D822A00575707 /* LocomotionEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82B07CBD6C0008493CA /* LocomotionEvent.cc */; };
+		69E6657A0B4D822A00575707 /* TextMsgEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A82E07CBD6C0008493CA /* TextMsgEvent.cc */; };
+		69E6657B0B4D822A00575707 /* VisionObjectEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83007CBD6C0008493CA /* VisionObjectEvent.cc */; };
+		69E6657C0B4D822A00575707 /* EmergencyStopMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83407CBD6C0008493CA /* EmergencyStopMC.cc */; };
+		69E6657D0B4D822A00575707 /* HeadPointerMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83807CBD6C0008493CA /* HeadPointerMC.cc */; };
+		69E6657E0B4D822A00575707 /* Kinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A83A07CBD6C0008493CA /* Kinematics.cc */; };
+		69E665800B4D822A00575707 /* MotionCommand.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84007CBD6C0008493CA /* MotionCommand.cc */; };
+		69E665810B4D822A00575707 /* MotionManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84207CBD6C0008493CA /* MotionManager.cc */; };
+		69E665820B4D822A00575707 /* MotionSequenceEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */; };
+		69E665840B4D822A00575707 /* OldKinematics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84A07CBD6C0008493CA /* OldKinematics.cc */; };
+		69E665850B4D822A00575707 /* OutputCmd.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A84C07CBD6C0008493CA /* OutputCmd.cc */; };
+		69E665860B4D822A00575707 /* PostureEngine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85107CBD6C0008493CA /* PostureEngine.cc */; };
+		69E665870B4D822A00575707 /* PostureMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85307CBD6C0008493CA /* PostureMC.cc */; };
+		69E665880B4D822A00575707 /* clik.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85707CBD6C0008493CA /* clik.cpp */; };
+		69E665890B4D822A00575707 /* comp_dq.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85907CBD6C0008493CA /* comp_dq.cpp */; };
+		69E6658A0B4D822A00575707 /* comp_dqp.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85A07CBD6C0008493CA /* comp_dqp.cpp */; };
+		69E6658B0B4D822A00575707 /* config.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85B07CBD6C0008493CA /* config.cpp */; };
+		69E6658C0B4D822A00575707 /* control_select.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85D07CBD6C0008493CA /* control_select.cpp */; };
+		69E6658D0B4D822A00575707 /* controller.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A85F07CBD6C0008493CA /* controller.cpp */; };
+		69E6658E0B4D822A00575707 /* delta_t.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86107CBD6C0008493CA /* delta_t.cpp */; };
+		69E6658F0B4D822A00575707 /* dynamics.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86207CBD6C0008493CA /* dynamics.cpp */; };
+		69E665900B4D822A00575707 /* dynamics_sim.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A86307CBD6C0008493CA /* dynamics_sim.cpp */; };
+		69E665910B4D822A00575707 /* gnugraph.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87907CBD6C0008493CA /* gnugraph.cpp */; };
+		69E665920B4D822A00575707 /* homogen.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87B07CBD6C0008493CA /* homogen.cpp */; };
+		69E665930B4D822A00575707 /* invkine.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87C07CBD6C0008493CA /* invkine.cpp */; };
+		69E665940B4D822A00575707 /* kinemat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87D07CBD6C0008493CA /* kinemat.cpp */; };
+		69E665950B4D822A00575707 /* quaternion.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A87F07CBD6C0008493CA /* quaternion.cpp */; };
+		69E665960B4D822A00575707 /* sensitiv.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88607CBD6C0008493CA /* sensitiv.cpp */; };
+		69E665970B4D822A00575707 /* trajectory.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88707CBD6C0008493CA /* trajectory.cpp */; };
+		69E665980B4D822A00575707 /* utils.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88907CBD6C0008493CA /* utils.cpp */; };
+		69E665990B4D822A00575707 /* WalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88D07CBD6C0008493CA /* WalkMC.cc */; };
+		69E6659A0B4D822A00575707 /* Buffer.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89207CBD6C0008493CA /* Buffer.cc */; };
+		69E6659B0B4D822A00575707 /* Config.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89507CBD6C0008493CA /* Config.cc */; };
+		69E6659C0B4D822A00575707 /* get_time.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A89D07CBD6C0008493CA /* get_time.cc */; };
+		69E6659D0B4D822A00575707 /* jpeg_mem_dest.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8DE07CBD6C1008493CA /* jpeg_mem_dest.cc */; };
+		69E6659E0B4D822A00575707 /* LoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8F807CBD6C1008493CA /* LoadSave.cc */; };
+		69E6659F0B4D822A00575707 /* bandmat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A8FE07CBD6C1008493CA /* bandmat.cpp */; };
+		69E665A00B4D822A00575707 /* cholesky.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A90007CBD6C1008493CA /* cholesky.cpp */; };
+		69E665A10B4D822A00575707 /* evalue.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A90707CBD6C1008493CA /* evalue.cpp */; };
+		69E665A20B4D822A00575707 /* fft.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93807CBD6C1008493CA /* fft.cpp */; };
+		69E665A30B4D822A00575707 /* hholder.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93907CBD6C1008493CA /* hholder.cpp */; };
+		69E665A40B4D822A00575707 /* jacobi.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93B07CBD6C1008493CA /* jacobi.cpp */; };
+		69E665A50B4D822A00575707 /* myexcept.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93D07CBD6C1008493CA /* myexcept.cpp */; };
+		69E665A60B4D822A00575707 /* newfft.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A93F07CBD6C1008493CA /* newfft.cpp */; };
+		69E665A70B4D822A00575707 /* newmat1.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94107CBD6C1008493CA /* newmat1.cpp */; };
+		69E665A80B4D822A00575707 /* newmat2.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94207CBD6C1008493CA /* newmat2.cpp */; };
+		69E665A90B4D822A00575707 /* newmat3.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94307CBD6C1008493CA /* newmat3.cpp */; };
+		69E665AA0B4D822A00575707 /* newmat4.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94407CBD6C1008493CA /* newmat4.cpp */; };
+		69E665AB0B4D822A00575707 /* newmat5.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94507CBD6C1008493CA /* newmat5.cpp */; };
+		69E665AC0B4D822A00575707 /* newmat6.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94607CBD6C1008493CA /* newmat6.cpp */; };
+		69E665AD0B4D822A00575707 /* newmat7.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94707CBD6C1008493CA /* newmat7.cpp */; };
+		69E665AE0B4D822A00575707 /* newmat8.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94807CBD6C1008493CA /* newmat8.cpp */; };
+		69E665AF0B4D822A00575707 /* newmat9.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94907CBD6C1008493CA /* newmat9.cpp */; };
+		69E665B00B4D822A00575707 /* newmatex.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94B07CBD6C1008493CA /* newmatex.cpp */; };
+		69E665B10B4D822A00575707 /* newmatnl.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A94D07CBD6C1008493CA /* newmatnl.cpp */; };
+		69E665B20B4D822A00575707 /* newmatrm.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95007CBD6C1008493CA /* newmatrm.cpp */; };
+		69E665B30B4D822A00575707 /* sort.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95407CBD6C1008493CA /* sort.cpp */; };
+		69E665B40B4D822A00575707 /* submat.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95507CBD6C1008493CA /* submat.cpp */; };
+		69E665B50B4D822A00575707 /* svd.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95607CBD6C1008493CA /* svd.cpp */; };
+		69E665B60B4D822A00575707 /* Profiler.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95A07CBD6C1008493CA /* Profiler.cc */; };
+		69E665B70B4D822A00575707 /* ProjectInterface.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A95C07CBD6C1008493CA /* ProjectInterface.cc */; };
+		69E665B80B4D822A00575707 /* string_util.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96507CBD6C1008493CA /* string_util.cc */; };
+		69E665B90B4D822A00575707 /* TimeET.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96807CBD6C1008493CA /* TimeET.cc */; };
+		69E665BA0B4D822A00575707 /* WMclass.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96B07CBD6C1008493CA /* WMclass.cc */; };
+		69E665BB0B4D822A00575707 /* WorldState.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A96D07CBD6C1008493CA /* WorldState.cc */; };
+		69E665BC0B4D822A00575707 /* SoundManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97007CBD6C1008493CA /* SoundManager.cc */; };
+		69E665BD0B4D822A00575707 /* WAV.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97307CBD6C1008493CA /* WAV.cc */; };
+		69E665BE0B4D822A00575707 /* BallDetectionGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97607CBD6C1008493CA /* BallDetectionGenerator.cc */; };
+		69E665BF0B4D822A00575707 /* CDTGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97807CBD6C1008493CA /* CDTGenerator.cc */; };
+		69E665C00B4D822A00575707 /* FilterBankGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A97F07CBD6C1008493CA /* FilterBankGenerator.cc */; };
+		69E665C10B4D822A00575707 /* InterleavedYUVGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98107CBD6C1008493CA /* InterleavedYUVGenerator.cc */; };
+		69E665C20B4D822A00575707 /* JPEGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98307CBD6C1008493CA /* JPEGGenerator.cc */; };
+		69E665C30B4D822A00575707 /* RawCameraGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98607CBD6C1008493CA /* RawCameraGenerator.cc */; };
+		69E665C40B4D822A00575707 /* RegionGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98807CBD6C1008493CA /* RegionGenerator.cc */; };
+		69E665C50B4D822A00575707 /* RLEGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98A07CBD6C1008493CA /* RLEGenerator.cc */; };
+		69E665C60B4D822A00575707 /* SegmentedColorGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A98C07CBD6C1008493CA /* SegmentedColorGenerator.cc */; };
+		69E665C70B4D822A00575707 /* Socket.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99107CBD6C1008493CA /* Socket.cc */; };
+		69E665C80B4D822A00575707 /* Wireless.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A99307CBD6C1008493CA /* Wireless.cc */; };
+		69E665C90B4D822A00575707 /* SemaphoreManager.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3CF07D4D35F003A7628 /* SemaphoreManager.cc */; };
+		69E665CA0B4D822A00575707 /* ProcessID.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D107D4D35F003A7628 /* ProcessID.cc */; };
+		69E665CB0B4D822A00575707 /* RCRegion.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D307D4D35F003A7628 /* RCRegion.cc */; };
+		69E665CC0B4D822A00575707 /* SharedObject.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6994F3D607D4D35F003A7628 /* SharedObject.cc */; };
+		69E665CD0B4D822A00575707 /* MutexLock.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942757707E0DCDD003DE3D9 /* MutexLock.cc */; };
+		69E665CE0B4D822A00575707 /* Thread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6942779007E164EA003DE3D9 /* Thread.cc */; };
+		69E665CF0B4D822A00575707 /* write_jpeg.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A323C007E35646009D94E1 /* write_jpeg.cc */; };
+		69E665D00B4D822A00575707 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E666BB07F0CE51005F4FA9 /* plist.cc */; };
+		69E665D10B4D822A00575707 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */; };
+		69E665D30B4D822A00575707 /* BufferedImageGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */; };
+		69E665D40B4D822A00575707 /* EchoBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A1995E080ED8A200540970 /* EchoBehavior.cc */; };
+		69E665D50B4D822A00575707 /* Base64.cc in Sources */ = {isa = PBXBuildFile; fileRef = 691C805508255F6300E8E256 /* Base64.cc */; };
+		69E665D60B4D822A00575707 /* StewartPlatformBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69970AC0083DB2760069D95C /* StewartPlatformBehavior.cc */; };
+		69E665D70B4D822A00575707 /* UPennWalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F5084C389D0003A261 /* UPennWalkMC.cc */; };
+		69E665D80B4D822A00575707 /* Graphics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F9084C38E80003A261 /* Graphics.cc */; };
+		69E665D90B4D822A00575707 /* UPennWalkControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA4901084C39230003A261 /* UPennWalkControllerBehavior.cc */; };
+		69E665DA0B4D822A00575707 /* MessageReceiver.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69AA7D690860898300185BA2 /* MessageReceiver.cc */; };
+		69E665DC0B4D822A00575707 /* robot.cpp in Sources */ = {isa = PBXBuildFile; fileRef = 69E0A88407CBD6C0008493CA /* robot.cpp */; };
+		69E665DD0B4D822A00575707 /* RegionCamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 693D801208ABF46D00AC993E /* RegionCamBehavior.cc */; };
+		69E665DE0B4D822A00575707 /* CameraStreamBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */; };
+		69E665DF0B4D822A00575707 /* MCNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6966753B0926558A00405769 /* MCNode.cc */; };
+		69E665E00B4D822A00575707 /* AgentData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6C09AA1D2000D1EC14 /* AgentData.cc */; };
+		69E665E10B4D822A00575707 /* BaseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F6E09AA1D2000D1EC14 /* BaseData.cc */; };
+		69E665E20B4D822A00575707 /* BlobData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7009AA1D2000D1EC14 /* BlobData.cc */; };
+		69E665E30B4D822A00575707 /* BrickData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7209AA1D2000D1EC14 /* BrickData.cc */; };
+		69E665E40B4D822A00575707 /* EllipseData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7709AA1D2000D1EC14 /* EllipseData.cc */; };
+		69E665E50B4D822A00575707 /* EndPoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7909AA1D2000D1EC14 /* EndPoint.cc */; };
+		69E665E60B4D822A00575707 /* LineData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7B09AA1D2000D1EC14 /* LineData.cc */; };
+		69E665E70B4D822A00575707 /* Lookout.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F7F09AA1D2000D1EC14 /* Lookout.cc */; };
+		69E665E80B4D822A00575707 /* MapBuilder.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8209AA1D2000D1EC14 /* MapBuilder.cc */; };
+		69E665EC0B4D822A00575707 /* ParticleShapes.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */; };
+		69E665ED0B4D822A00575707 /* Point.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F8E09AA1D2000D1EC14 /* Point.cc */; };
+		69E665EE0B4D822A00575707 /* PointData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9009AA1D2000D1EC14 /* PointData.cc */; };
+		69E665EF0B4D822A00575707 /* PolygonData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9209AA1D2000D1EC14 /* PolygonData.cc */; };
+		69E665F00B4D822A00575707 /* Region.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9409AA1D2000D1EC14 /* Region.cc */; };
+		69E665F10B4D822A00575707 /* ShapeAgent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9609AA1D2000D1EC14 /* ShapeAgent.cc */; };
+		69E665F20B4D822A00575707 /* ShapeBlob.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9809AA1D2000D1EC14 /* ShapeBlob.cc */; };
+		69E665F30B4D822A00575707 /* ShapeBrick.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9A09AA1D2000D1EC14 /* ShapeBrick.cc */; };
+		69E665F40B4D822A00575707 /* ShapeEllipse.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9C09AA1D2000D1EC14 /* ShapeEllipse.cc */; };
+		69E665F50B4D822A00575707 /* ShapeFuns.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469F9E09AA1D2000D1EC14 /* ShapeFuns.cc */; };
+		69E665F60B4D822A00575707 /* ShapeLine.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA009AA1D2100D1EC14 /* ShapeLine.cc */; };
+		69E665F70B4D822A00575707 /* ShapePoint.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA209AA1D2100D1EC14 /* ShapePoint.cc */; };
+		69E665F80B4D822A00575707 /* ShapePolygon.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */; };
+		69E665F90B4D822A00575707 /* ShapeRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA609AA1D2100D1EC14 /* ShapeRoot.cc */; };
+		69E665FA0B4D822A00575707 /* ShapeSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FA809AA1D2100D1EC14 /* ShapeSpace.cc */; };
+		69E665FB0B4D822A00575707 /* ShapeSphere.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */; };
+		69E665FD0B4D822A00575707 /* Sketch.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FAE09AA1D2100D1EC14 /* Sketch.cc */; };
+		69E665FE0B4D822A00575707 /* SketchDataRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB109AA1D2100D1EC14 /* SketchDataRoot.cc */; };
+		69E665FF0B4D822A00575707 /* SketchIndices.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB309AA1D2100D1EC14 /* SketchIndices.cc */; };
+		69E666000B4D822A00575707 /* SketchRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB609AA1D2100D1EC14 /* SketchRoot.cc */; };
+		69E666010B4D822A00575707 /* SketchSpace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FB809AA1D2100D1EC14 /* SketchSpace.cc */; };
+		69E666020B4D822A00575707 /* SphereData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBB09AA1D2100D1EC14 /* SphereData.cc */; };
+		69E666030B4D822A00575707 /* susan.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBD09AA1D2100D1EC14 /* susan.cc */; };
+		69E666040B4D822A00575707 /* ViewerConnection.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */; };
+		69E666050B4D822A00575707 /* visops.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC109AA1D2100D1EC14 /* visops.cc */; };
+		69E666060B4D822A00575707 /* VisualRoutinesBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69469FC309AA1D2100D1EC14 /* VisualRoutinesBehavior.cc */; };
+		69E666070B4D822A00575707 /* VRmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A109AAE1C600D1EC14 /* VRmixin.cc */; };
+		69E666080B4D822A00575707 /* VisualRoutinesStateNode.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6946A1A409AAE1D800D1EC14 /* VisualRoutinesStateNode.cc */; };
+		69E666090B4D822A00575707 /* MessageQueue.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */; };
+		69E6660A0B4D822A00575707 /* MessageQueueStatusThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */; };
+		69E6660B0B4D822A00575707 /* PollThread.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EBE909C7162E003DDD18 /* PollThread.cc */; };
+		69E6660E0B4D822A00575707 /* plistPrimitives.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */; };
+		69E6660F0B4D822A00575707 /* StackTrace.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E78D0109F6C114000385E9 /* StackTrace.cc */; };
+		69E666100B4D822A00575707 /* SketchPoolRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */; };
+		69E666110B4D822A00575707 /* jpeg_mem_src.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */; };
+		69E666120B4D822A00575707 /* Resource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EB5B530A41CCD700415C6B /* Resource.cc */; };
+		69E666130B4D822A00575707 /* PNGGenerator.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6900659D0A4EF58700E895F9 /* PNGGenerator.cc */; };
+		69E666140B4D822A00575707 /* WorldStatePool.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */; };
+		69E666150B4D822A00575707 /* PyramidData.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B344670A7152900021FBE6 /* PyramidData.cc */; };
+		69E666160B4D822A00575707 /* ShapePyramid.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */; };
+		69E666170B4D822A00575707 /* BrickOps.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B3446F0A7152C30021FBE6 /* BrickOps.cc */; };
+		69E666180B4D822A00575707 /* LookoutEvents.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */; };
+		69E666190B4D822A00575707 /* Aibo3DControllerBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2EE0A917E74002DDEC9 /* Aibo3DControllerBehavior.cc */; };
+		69E6661A0B4D822A00575707 /* LookoutRequests.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */; };
+		69E6661B0B4D822A00575707 /* TestBehaviors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 692964F60AA8CEEF00F47522 /* TestBehaviors.cc */; };
+		69E6661C0B4D822A00575707 /* TimerEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6901D58D0AAF288500104815 /* TimerEvent.cc */; };
+		69E6661D0B4D822A00575707 /* FlashIPAddrBehavior.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */; };
+		69E6661E0B4D822A00575707 /* PitchEvent.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E67E40AC308290087EC83 /* PitchEvent.cc */; };
+		69E6661F0B4D822A00575707 /* PitchDetector.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694E684B0AC338CF0087EC83 /* PitchDetector.cc */; };
+		69E666200B4D822A00575707 /* LGmixin.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69B8DDC00AC44735003EC54A /* LGmixin.cc */; };
+		69E666230B4D822A00575707 /* colors.cc in Sources */ = {isa = PBXBuildFile; fileRef = 6959FAC20B08FF4D006F08BB /* colors.cc */; };
+		69E666260B4D822A00575707 /* libiconv.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9207EB57480047DA8D /* libiconv.dylib */; };
+		69E666270B4D822A00575707 /* libxml2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9307EB57480047DA8D /* libxml2.dylib */; };
+		69E666280B4D822A00575707 /* libz.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9407EB57480047DA8D /* libz.dylib */; };
+		69E666290B4D822A00575707 /* libjpeg.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43507F48A860071A2AE /* libjpeg.dylib */; };
+		69E6662A0B4D822A00575707 /* libpng12.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 694AB43607F48A860071A2AE /* libpng12.dylib */; };
+		69E6662B0B4D822A00575707 /* libreadline.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */; };
 		69E666BC07F0CE51005F4FA9 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E666BB07F0CE51005F4FA9 /* plist.cc */; };
 		69E666BD07F0CE51005F4FA9 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E666BB07F0CE51005F4FA9 /* plist.cc */; };
 		69E6674907F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */; };
@@ -495,6 +1414,19 @@
 		69EA8B9D07EB57480047DA8D /* libz.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69EA8B9407EB57480047DA8D /* libz.dylib */; };
 		69EB5B550A41CCD700415C6B /* Resource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EB5B530A41CCD700415C6B /* Resource.cc */; };
 		69EB5B560A41CCD700415C6B /* Resource.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EB5B530A41CCD700415C6B /* Resource.cc */; };
+		69EE785F0B68024A00202E66 /* HolonomicMotionModel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */; };
+		69EE78600B68024A00202E66 /* HolonomicMotionModel.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */; };
+		69EF73270B57E27500FF5476 /* zignor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73230B57E27500FF5476 /* zignor.cc */; };
+		69EF73280B57E27500FF5476 /* zigrandom.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73250B57E27500FF5476 /* zigrandom.cc */; };
+		69EF73290B57E27500FF5476 /* zignor.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73230B57E27500FF5476 /* zignor.cc */; };
+		69EF732A0B57E27500FF5476 /* zigrandom.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF73250B57E27500FF5476 /* zigrandom.cc */; };
+		69EF74840B59EC7200FF5476 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF74820B59EC7200FF5476 /* Measures.cc */; };
+		69EF74850B59EC7200FF5476 /* Measures.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69EF74820B59EC7200FF5476 /* Measures.cc */; };
+		69F74F0C0B98920D00FBA370 /* PFShapeLocalization.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */; };
+		69F74F0D0B98920D00FBA370 /* PFShapeSLAM.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */; };
+		69F74F0E0B98920D00FBA370 /* PFShapeLocalization.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */; };
+		69F74F0F0B98920D00FBA370 /* PFShapeSLAM.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */; };
+		69F755C20B9BB9B500FBA370 /* SketchPoolRoot.cc in Sources */ = {isa = PBXBuildFile; fileRef = 694B2B1E0A0FC983002ABC4C /* SketchPoolRoot.cc */; };
 		69FA48F7084C389E0003A261 /* UPennWalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F5084C389D0003A261 /* UPennWalkMC.cc */; };
 		69FA48F8084C389E0003A261 /* UPennWalkMC.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F5084C389D0003A261 /* UPennWalkMC.cc */; };
 		69FA48FD084C38E80003A261 /* Graphics.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69FA48F9084C38E80003A261 /* Graphics.cc */; };
@@ -504,21 +1436,114 @@
 /* End PBXBuildFile section */
 
 /* Begin PBXFileReference section */
-		0249A663FF388D9811CA2CEA /* libstdc++.a */ = {isa = PBXFileReference; lastKnownFileType = archive.ar; name = "libstdc++.a"; path = "/usr/lib/libstdc++.a"; sourceTree = "<absolute>"; };
 		6900659D0A4EF58700E895F9 /* PNGGenerator.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = PNGGenerator.cc; sourceTree = "<group>"; };
 		6900659E0A4EF58700E895F9 /* PNGGenerator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = PNGGenerator.h; sourceTree = "<group>"; };
 		6901D58D0AAF288500104815 /* TimerEvent.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TimerEvent.cc; sourceTree = "<group>"; };
 		6901D58E0AAF288500104815 /* TimerEvent.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TimerEvent.h; sourceTree = "<group>"; };
-		690564F20819531A00613A0E /* minisim.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = minisim.h; sourceTree = "<group>"; };
+		6917A76E0BB1BCCA00F0B40B /* QwerkInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = QwerkInfo.h; sourceTree = "<group>"; };
 		691C805508255F6300E8E256 /* Base64.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Base64.cc; sourceTree = "<group>"; };
 		691C805C08255F6D00E8E256 /* Base64.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Base64.h; sourceTree = "<group>"; };
+		691FC35E0B4EDCF600246924 /* CommonERSInfo.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = CommonERSInfo.h; sourceTree = "<group>"; };
 		692964F60AA8CEEF00F47522 /* TestBehaviors.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = TestBehaviors.cc; sourceTree = "<group>"; };
 		692964F70AA8CEEF00F47522 /* TestBehaviors.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = TestBehaviors.h; sourceTree = "<group>"; };
-		692CD63407F8C46B00604100 /* sim.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = sim.cc; sourceTree = "<group>"; };
-		6934224207D408E600BB3331 /* sim.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = sim.h; sourceTree = "<group>"; };
+		692E74920B9E77C100816584 /* tekkotsu-QBOTPLUS */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "tekkotsu-QBOTPLUS"; sourceTree = BUILT_PRODUCTS_DIR; };
+		692E74A90B9E7B3A00816584 /* libGlacier2.dylib */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.dylib"; name = libGlacier2.dylib; path = /usr/local/Ice/lib/libGlacier2.dylib; sourceTree = "<absolute>"; };
+		692E74AA0B9E7B3A00816584 /* libIce.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libIce.dylib; path = /usr/local/Ice/lib/libIce.dylib; sourceTree = "<absolute>"; };
+		692E74AB0B9E7B3A00816584 /* libIceUtil.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libIceUtil.dylib; path = /usr/local/Ice/lib/libIceUtil.dylib; sourceTree = "<absolute>"; };
+		692E74D10B9E7CDD00816584 /* ImageCache.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ImageCache.cc; sourceTree = "<group>"; };
+		692E74D20B9E7CDD00816584 /* ImageCache.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ImageCache.h; sourceTree = "<group>"; };
+		692E74D30B9E7CDD00816584 /* ObjectPingThread.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ObjectPingThread.cc; sourceTree = "<group>"; };
+		692E74D40B9E7CDD00816584 /* ObjectPingThread.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ObjectPingThread.h; sourceTree = "<group>"; };
+		692E74D50B9E7CDD00816584 /* PropertyManagerI.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PropertyManagerI.cc; sourceTree = "<group>"; };
+		692E74D60B9E7CDD00816584 /* PropertyManagerI.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PropertyManagerI.h; sourceTree = "<group>"; };
+		692E74D70B9E7CDD00816584 /* QwerkBot.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = QwerkBot.cc; sourceTree = "<group>"; };
+		692E74D80B9E7CDD00816584 /* QwerkBot.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = QwerkBot.h; sourceTree = "<group>"; };
+		692E74DB0B9E7CDD00816584 /* TeRKPeerCommon.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TeRKPeerCommon.cc; sourceTree = "<group>"; };
+		692E74DC0B9E7CDD00816584 /* TeRKPeerCommon.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TeRKPeerCommon.h; sourceTree = "<group>"; };
+		692E74DD0B9E7CDD00816584 /* TerkUserI.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TerkUserI.cc; sourceTree = "<group>"; };
+		692E74DE0B9E7CDD00816584 /* TerkUserI.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TerkUserI.h; sourceTree = "<group>"; };
+		692E751D0B9E821800816584 /* MRPLPeer.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = MRPLPeer.cc; sourceTree = "<group>"; };
+		692E751E0B9E821800816584 /* MRPLPeer.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = MRPLPeer.h; sourceTree = "<group>"; };
+		6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupVision.cc; sourceTree = "<group>"; };
+		693688250C594E3900D54726 /* QBotPlusInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = QBotPlusInfo.h; sourceTree = "<group>"; };
+		6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = CameraSourceOSX.cc; sourceTree = "<group>"; };
+		6937766C0C17358C001E2C9E /* CameraSourceOSX.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CameraSourceOSX.h; sourceTree = "<group>"; };
+		693776720C17359B001E2C9E /* CameraDriverOSX.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = CameraDriverOSX.cc; sourceTree = "<group>"; };
+		693776730C17359B001E2C9E /* CameraDriverOSX.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CameraDriverOSX.h; sourceTree = "<group>"; };
+		693776B70C175811001E2C9E /* Carbon.framework */ = {isa = PBXFileReference; lastKnownFileType = wrapper.framework; name = Carbon.framework; path = /System/Library/Frameworks/Carbon.framework; sourceTree = "<absolute>"; };
+		693776D10C17581F001E2C9E /* QuickTime.framework */ = {isa = PBXFileReference; lastKnownFileType = wrapper.framework; name = QuickTime.framework; path = /System/Library/Frameworks/QuickTime.framework; sourceTree = "<absolute>"; };
+		693A55EA0BE1474500509F85 /* TargetData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TargetData.cc; sourceTree = "<group>"; };
+		693A55EB0BE1474500509F85 /* TargetData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TargetData.h; sourceTree = "<group>"; };
+		693A55F40BE1478000509F85 /* ShapeTypes.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeTypes.cc; sourceTree = "<group>"; };
+		693A55F50BE1478000509F85 /* ShapeTypes.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeTypes.h; sourceTree = "<group>"; };
+		693A55FA0BE1479800509F85 /* ShapeTarget.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeTarget.cc; sourceTree = "<group>"; };
+		693A55FB0BE1479800509F85 /* ShapeTarget.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeTarget.h; sourceTree = "<group>"; };
+		693AD5880C205BE80053F7DE /* Main.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Main.cc; sourceTree = "<group>"; };
+		693AD5890C205BE80053F7DE /* Main.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Main.h; sourceTree = "<group>"; };
+		693AD58A0C205BE80053F7DE /* Motion.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Motion.cc; sourceTree = "<group>"; };
+		693AD58B0C205BE80053F7DE /* Motion.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Motion.h; sourceTree = "<group>"; };
+		693AD58C0C205BE80053F7DE /* MotionExecThread.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = MotionExecThread.cc; sourceTree = "<group>"; };
+		693AD58D0C205BE80053F7DE /* MotionExecThread.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = MotionExecThread.h; sourceTree = "<group>"; };
+		693AD58E0C205BE80053F7DE /* Process.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Process.cc; sourceTree = "<group>"; };
+		693AD58F0C205BE80053F7DE /* Process.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Process.h; sourceTree = "<group>"; };
+		693AD5900C205BE80053F7DE /* SharedGlobals.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SharedGlobals.cc; sourceTree = "<group>"; };
+		693AD5910C205BE80053F7DE /* SharedGlobals.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SharedGlobals.h; sourceTree = "<group>"; };
+		693AD5920C205BE80053F7DE /* sim.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = sim.cc; sourceTree = "<group>"; };
+		693AD5930C205BE80053F7DE /* sim.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = sim.h; sourceTree = "<group>"; };
+		693AD5940C205BE80053F7DE /* SimConfig.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SimConfig.h; sourceTree = "<group>"; };
+		693AD5950C205BE80053F7DE /* Simulator.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Simulator.cc; sourceTree = "<group>"; };
+		693AD5960C205BE80053F7DE /* Simulator.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Simulator.h; sourceTree = "<group>"; };
+		693AD5970C205BE80053F7DE /* SoundPlay.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SoundPlay.cc; sourceTree = "<group>"; };
+		693AD5980C205BE80053F7DE /* SoundPlay.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SoundPlay.h; sourceTree = "<group>"; };
+		693AD5990C205BE80053F7DE /* TimerExecThread.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TimerExecThread.cc; sourceTree = "<group>"; };
+		693AD59A0C205BE80053F7DE /* TimerExecThread.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TimerExecThread.h; sourceTree = "<group>"; };
 		693C86E7090EE6F00058EE92 /* MCNode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = MCNode.h; sourceTree = "<group>"; };
+		693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = jpeg_istream_src.cc; sourceTree = "<group>"; };
+		693D09C80C525F7E00A56175 /* jpeg_istream_src.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = jpeg_istream_src.h; sourceTree = "<group>"; };
+		693D09D50C525FA000A56175 /* Regis1Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Regis1Info.h; sourceTree = "<group>"; };
+		693D0AF50C52643E00A56175 /* tekkotsu-REGIS1 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "tekkotsu-REGIS1"; sourceTree = BUILT_PRODUCTS_DIR; };
+		693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RoverControllerBehavior.cc; sourceTree = "<group>"; };
+		693D0B1B0C52687D00A56175 /* RoverControllerBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = RoverControllerBehavior.h; sourceTree = "<group>"; };
+		693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ImageStreamDriver.cc; sourceTree = "<group>"; };
+		693D0C690C52FE6D00A56175 /* ImageStreamDriver.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ImageStreamDriver.h; sourceTree = "<group>"; };
+		693D0E540C56632100A56175 /* TeRKDriver.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = TeRKDriver.cc; sourceTree = "<group>"; };
+		693D0E550C56632100A56175 /* TeRKDriver.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 4; path = TeRKDriver.h; sourceTree = "<group>"; };
+		693D0E7A0C572C4C00A56175 /* DataCache.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = DataCache.cc; sourceTree = "<group>"; };
+		693D0E7B0C572C4C00A56175 /* DataCache.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = DataCache.h; sourceTree = "<group>"; };
+		693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = CameraDriverV4L.cc; sourceTree = "<group>"; };
+		693D23EC0C91B9C3006D6505 /* CameraDriverV4L.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CameraDriverV4L.h; sourceTree = "<group>"; };
 		693D801208ABF46D00AC993E /* RegionCamBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RegionCamBehavior.cc; sourceTree = "<group>"; };
 		693D801308ABF46D00AC993E /* RegionCamBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = RegionCamBehavior.h; sourceTree = "<group>"; };
+		693E649F0BF113FA00A5D8B8 /* FamilyFactory.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = FamilyFactory.h; sourceTree = "<group>"; };
+		693E65710BF3C04400A5D8B8 /* Factories.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = Factories.h; sourceTree = "<group>"; };
+		693E673A0BF5185500A5D8B8 /* InstanceTracker.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = InstanceTracker.h; sourceTree = "<group>"; };
+		69401C870C1291F000FE900C /* ExecutableCommPort.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ExecutableCommPort.cc; sourceTree = "<group>"; };
+		69401C880C1291F000FE900C /* ExecutableCommPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ExecutableCommPort.h; sourceTree = "<group>"; };
+		69401C890C1291F000FE900C /* FileSystemCommPort.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = FileSystemCommPort.cc; sourceTree = "<group>"; };
+		69401C8A0C1291F000FE900C /* FileSystemCommPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = FileSystemCommPort.h; sourceTree = "<group>"; };
+		69401C8B0C1291F000FE900C /* NetworkCommPort.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = NetworkCommPort.cc; sourceTree = "<group>"; };
+		69401C8C0C1291F000FE900C /* NetworkCommPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = NetworkCommPort.h; sourceTree = "<group>"; };
+		69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RedirectionCommPort.cc; sourceTree = "<group>"; };
+		69401C8E0C1291F000FE900C /* RedirectionCommPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = RedirectionCommPort.h; sourceTree = "<group>"; };
+		69401C8F0C1291F000FE900C /* SerialCommPort.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SerialCommPort.cc; sourceTree = "<group>"; };
+		69401C900C1291F000FE900C /* SerialCommPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SerialCommPort.h; sourceTree = "<group>"; };
+		69401CA60C12922400FE900C /* FileSystemDataSource.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = FileSystemDataSource.cc; sourceTree = "<group>"; };
+		69401CA70C12922400FE900C /* FileSystemDataSource.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = FileSystemDataSource.h; sourceTree = "<group>"; };
+		69401CA80C12922400FE900C /* FileSystemImageSource.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = FileSystemImageSource.cc; sourceTree = "<group>"; };
+		69401CA90C12922400FE900C /* FileSystemImageSource.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = FileSystemImageSource.h; sourceTree = "<group>"; };
+		69401CAB0C12922400FE900C /* LoggedDataDriver.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LoggedDataDriver.cc; sourceTree = "<group>"; };
+		69401CAC0C12922400FE900C /* LoggedDataDriver.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LoggedDataDriver.h; sourceTree = "<group>"; };
+		69401CAD0C12922400FE900C /* SSC32Driver.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SSC32Driver.cc; sourceTree = "<group>"; };
+		69401CAE0C12922400FE900C /* SSC32Driver.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SSC32Driver.h; sourceTree = "<group>"; };
+		69401CB00C12922400FE900C /* IPCMotionHook.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = IPCMotionHook.cc; sourceTree = "<group>"; };
+		69401CB10C12922400FE900C /* IPCMotionHook.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = IPCMotionHook.h; sourceTree = "<group>"; };
+		694252150CC7E65B00129C8D /* Dynamixel.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Dynamixel.cc; sourceTree = "<group>"; };
+		694252160CC7E65B00129C8D /* Dynamixel.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Dynamixel.h; sourceTree = "<group>"; };
+		6942521E0CC7E8DC00129C8D /* SocketListener.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SocketListener.h; sourceTree = "<group>"; };
+		694252380CC7E98D00129C8D /* NetworkBuffer.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = NetworkBuffer.h; sourceTree = "<group>"; };
+		6942525C0CC7EB2300129C8D /* SerialPort.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SerialPort.cc; sourceTree = "<group>"; };
+		6942525D0CC7EB2300129C8D /* SerialPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SerialPort.h; sourceTree = "<group>"; };
+		6942525E0CC7EB2300129C8D /* SerialStream.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SerialStream.h; sourceTree = "<group>"; };
 		6942757707E0DCDD003DE3D9 /* MutexLock.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MutexLock.cc; sourceTree = "<group>"; };
 		6942779007E164EA003DE3D9 /* Thread.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Thread.cc; sourceTree = "<group>"; };
 		69469F6C09AA1D2000D1EC14 /* AgentData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = AgentData.cc; sourceTree = "<group>"; };
@@ -541,12 +1566,6 @@
 		69469F8109AA1D2000D1EC14 /* Macrodefs.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Macrodefs.h; sourceTree = "<group>"; };
 		69469F8209AA1D2000D1EC14 /* MapBuilder.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = MapBuilder.cc; sourceTree = "<group>"; };
 		69469F8309AA1D2000D1EC14 /* MapBuilder.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = MapBuilder.h; sourceTree = "<group>"; };
-		69469F8409AA1D2000D1EC14 /* Measures.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Measures.cc; sourceTree = "<group>"; };
-		69469F8509AA1D2000D1EC14 /* Measures.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Measures.h; sourceTree = "<group>"; };
-		69469F8609AA1D2000D1EC14 /* Particle.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Particle.cc; sourceTree = "<group>"; };
-		69469F8709AA1D2000D1EC14 /* Particle.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Particle.h; sourceTree = "<group>"; };
-		69469F8809AA1D2000D1EC14 /* ParticleFilter.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ParticleFilter.cc; sourceTree = "<group>"; };
-		69469F8909AA1D2000D1EC14 /* ParticleFilter.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ParticleFilter.h; sourceTree = "<group>"; };
 		69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ParticleShapes.cc; sourceTree = "<group>"; };
 		69469F8B09AA1D2000D1EC14 /* ParticleShapes.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ParticleShapes.h; sourceTree = "<group>"; };
 		69469F8D09AA1D2000D1EC14 /* Pilot.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Pilot.h; sourceTree = "<group>"; };
@@ -580,8 +1599,6 @@
 		69469FA909AA1D2100D1EC14 /* ShapeSpace.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeSpace.h; sourceTree = "<group>"; };
 		69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeSphere.cc; sourceTree = "<group>"; };
 		69469FAB09AA1D2100D1EC14 /* ShapeSphere.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeSphere.h; sourceTree = "<group>"; };
-		69469FAC09AA1D2100D1EC14 /* ShapeTypes.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeTypes.cc; sourceTree = "<group>"; };
-		69469FAD09AA1D2100D1EC14 /* ShapeTypes.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeTypes.h; sourceTree = "<group>"; };
 		69469FAE09AA1D2100D1EC14 /* Sketch.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Sketch.cc; sourceTree = "<group>"; };
 		69469FAF09AA1D2100D1EC14 /* Sketch.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Sketch.h; sourceTree = "<group>"; };
 		69469FB009AA1D2100D1EC14 /* SketchData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SketchData.h; sourceTree = "<group>"; };
@@ -619,11 +1636,22 @@
 		694E67E40AC308290087EC83 /* PitchEvent.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = PitchEvent.cc; sourceTree = "<group>"; };
 		694E67E50AC308290087EC83 /* PitchEvent.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = PitchEvent.h; sourceTree = "<group>"; };
 		694E684B0AC338CF0087EC83 /* PitchDetector.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = PitchDetector.cc; sourceTree = "<group>"; };
+		694F657F0C738659005A6654 /* CreateInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CreateInfo.h; sourceTree = "<group>"; };
+		694F65AA0C738675005A6654 /* CreateInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CreateInfo.h; sourceTree = "<group>"; };
 		6952B61A07DBFDCC00E2565F /* SemaphoreManager.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SemaphoreManager.h; sourceTree = "<group>"; };
 		6958D6890A5EE5AB00D46050 /* WorldStatePool.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = WorldStatePool.cc; sourceTree = "<group>"; };
 		6958D68A0A5EE5AB00D46050 /* WorldStatePool.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = WorldStatePool.h; sourceTree = "<group>"; };
+		695984730B8BF72200AB633A /* LocalizationParticleData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LocalizationParticleData.cc; sourceTree = "<group>"; };
+		695984740B8BF72200AB633A /* LocalizationParticleData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LocalizationParticleData.h; sourceTree = "<group>"; };
+		695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapeLocalizationParticle.cc; sourceTree = "<group>"; };
+		695984790B8BF76800AB633A /* ShapeLocalizationParticle.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ShapeLocalizationParticle.h; sourceTree = "<group>"; };
+		6959FAC20B08FF4D006F08BB /* colors.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = colors.cc; sourceTree = "<group>"; };
 		695F1AC80804A81800ACB3D7 /* BufferedImageGenerator.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = BufferedImageGenerator.cc; sourceTree = "<group>"; };
 		695F1AC90804A81800ACB3D7 /* BufferedImageGenerator.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = BufferedImageGenerator.h; sourceTree = "<group>"; };
+		695FC79B0CE62E4300069A68 /* PostureNode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = PostureNode.h; sourceTree = "<group>"; };
+		695FC7B30CE62E9500069A68 /* WaypointWalkNode.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = WaypointWalkNode.h; sourceTree = "<group>"; };
+		695FCB310CE8BFBD00069A68 /* PathPlanner.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = PathPlanner.cc; sourceTree = "<group>"; };
+		695FCB320CE8BFBD00069A68 /* PathPlanner.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = PathPlanner.h; sourceTree = "<group>"; };
 		69616DF90AA4EDED00E63351 /* SimulatorAdvanceFrameControl.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SimulatorAdvanceFrameControl.h; sourceTree = "<group>"; };
 		6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LookoutEvents.cc; sourceTree = "<group>"; };
 		6962F2EA0A917E33002DDEC9 /* LookoutEvents.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LookoutEvents.h; sourceTree = "<group>"; };
@@ -637,6 +1665,8 @@
 		69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = FlashIPAddrBehavior.cc; sourceTree = "<group>"; };
 		69750F060AC03FFE004FE3CF /* FlashIPAddrBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = FlashIPAddrBehavior.h; sourceTree = "<group>"; };
 		69750F070AC03FFE004FE3CF /* WorldStateVelDaemon.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = WorldStateVelDaemon.h; sourceTree = "<group>"; };
+		6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ConfigurationEditor.cc; sourceTree = "<group>"; };
+		6975CDCF0B6D67B800B2FAC9 /* ConfigurationEditor.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ConfigurationEditor.h; sourceTree = "<group>"; };
 		69761DBB0856207A007DB073 /* AiboComm.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = AiboComm.java; sourceTree = "<group>"; };
 		69761DBC0856207A007DB073 /* Base64.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = Base64.java; sourceTree = "<group>"; };
 		69761DBD0856207A007DB073 /* ClassPathModifier.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = ClassPathModifier.java; sourceTree = "<group>"; };
@@ -699,14 +1729,22 @@
 		69761DF60856207A007DB073 /* WorldModel2Conf.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = WorldModel2Conf.java; sourceTree = "<group>"; };
 		69761DF70856207A007DB073 /* WorldStateJointsListener.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = WorldStateJointsListener.java; sourceTree = "<group>"; };
 		69761DF80856207A007DB073 /* WorldStatePIDsListener.java */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.java; path = WorldStatePIDsListener.java; sourceTree = "<group>"; };
-		6976B20E0ACC669F00BA657B /* EntryPoint.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = EntryPoint.h; sourceTree = "<group>"; };
-		6976B20F0ACC669F00BA657B /* LoadFileThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = LoadFileThread.cc; sourceTree = "<group>"; };
-		6976B2100ACC669F00BA657B /* LoadFileThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = LoadFileThread.h; sourceTree = "<group>"; };
-		6976B2110ACC669F00BA657B /* LoadImageThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = LoadImageThread.cc; sourceTree = "<group>"; };
-		6976B2120ACC669F00BA657B /* LoadImageThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = LoadImageThread.h; sourceTree = "<group>"; };
 		69844A2A08CE5F7F00BCDD5C /* CameraStreamBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = CameraStreamBehavior.cc; sourceTree = "<group>"; };
 		69844A2B08CE5F7F00BCDD5C /* CameraStreamBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CameraStreamBehavior.h; sourceTree = "<group>"; };
+		69846B500B84F4C20011B614 /* LocalizationBehavior.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LocalizationBehavior.h; sourceTree = "<group>"; };
 		6985DA3408527479009FD05A /* tools */ = {isa = PBXFileReference; lastKnownFileType = folder; path = tools; sourceTree = TEKKOTSU_ROOT; };
+		6989FE210C66332F001B9A11 /* CommonERSInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CommonERSInfo.h; sourceTree = "<group>"; };
+		6989FE220C66332F001B9A11 /* CommonInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CommonInfo.h; sourceTree = "<group>"; };
+		6989FE230C66332F001B9A11 /* ERS2xxInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ERS2xxInfo.h; sourceTree = "<group>"; };
+		6989FE240C66332F001B9A11 /* ERS7Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ERS7Info.h; sourceTree = "<group>"; };
+		6989FE250C66332F001B9A11 /* ERS210Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ERS210Info.h; sourceTree = "<group>"; };
+		6989FE260C66332F001B9A11 /* ERS220Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ERS220Info.h; sourceTree = "<group>"; };
+		6989FE280C66332F001B9A11 /* LynxArm6Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LynxArm6Info.h; sourceTree = "<group>"; };
+		6989FE290C66332F001B9A11 /* QBotPlusInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = QBotPlusInfo.h; sourceTree = "<group>"; };
+		6989FE2A0C66332F001B9A11 /* QwerkInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = QwerkInfo.h; sourceTree = "<group>"; };
+		6989FE2B0C66332F001B9A11 /* Regis1Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Regis1Info.h; sourceTree = "<group>"; };
+		6989FE2C0C66332F001B9A11 /* RobotInfo.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RobotInfo.cc; sourceTree = "<group>"; };
+		6989FE2D0C66332F001B9A11 /* RobotInfo.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = RobotInfo.h; sourceTree = "<group>"; };
 		698A06D10955F0E4001A13D5 /* Cloneable.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Cloneable.h; sourceTree = "<group>"; };
 		698A071B09575F41001A13D5 /* plistBase.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plistBase.cc; sourceTree = "<group>"; };
 		698A071C09575F41001A13D5 /* plistBase.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = plistBase.h; sourceTree = "<group>"; };
@@ -759,17 +1797,34 @@
 		69A19963080ED8AE00540970 /* EchoBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = EchoBehavior.h; sourceTree = "<group>"; };
 		69A323C007E35646009D94E1 /* write_jpeg.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = write_jpeg.cc; sourceTree = "<group>"; };
 		69A323C107E35646009D94E1 /* write_jpeg.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = write_jpeg.h; sourceTree = "<group>"; };
-		69A6D61007CD2C7700CB4720 /* sim-ERS7 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "sim-ERS7"; sourceTree = BUILT_PRODUCTS_DIR; };
+		69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = ImageUtil.cc; sourceTree = "<group>"; };
+		69A5E2360BBD6CC8006D6EED /* ImageUtil.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = ImageUtil.h; sourceTree = "<group>"; };
+		69A5E2E60BBD9C37006D6EED /* DataSource.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = DataSource.h; sourceTree = "<group>"; };
+		69A5E2E70BBD9C37006D6EED /* EntryPoint.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = EntryPoint.h; sourceTree = "<group>"; };
+		69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LoadDataThread.cc; sourceTree = "<group>"; };
+		69A5E2EF0BBD9C37006D6EED /* LoadDataThread.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = LoadDataThread.h; sourceTree = "<group>"; };
+		69A5E2F30BBD9C37006D6EED /* minisim.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = minisim.h; sourceTree = "<group>"; };
+		69A5E2F40BBD9C37006D6EED /* MotionHook.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MotionHook.h; sourceTree = "<group>"; };
+		69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SoundPlayThread.cc; sourceTree = "<group>"; };
+		69A5E2F80BBD9C37006D6EED /* SoundPlayThread.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SoundPlayThread.h; sourceTree = "<group>"; };
+		69A6D61007CD2C7700CB4720 /* tekkotsu-ERS7 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "tekkotsu-ERS7"; sourceTree = BUILT_PRODUCTS_DIR; };
+		69A6E5DA0CDA51BE00039162 /* CreateCommands.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CreateCommands.h; sourceTree = "<group>"; };
+		69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = CreateDriver.cc; sourceTree = "<group>"; };
+		69A6E5DC0CDA51BE00039162 /* CreateDriver.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CreateDriver.h; sourceTree = "<group>"; };
 		69A7EBE909C7162E003DDD18 /* PollThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = PollThread.cc; sourceTree = "<group>"; };
 		69A7EBEA09C7162E003DDD18 /* PollThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = PollThread.h; sourceTree = "<group>"; };
-		69A7EC7909C79817003DDD18 /* TimerExecThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = TimerExecThread.cc; sourceTree = "<group>"; };
-		69A7EC7A09C79817003DDD18 /* TimerExecThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = TimerExecThread.h; sourceTree = "<group>"; };
-		69A7ED9909C88622003DDD18 /* MotionExecThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MotionExecThread.cc; sourceTree = "<group>"; };
-		69A7ED9A09C88622003DDD18 /* MotionExecThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = MotionExecThread.h; sourceTree = "<group>"; };
 		69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libreadline.dylib; path = /usr/lib/libedit.2.dylib; sourceTree = "<absolute>"; };
 		69A7EF2709C9EA77003DDD18 /* plistPrimitives.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = plistPrimitives.cc; sourceTree = "<group>"; };
 		69A7EF6F09C9FE5B003DDD18 /* attributes.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = attributes.h; sourceTree = "<group>"; };
 		69AA7D690860898300185BA2 /* MessageReceiver.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MessageReceiver.cc; sourceTree = "<group>"; };
+		69AA82280CC19CEE00DD162A /* RemoteEvents.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RemoteEvents.cc; sourceTree = "<group>"; };
+		69AA82290CC19CEE00DD162A /* RemoteEvents.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = RemoteEvents.h; sourceTree = "<group>"; };
+		69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RemoteRouter.cc; sourceTree = "<group>"; };
+		69AA822B0CC19CEE00DD162A /* RemoteRouter.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = RemoteRouter.h; sourceTree = "<group>"; };
+		69AA824B0CC19D3E00DD162A /* EventProxy.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = EventProxy.cc; sourceTree = "<group>"; };
+		69AA824C0CC19D3E00DD162A /* EventProxy.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = EventProxy.h; sourceTree = "<group>"; };
+		69AA82650CC19D8600DD162A /* RemoteState.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = RemoteState.cc; sourceTree = "<group>"; };
+		69AA82660CC19D8600DD162A /* RemoteState.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = RemoteState.h; sourceTree = "<group>"; };
 		69B344670A7152900021FBE6 /* PyramidData.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PyramidData.cc; sourceTree = "<group>"; };
 		69B344680A7152900021FBE6 /* PyramidData.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PyramidData.h; sourceTree = "<group>"; };
 		69B3446B0A7152AC0021FBE6 /* ShapePyramid.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = ShapePyramid.cc; sourceTree = "<group>"; };
@@ -782,32 +1837,28 @@
 		69B8DDC10AC44735003EC54A /* LGmixin.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = LGmixin.h; sourceTree = "<group>"; };
 		69B8DEC00AC4952D003EC54A /* DrawSkeletonBehavior.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = DrawSkeletonBehavior.h; sourceTree = "<group>"; };
 		69B8DEC10AC4952D003EC54A /* DrawVisObjBoundBehavior.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = DrawVisObjBoundBehavior.h; sourceTree = "<group>"; };
+		69BE64950BF979A800BC9A15 /* netstream.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = netstream.cc; sourceTree = "<group>"; };
+		69BE64960BF979A800BC9A15 /* netstream.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = netstream.h; sourceTree = "<group>"; };
+		69BE86B00C2F72440046EEAD /* RobotInfo.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = RobotInfo.cc; sourceTree = "<group>"; };
+		69CB303D0BCED185002F46DC /* SerialIO.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SerialIO.cc; sourceTree = "<group>"; };
+		69CB303E0BCED185002F46DC /* SerialIO.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = SerialIO.h; sourceTree = "<group>"; };
+		69CEAA290B779858004F6B1D /* MapBuilderRequest.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = MapBuilderRequest.h; sourceTree = "<group>"; };
+		69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Pilot.cc; sourceTree = "<group>"; };
+		69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PilotRequest.cc; sourceTree = "<group>"; };
+		69D0FBAD0B8F9B3500CC1DF1 /* PilotRequest.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PilotRequest.h; sourceTree = "<group>"; };
 		69D5F7BB09BB4DC9000602D2 /* MessageQueue.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MessageQueue.cc; sourceTree = "<group>"; };
 		69D5F82709BBDF0C000602D2 /* MessageQueueStatusThread.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = MessageQueueStatusThread.cc; sourceTree = "<group>"; };
 		69D5F82809BBDF0C000602D2 /* MessageQueueStatusThread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = MessageQueueStatusThread.h; sourceTree = "<group>"; };
-		69E0A75707CBD4F9008493CA /* SampleBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SampleBehavior.h; sourceTree = "<group>"; };
-		69E0A75807CBD4F9008493CA /* SampleMC.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SampleMC.h; sourceTree = "<group>"; };
+		69DE80FD0BE98C790045DCEE /* DeviceDriver.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = DeviceDriver.h; sourceTree = "<group>"; };
+		69DE81090BE98C840045DCEE /* CommPort.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = CommPort.h; sourceTree = "<group>"; };
 		69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupBackgroundBehaviors.cc; sourceTree = "<group>"; };
 		69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupFileAccess.cc; sourceTree = "<group>"; };
 		69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupModeSwitch.cc; sourceTree = "<group>"; };
 		69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupStatusReports.cc; sourceTree = "<group>"; };
 		69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupTekkotsuMon.cc; sourceTree = "<group>"; };
-		69E0A75E07CBD4F9008493CA /* StartupBehavior_SetupVision.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupVision.cc; sourceTree = "<group>"; };
 		69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior_SetupWalkEdit.cc; sourceTree = "<group>"; };
 		69E0A76007CBD4F9008493CA /* StartupBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = StartupBehavior.cc; sourceTree = "<group>"; };
 		69E0A76107CBD4F9008493CA /* StartupBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = StartupBehavior.h; sourceTree = "<group>"; };
-		69E0A76F07CBD52D008493CA /* Main.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Main.cc; sourceTree = "<group>"; };
-		69E0A77007CBD52D008493CA /* Main.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Main.h; sourceTree = "<group>"; };
-		69E0A77107CBD52D008493CA /* Motion.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Motion.cc; sourceTree = "<group>"; };
-		69E0A77207CBD52D008493CA /* Motion.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Motion.h; sourceTree = "<group>"; };
-		69E0A77307CBD52D008493CA /* Process.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Process.cc; sourceTree = "<group>"; };
-		69E0A77407CBD52D008493CA /* Process.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Process.h; sourceTree = "<group>"; };
-		69E0A77607CBD52D008493CA /* SharedGlobals.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SharedGlobals.cc; sourceTree = "<group>"; };
-		69E0A77707CBD52D008493CA /* SharedGlobals.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SharedGlobals.h; sourceTree = "<group>"; };
-		69E0A77807CBD52D008493CA /* Simulator.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Simulator.cc; sourceTree = "<group>"; };
-		69E0A77907CBD52D008493CA /* Simulator.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Simulator.h; sourceTree = "<group>"; };
-		69E0A77A07CBD52D008493CA /* SoundPlay.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SoundPlay.cc; sourceTree = "<group>"; };
-		69E0A77B07CBD52D008493CA /* SoundPlay.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SoundPlay.h; sourceTree = "<group>"; };
 		69E0A78C07CBD6BF008493CA /* BehaviorBase.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = BehaviorBase.cc; sourceTree = "<group>"; };
 		69E0A78D07CBD6BF008493CA /* BehaviorBase.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = BehaviorBase.h; sourceTree = "<group>"; };
 		69E0A78F07CBD6BF008493CA /* Controller.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Controller.cc; sourceTree = "<group>"; };
@@ -874,8 +1925,7 @@
 		69E0A7D207CBD6C0008493CA /* FollowHeadBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = FollowHeadBehavior.h; sourceTree = "<group>"; };
 		69E0A7D307CBD6C0008493CA /* FreezeTestBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = FreezeTestBehavior.h; sourceTree = "<group>"; };
 		69E0A7D407CBD6C0008493CA /* GroundPlaneBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = GroundPlaneBehavior.h; sourceTree = "<group>"; };
-		69E0A7D507CBD6C0008493CA /* HeadLevelBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = HeadLevelBehavior.h; sourceTree = "<group>"; };
-		69E0A7D607CBD6C0008493CA /* HelloWorldBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = HelloWorldBehavior.h; sourceTree = "<group>"; };
+		69E0A7D607CBD6C0008493CA /* HelloWorldBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = HelloWorldBehavior.h; sourceTree = "<group>"; wrapsLines = 0; };
 		69E0A7D707CBD6C0008493CA /* karmedbandit.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = karmedbandit.h; sourceTree = "<group>"; };
 		69E0A7D807CBD6C0008493CA /* KinematicSampleBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = KinematicSampleBehavior.h; sourceTree = "<group>"; };
 		69E0A7D907CBD6C0008493CA /* KinematicSampleBehavior2.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = KinematicSampleBehavior2.h; sourceTree = "<group>"; };
@@ -906,8 +1956,6 @@
 		69E0A7F507CBD6C0008493CA /* SegCamBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SegCamBehavior.h; sourceTree = "<group>"; };
 		69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SpeakerServer.cc; sourceTree = "<group>"; };
 		69E0A7F707CBD6C0008493CA /* SpeakerServer.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SpeakerServer.h; sourceTree = "<group>"; };
-		69E0A7F807CBD6C0008493CA /* SpiderMachineBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = SpiderMachineBehavior.cc; sourceTree = "<group>"; };
-		69E0A7F907CBD6C0008493CA /* SpiderMachineBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = SpiderMachineBehavior.h; sourceTree = "<group>"; };
 		69E0A7FA07CBD6C0008493CA /* ViewWMVarsBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = ViewWMVarsBehavior.h; sourceTree = "<group>"; };
 		69E0A7FB07CBD6C0008493CA /* WalkControllerBehavior.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = WalkControllerBehavior.cc; sourceTree = "<group>"; };
 		69E0A7FC07CBD6C0008493CA /* WalkControllerBehavior.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = WalkControllerBehavior.h; sourceTree = "<group>"; };
@@ -981,8 +2029,6 @@
 		69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = MotionSequenceEngine.cc; sourceTree = "<group>"; };
 		69E0A84607CBD6C0008493CA /* MotionSequenceEngine.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MotionSequenceEngine.h; sourceTree = "<group>"; };
 		69E0A84707CBD6C0008493CA /* MotionSequenceMC.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = MotionSequenceMC.h; sourceTree = "<group>"; };
-		69E0A84807CBD6C0008493CA /* OldHeadPointerMC.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = OldHeadPointerMC.cc; sourceTree = "<group>"; };
-		69E0A84907CBD6C0008493CA /* OldHeadPointerMC.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = OldHeadPointerMC.h; sourceTree = "<group>"; };
 		69E0A84A07CBD6C0008493CA /* OldKinematics.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = OldKinematics.cc; sourceTree = "<group>"; };
 		69E0A84B07CBD6C0008493CA /* OldKinematics.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = OldKinematics.h; sourceTree = "<group>"; };
 		69E0A84C07CBD6C0008493CA /* OutputCmd.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = OutputCmd.cc; sourceTree = "<group>"; };
@@ -1140,20 +2186,21 @@
 		69E0A99207CBD6C1008493CA /* Socket.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Socket.h; sourceTree = "<group>"; };
 		69E0A99307CBD6C1008493CA /* Wireless.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Wireless.cc; sourceTree = "<group>"; };
 		69E0A99407CBD6C1008493CA /* Wireless.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 30; path = Wireless.h; sourceTree = "<group>"; };
-		69E0AD5C07CBDE11008493CA /* sim-ERS210 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "sim-ERS210"; sourceTree = BUILT_PRODUCTS_DIR; };
+		69E0AD5C07CBDE11008493CA /* tekkotsu-ERS210 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "tekkotsu-ERS210"; sourceTree = BUILT_PRODUCTS_DIR; };
 		69E0AD8407CBED91008493CA /* Makefile */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
 		69E0AD8907CBEDAA008493CA /* Makefile */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
 		69E0AD9107CBEDC6008493CA /* Environment.conf */ = {isa = PBXFileReference; explicitFileType = sourcecode.make; fileEncoding = 30; path = Environment.conf; sourceTree = "<group>"; };
 		69E0ADB607CBF0AB008493CA /* libroboop.a */ = {isa = PBXFileReference; lastKnownFileType = archive.ar; name = libroboop.a; path = PLATFORM_LOCAL/Motion/roboop/libroboop.a; sourceTree = TEKKOTSU_BUILDDIR; };
 		69E0ADBD07CBF0F8008493CA /* libnewmat.a */ = {isa = PBXFileReference; lastKnownFileType = archive.ar; name = libnewmat.a; path = PLATFORM_LOCAL/Shared/newmat/libnewmat.a; sourceTree = TEKKOTSU_BUILDDIR; };
 		69E0ADC407CBF382008493CA /* libtekkotsu.a */ = {isa = PBXFileReference; lastKnownFileType = archive.ar; name = libtekkotsu.a; path = PLATFORM_LOCAL/TGT_ERS7/libtekkotsu.a; sourceTree = TEKKOTSU_BUILDDIR; };
-		69E0AFA807CBF79B008493CA /* sim-ERS7 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "sim-ERS7"; sourceTree = BUILT_PRODUCTS_DIR; };
-		69E0AFDC07CC0113008493CA /* libtekkotsu.a */ = {isa = PBXFileReference; lastKnownFileType = archive.ar; name = libtekkotsu.a; path = PLATFORM_LOCAL/TGT_ERS210/libtekkotsu.a; sourceTree = TEKKOTSU_BUILDDIR; };
+		69E0AFA807CBF79B008493CA /* tekkotsu-ERS7 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "tekkotsu-ERS7"; sourceTree = BUILT_PRODUCTS_DIR; };
+		69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = TorqueCalibrate.cc; sourceTree = "<group>"; };
+		69E62FEA0BAB4234009D8FC0 /* TorqueCalibrate.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = TorqueCalibrate.h; sourceTree = "<group>"; };
+		69E6662F0B4D822A00575707 /* tekkotsu-LYNXARM6 */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = "tekkotsu-LYNXARM6"; sourceTree = BUILT_PRODUCTS_DIR; };
 		69E666B607F0CE3A005F4FA9 /* plist.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = plist.h; sourceTree = "<group>"; };
 		69E666BB07F0CE51005F4FA9 /* plist.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = plist.cc; sourceTree = "<group>"; };
 		69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = XMLLoadSave.cc; sourceTree = "<group>"; };
 		69E6674807F1E23A005F4FA9 /* XMLLoadSave.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = XMLLoadSave.h; sourceTree = "<group>"; };
-		69E6696407F3398F005F4FA9 /* SimConfig.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = SimConfig.h; sourceTree = "<group>"; };
 		69E78D0109F6C114000385E9 /* StackTrace.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = StackTrace.cc; sourceTree = "<group>"; };
 		69E78D0209F6C114000385E9 /* StackTrace.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = StackTrace.h; sourceTree = "<group>"; };
 		69EA8B9207EB57480047DA8D /* libiconv.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libiconv.dylib; path = /usr/lib/libiconv.dylib; sourceTree = "<absolute>"; };
@@ -1165,7 +2212,23 @@
 		69ED0BB807DEABF700114CD2 /* Thread.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = Thread.h; sourceTree = "<group>"; };
 		69EE6BE00A951DC900DB7B88 /* EntryPoint.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = EntryPoint.cc; sourceTree = "<group>"; };
 		69EE6BE10A951DC900DB7B88 /* EntryPoint.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = EntryPoint.h; sourceTree = "<group>"; };
+		69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = HolonomicMotionModel.cc; sourceTree = "<group>"; };
+		69EE785E0B68024A00202E66 /* HolonomicMotionModel.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = HolonomicMotionModel.h; sourceTree = "<group>"; };
+		69EF73230B57E27500FF5476 /* zignor.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = zignor.cc; sourceTree = "<group>"; };
+		69EF73240B57E27500FF5476 /* zignor.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = zignor.h; sourceTree = "<group>"; };
+		69EF73250B57E27500FF5476 /* zigrandom.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = zigrandom.cc; sourceTree = "<group>"; };
+		69EF73260B57E27500FF5476 /* zigrandom.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = zigrandom.h; sourceTree = "<group>"; };
+		69EF732B0B57E28800FF5476 /* ParticleFilter.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = ParticleFilter.h; sourceTree = "<group>"; };
+		69EF73450B57F42500FF5476 /* LocalizationParticle.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LocalizationParticle.h; sourceTree = "<group>"; };
+		69EF737B0B57F79B00FF5476 /* DeadReckoningBehavior.h */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.c.h; path = DeadReckoningBehavior.h; sourceTree = "<group>"; };
+		69EF74820B59EC7200FF5476 /* Measures.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Measures.cc; sourceTree = "<group>"; };
+		69EF74830B59EC7200FF5476 /* Measures.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Measures.h; sourceTree = "<group>"; };
 		69F6038C0A40800F0052ECA1 /* Resource.h */ = {isa = PBXFileReference; explicitFileType = sourcecode.cpp.h; fileEncoding = 4; path = Resource.h; sourceTree = "<group>"; };
+		69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PFShapeLocalization.cc; sourceTree = "<group>"; };
+		69F74F090B98920D00FBA370 /* PFShapeLocalization.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PFShapeLocalization.h; sourceTree = "<group>"; };
+		69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = PFShapeSLAM.cc; sourceTree = "<group>"; };
+		69F74F0B0B98920D00FBA370 /* PFShapeSLAM.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = PFShapeSLAM.h; sourceTree = "<group>"; };
+		69F7556E0B9BA9D300FBA370 /* LynxArm6Info.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LynxArm6Info.h; sourceTree = "<group>"; };
 		69FA48F5084C389D0003A261 /* UPennWalkMC.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = UPennWalkMC.cc; sourceTree = "<group>"; };
 		69FA48F6084C389D0003A261 /* UPennWalkMC.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = UPennWalkMC.h; sourceTree = "<group>"; };
 		69FA48F9084C38E80003A261 /* Graphics.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Graphics.cc; sourceTree = "<group>"; };
@@ -1175,17 +2238,54 @@
 /* End PBXFileReference section */
 
 /* Begin PBXFrameworksBuildPhase section */
+		692E74870B9E77C100816584 /* Frameworks */ = {
+			isa = PBXFrameworksBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				692E74890B9E77C100816584 /* libiconv.dylib in Frameworks */,
+				692E748A0B9E77C100816584 /* libxml2.dylib in Frameworks */,
+				692E748B0B9E77C100816584 /* libz.dylib in Frameworks */,
+				692E748C0B9E77C100816584 /* libjpeg.dylib in Frameworks */,
+				692E748D0B9E77C100816584 /* libpng12.dylib in Frameworks */,
+				692E748E0B9E77C100816584 /* libreadline.dylib in Frameworks */,
+				692E74AD0B9E7B3A00816584 /* libIce.dylib in Frameworks */,
+				692E74AE0B9E7B3A00816584 /* libIceUtil.dylib in Frameworks */,
+				69CB31030BCFD575002F46DC /* libGlacier2.dylib in Frameworks */,
+				693776D00C175812001E2C9E /* Carbon.framework in Frameworks */,
+				693776F90C17581F001E2C9E /* QuickTime.framework in Frameworks */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+		693D0AE60C52643E00A56175 /* Frameworks */ = {
+			isa = PBXFrameworksBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				693D0AE70C52643E00A56175 /* libiconv.dylib in Frameworks */,
+				693D0AE80C52643E00A56175 /* libxml2.dylib in Frameworks */,
+				693D0AE90C52643E00A56175 /* libz.dylib in Frameworks */,
+				693D0AEA0C52643E00A56175 /* libjpeg.dylib in Frameworks */,
+				693D0AEB0C52643E00A56175 /* libpng12.dylib in Frameworks */,
+				693D0AEC0C52643E00A56175 /* libreadline.dylib in Frameworks */,
+				693D0AED0C52643E00A56175 /* libGlacier2.dylib in Frameworks */,
+				693D0AEE0C52643E00A56175 /* libIce.dylib in Frameworks */,
+				693D0AEF0C52643E00A56175 /* libIceUtil.dylib in Frameworks */,
+				693D0AF00C52643E00A56175 /* Carbon.framework in Frameworks */,
+				693D0AF10C52643E00A56175 /* QuickTime.framework in Frameworks */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
 		69E0AC5A07CBDE11008493CA /* Frameworks */ = {
 			isa = PBXFrameworksBuildPhase;
 			buildActionMask = 2147483647;
 			files = (
-				69E0AC5B07CBDE11008493CA /* libstdc++.a in Frameworks */,
 				69EA8B9B07EB57480047DA8D /* libiconv.dylib in Frameworks */,
 				69EA8B9C07EB57480047DA8D /* libxml2.dylib in Frameworks */,
 				69EA8B9D07EB57480047DA8D /* libz.dylib in Frameworks */,
 				694AB43707F48A860071A2AE /* libjpeg.dylib in Frameworks */,
 				694AB43807F48A860071A2AE /* libpng12.dylib in Frameworks */,
 				69A7EE7009C8F70C003DDD18 /* libreadline.dylib in Frameworks */,
+				693776CE0C175812001E2C9E /* Carbon.framework in Frameworks */,
+				693776F70C17581F001E2C9E /* QuickTime.framework in Frameworks */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -1202,6 +2302,26 @@
 				694AB43B07F48A860071A2AE /* libjpeg.dylib in Frameworks */,
 				694AB43C07F48A860071A2AE /* libpng12.dylib in Frameworks */,
 				69A7EE7209C8F70C003DDD18 /* libreadline.dylib in Frameworks */,
+				693776CC0C175812001E2C9E /* Carbon.framework in Frameworks */,
+				693776F50C17581F001E2C9E /* QuickTime.framework in Frameworks */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+		69E666240B4D822A00575707 /* Frameworks */ = {
+			isa = PBXFrameworksBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				69E666260B4D822A00575707 /* libiconv.dylib in Frameworks */,
+				69E666270B4D822A00575707 /* libxml2.dylib in Frameworks */,
+				69E666280B4D822A00575707 /* libz.dylib in Frameworks */,
+				69E666290B4D822A00575707 /* libjpeg.dylib in Frameworks */,
+				69E6662A0B4D822A00575707 /* libpng12.dylib in Frameworks */,
+				69E6662B0B4D822A00575707 /* libreadline.dylib in Frameworks */,
+				69401DBD0C131EBD00FE900C /* libGlacier2.dylib in Frameworks */,
+				69401DC00C131EC600FE900C /* libIce.dylib in Frameworks */,
+				69401DC10C131EC600FE900C /* libIceUtil.dylib in Frameworks */,
+				693776CF0C175812001E2C9E /* Carbon.framework in Frameworks */,
+				693776F80C17581F001E2C9E /* QuickTime.framework in Frameworks */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -1209,13 +2329,14 @@
 			isa = PBXFrameworksBuildPhase;
 			buildActionMask = 2147483647;
 			files = (
-				69A6D6DB07CD7C9500CB4720 /* libstdc++.a in Frameworks */,
 				69EA8B9507EB57480047DA8D /* libiconv.dylib in Frameworks */,
 				69EA8B9607EB57480047DA8D /* libxml2.dylib in Frameworks */,
 				69EA8B9707EB57480047DA8D /* libz.dylib in Frameworks */,
 				694AB43907F48A860071A2AE /* libjpeg.dylib in Frameworks */,
 				694AB43A07F48A860071A2AE /* libpng12.dylib in Frameworks */,
 				69A7EE7109C8F70C003DDD18 /* libreadline.dylib in Frameworks */,
+				693776CD0C175812001E2C9E /* Carbon.framework in Frameworks */,
+				693776F60C17581F001E2C9E /* QuickTime.framework in Frameworks */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -1225,11 +2346,14 @@
 		0249A662FF388D9811CA2CEA /* External Frameworks and Libraries */ = {
 			isa = PBXGroup;
 			children = (
+				693776D10C17581F001E2C9E /* QuickTime.framework */,
+				693776B70C175811001E2C9E /* Carbon.framework */,
+				692E74A90B9E7B3A00816584 /* libGlacier2.dylib */,
+				692E74AA0B9E7B3A00816584 /* libIce.dylib */,
+				692E74AB0B9E7B3A00816584 /* libIceUtil.dylib */,
 				69E0ADC407CBF382008493CA /* libtekkotsu.a */,
-				69E0AFDC07CC0113008493CA /* libtekkotsu.a */,
 				69E0ADB607CBF0AB008493CA /* libroboop.a */,
 				69E0ADBD07CBF0F8008493CA /* libnewmat.a */,
-				0249A663FF388D9811CA2CEA /* libstdc++.a */,
 				694AB43507F48A860071A2AE /* libjpeg.dylib */,
 				694AB43607F48A860071A2AE /* libpng12.dylib */,
 				69EA8B9307EB57480047DA8D /* libxml2.dylib */,
@@ -1238,14 +2362,13 @@
 				69A7EE6F09C8F70C003DDD18 /* libreadline.dylib */,
 			);
 			name = "External Frameworks and Libraries";
-			sourceTree = "<group>";
+			sourceTree = SOURCE_ROOT;
 		};
 		08FB7794FE84155DC02AAC07 /* sim */ = {
 			isa = PBXGroup;
 			children = (
 				08FB7795FE84155DC02AAC07 /* Project Files */,
 				69E0A74A07CBBECE008493CA /* Tekkotsu Source */,
-				69E0A75107CBBF2D008493CA /* local */,
 				6985DA3408527479009FD05A /* tools */,
 				69761DB608562012007DB073 /* mon */,
 				69E0AD5D07CBDE11008493CA /* Products */,
@@ -1258,14 +2381,12 @@
 			isa = PBXGroup;
 			children = (
 				696B01FB07D6906E000C1839 /* ms */,
-				69E0A75707CBD4F9008493CA /* SampleBehavior.h */,
-				69E0A75807CBD4F9008493CA /* SampleMC.h */,
 				69E0A75907CBD4F9008493CA /* StartupBehavior_SetupBackgroundBehaviors.cc */,
 				69E0A75A07CBD4F9008493CA /* StartupBehavior_SetupFileAccess.cc */,
 				69E0A75B07CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc */,
 				69E0A75C07CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc */,
 				69E0A75D07CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc */,
-				69E0A75E07CBD4F9008493CA /* StartupBehavior_SetupVision.cc */,
+				6933B8800C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc */,
 				69E0A75F07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc */,
 				69E0A76007CBD4F9008493CA /* StartupBehavior.cc */,
 				69E0A76107CBD4F9008493CA /* StartupBehavior.h */,
@@ -1278,6 +2399,131 @@
 			name = "Project Files";
 			sourceTree = "<group>";
 		};
+		692E74C60B9E7CA200816584 /* terk */ = {
+			isa = PBXGroup;
+			children = (
+				692E75050B9E81EA00816584 /* peer */,
+				693D0E7A0C572C4C00A56175 /* DataCache.cc */,
+				693D0E7B0C572C4C00A56175 /* DataCache.h */,
+				692E74D10B9E7CDD00816584 /* ImageCache.cc */,
+				692E74D20B9E7CDD00816584 /* ImageCache.h */,
+				692E74D30B9E7CDD00816584 /* ObjectPingThread.cc */,
+				692E74D40B9E7CDD00816584 /* ObjectPingThread.h */,
+				692E74D50B9E7CDD00816584 /* PropertyManagerI.cc */,
+				692E74D60B9E7CDD00816584 /* PropertyManagerI.h */,
+				692E74D70B9E7CDD00816584 /* QwerkBot.cc */,
+				692E74D80B9E7CDD00816584 /* QwerkBot.h */,
+				69CB303D0BCED185002F46DC /* SerialIO.cc */,
+				69CB303E0BCED185002F46DC /* SerialIO.h */,
+				6942525C0CC7EB2300129C8D /* SerialPort.cc */,
+				6942525D0CC7EB2300129C8D /* SerialPort.h */,
+				6942525E0CC7EB2300129C8D /* SerialStream.h */,
+				692E74DB0B9E7CDD00816584 /* TeRKPeerCommon.cc */,
+				692E74DC0B9E7CDD00816584 /* TeRKPeerCommon.h */,
+				692E74DD0B9E7CDD00816584 /* TerkUserI.cc */,
+				692E74DE0B9E7CDD00816584 /* TerkUserI.h */,
+			);
+			path = terk;
+			sourceTree = "<group>";
+		};
+		692E75050B9E81EA00816584 /* peer */ = {
+			isa = PBXGroup;
+			children = (
+				692E751D0B9E821800816584 /* MRPLPeer.cc */,
+				692E751E0B9E821800816584 /* MRPLPeer.h */,
+			);
+			path = peer;
+			sourceTree = "<group>";
+		};
+		693AD5870C205BE80053F7DE /* tekkotsu */ = {
+			isa = PBXGroup;
+			children = (
+				693AD5880C205BE80053F7DE /* Main.cc */,
+				693AD5890C205BE80053F7DE /* Main.h */,
+				693AD58A0C205BE80053F7DE /* Motion.cc */,
+				693AD58B0C205BE80053F7DE /* Motion.h */,
+				693AD58C0C205BE80053F7DE /* MotionExecThread.cc */,
+				693AD58D0C205BE80053F7DE /* MotionExecThread.h */,
+				693AD58E0C205BE80053F7DE /* Process.cc */,
+				693AD58F0C205BE80053F7DE /* Process.h */,
+				693AD5900C205BE80053F7DE /* SharedGlobals.cc */,
+				693AD5910C205BE80053F7DE /* SharedGlobals.h */,
+				693AD5920C205BE80053F7DE /* sim.cc */,
+				693AD5930C205BE80053F7DE /* sim.h */,
+				693AD5940C205BE80053F7DE /* SimConfig.h */,
+				693AD5950C205BE80053F7DE /* Simulator.cc */,
+				693AD5960C205BE80053F7DE /* Simulator.h */,
+				693AD5970C205BE80053F7DE /* SoundPlay.cc */,
+				693AD5980C205BE80053F7DE /* SoundPlay.h */,
+				693AD5990C205BE80053F7DE /* TimerExecThread.cc */,
+				693AD59A0C205BE80053F7DE /* TimerExecThread.h */,
+			);
+			path = tekkotsu;
+			sourceTree = "<group>";
+		};
+		69401C860C1291F000FE900C /* CommPorts */ = {
+			isa = PBXGroup;
+			children = (
+				69401C870C1291F000FE900C /* ExecutableCommPort.cc */,
+				69401C880C1291F000FE900C /* ExecutableCommPort.h */,
+				69401C890C1291F000FE900C /* FileSystemCommPort.cc */,
+				69401C8A0C1291F000FE900C /* FileSystemCommPort.h */,
+				69401C8B0C1291F000FE900C /* NetworkCommPort.cc */,
+				69401C8C0C1291F000FE900C /* NetworkCommPort.h */,
+				69401C8D0C1291F000FE900C /* RedirectionCommPort.cc */,
+				69401C8E0C1291F000FE900C /* RedirectionCommPort.h */,
+				69401C8F0C1291F000FE900C /* SerialCommPort.cc */,
+				69401C900C1291F000FE900C /* SerialCommPort.h */,
+			);
+			path = CommPorts;
+			sourceTree = "<group>";
+		};
+		69401CA50C12922400FE900C /* DataSources */ = {
+			isa = PBXGroup;
+			children = (
+				6937766B0C17358B001E2C9E /* CameraSourceOSX.cc */,
+				6937766C0C17358C001E2C9E /* CameraSourceOSX.h */,
+				69401CA60C12922400FE900C /* FileSystemDataSource.cc */,
+				69401CA70C12922400FE900C /* FileSystemDataSource.h */,
+				69401CA80C12922400FE900C /* FileSystemImageSource.cc */,
+				69401CA90C12922400FE900C /* FileSystemImageSource.h */,
+			);
+			path = DataSources;
+			sourceTree = "<group>";
+		};
+		69401CAA0C12922400FE900C /* DeviceDrivers */ = {
+			isa = PBXGroup;
+			children = (
+				693776720C17359B001E2C9E /* CameraDriverOSX.cc */,
+				693776730C17359B001E2C9E /* CameraDriverOSX.h */,
+				693D23EB0C91B9C3006D6505 /* CameraDriverV4L.cc */,
+				693D23EC0C91B9C3006D6505 /* CameraDriverV4L.h */,
+				69A6E5DA0CDA51BE00039162 /* CreateCommands.h */,
+				69A6E5DB0CDA51BE00039162 /* CreateDriver.cc */,
+				69A6E5DC0CDA51BE00039162 /* CreateDriver.h */,
+				694252150CC7E65B00129C8D /* Dynamixel.cc */,
+				694252160CC7E65B00129C8D /* Dynamixel.h */,
+				693D0C680C52FE6D00A56175 /* ImageStreamDriver.cc */,
+				693D0C690C52FE6D00A56175 /* ImageStreamDriver.h */,
+				69401CAB0C12922400FE900C /* LoggedDataDriver.cc */,
+				69401CAC0C12922400FE900C /* LoggedDataDriver.h */,
+				69401CAD0C12922400FE900C /* SSC32Driver.cc */,
+				69401CAE0C12922400FE900C /* SSC32Driver.h */,
+				693D0E540C56632100A56175 /* TeRKDriver.cc */,
+				693D0E550C56632100A56175 /* TeRKDriver.h */,
+			);
+			path = DeviceDrivers;
+			sourceTree = "<group>";
+		};
+		69401CAF0C12922400FE900C /* MotionHooks */ = {
+			isa = PBXGroup;
+			children = (
+				69401CB00C12922400FE900C /* IPCMotionHook.cc */,
+				69401CB10C12922400FE900C /* IPCMotionHook.h */,
+			);
+			path = MotionHooks;
+			sourceTree = "<group>";
+		};
 		69469F6B09AA1D2000D1EC14 /* DualCoding */ = {
 			isa = PBXGroup;
 			children = (
@@ -1298,6 +2544,8 @@
 				69469F7A09AA1D2000D1EC14 /* EndPoint.h */,
 				69469F7B09AA1D2000D1EC14 /* LineData.cc */,
 				69469F7C09AA1D2000D1EC14 /* LineData.h */,
+				695984730B8BF72200AB633A /* LocalizationParticleData.cc */,
+				695984740B8BF72200AB633A /* LocalizationParticleData.h */,
 				69469F7F09AA1D2000D1EC14 /* Lookout.cc */,
 				69469F8009AA1D2000D1EC14 /* Lookout.h */,
 				6962F2FD0A917F40002DDEC9 /* LookoutRequests.cc */,
@@ -1305,15 +2553,19 @@
 				69469F8109AA1D2000D1EC14 /* Macrodefs.h */,
 				69469F8209AA1D2000D1EC14 /* MapBuilder.cc */,
 				69469F8309AA1D2000D1EC14 /* MapBuilder.h */,
-				69469F8409AA1D2000D1EC14 /* Measures.cc */,
-				69469F8509AA1D2000D1EC14 /* Measures.h */,
-				69469F8609AA1D2000D1EC14 /* Particle.cc */,
-				69469F8709AA1D2000D1EC14 /* Particle.h */,
-				69469F8809AA1D2000D1EC14 /* ParticleFilter.cc */,
-				69469F8909AA1D2000D1EC14 /* ParticleFilter.h */,
+				69CEAA290B779858004F6B1D /* MapBuilderRequest.h */,
 				69469F8A09AA1D2000D1EC14 /* ParticleShapes.cc */,
 				69469F8B09AA1D2000D1EC14 /* ParticleShapes.h */,
+				695FCB310CE8BFBD00069A68 /* PathPlanner.cc */,
+				695FCB320CE8BFBD00069A68 /* PathPlanner.h */,
+				69F74F080B98920D00FBA370 /* PFShapeLocalization.cc */,
+				69F74F090B98920D00FBA370 /* PFShapeLocalization.h */,
+				69F74F0A0B98920D00FBA370 /* PFShapeSLAM.cc */,
+				69F74F0B0B98920D00FBA370 /* PFShapeSLAM.h */,
+				69D0FB9F0B8F82C900CC1DF1 /* Pilot.cc */,
 				69469F8D09AA1D2000D1EC14 /* Pilot.h */,
+				69D0FBAC0B8F9B3500CC1DF1 /* PilotRequest.cc */,
+				69D0FBAD0B8F9B3500CC1DF1 /* PilotRequest.h */,
 				69469F8E09AA1D2000D1EC14 /* Point.cc */,
 				69469F8F09AA1D2000D1EC14 /* Point.h */,
 				69469F9009AA1D2000D1EC14 /* PointData.cc */,
@@ -1336,6 +2588,8 @@
 				69469F9F09AA1D2000D1EC14 /* ShapeFuns.h */,
 				69469FA009AA1D2100D1EC14 /* ShapeLine.cc */,
 				69469FA109AA1D2100D1EC14 /* ShapeLine.h */,
+				695984780B8BF76800AB633A /* ShapeLocalizationParticle.cc */,
+				695984790B8BF76800AB633A /* ShapeLocalizationParticle.h */,
 				69469FA209AA1D2100D1EC14 /* ShapePoint.cc */,
 				69469FA309AA1D2100D1EC14 /* ShapePoint.h */,
 				69469FA409AA1D2100D1EC14 /* ShapePolygon.cc */,
@@ -1348,8 +2602,10 @@
 				69469FA909AA1D2100D1EC14 /* ShapeSpace.h */,
 				69469FAA09AA1D2100D1EC14 /* ShapeSphere.cc */,
 				69469FAB09AA1D2100D1EC14 /* ShapeSphere.h */,
-				69469FAC09AA1D2100D1EC14 /* ShapeTypes.cc */,
-				69469FAD09AA1D2100D1EC14 /* ShapeTypes.h */,
+				693A55FA0BE1479800509F85 /* ShapeTarget.cc */,
+				693A55FB0BE1479800509F85 /* ShapeTarget.h */,
+				693A55F40BE1478000509F85 /* ShapeTypes.cc */,
+				693A55F50BE1478000509F85 /* ShapeTypes.h */,
 				69469FAE09AA1D2100D1EC14 /* Sketch.cc */,
 				69469FAF09AA1D2100D1EC14 /* Sketch.h */,
 				69469FB009AA1D2100D1EC14 /* SketchData.h */,
@@ -1369,6 +2625,8 @@
 				69469FBC09AA1D2100D1EC14 /* SphereData.h */,
 				69469FBD09AA1D2100D1EC14 /* susan.cc */,
 				69469FBE09AA1D2100D1EC14 /* susan.h */,
+				693A55EA0BE1474500509F85 /* TargetData.cc */,
+				693A55EB0BE1474500509F85 /* TargetData.h */,
 				69469FBF09AA1D2100D1EC14 /* ViewerConnection.cc */,
 				69469FC009AA1D2100D1EC14 /* ViewerConnection.h */,
 				69469FC109AA1D2100D1EC14 /* visops.cc */,
@@ -1388,6 +2646,7 @@
 			children = (
 				69750F030AC03FFE004FE3CF /* AutoGetupBehavior.h */,
 				69750F040AC03FFE004FE3CF /* BatteryMonitorBehavior.h */,
+				69EF737B0B57F79B00FF5476 /* DeadReckoningBehavior.h */,
 				69750F050AC03FFE004FE3CF /* FlashIPAddrBehavior.cc */,
 				69750F060AC03FFE004FE3CF /* FlashIPAddrBehavior.h */,
 				69750F070AC03FFE004FE3CF /* WorldStateVelDaemon.h */,
@@ -1465,6 +2724,26 @@
 			path = tools/mon/org/tekkotsu/mon;
 			sourceTree = TEKKOTSU_ROOT;
 		};
+		6989FE1C0C6632AE001B9A11 /* RobotInfos */ = {
+			isa = PBXGroup;
+			children = (
+				6989FE2D0C66332F001B9A11 /* RobotInfo.h */,
+				6989FE2C0C66332F001B9A11 /* RobotInfo.cc */,
+				6989FE220C66332F001B9A11 /* CommonInfo.h */,
+				6989FE210C66332F001B9A11 /* CommonERSInfo.h */,
+				6989FE230C66332F001B9A11 /* ERS2xxInfo.h */,
+				6989FE240C66332F001B9A11 /* ERS7Info.h */,
+				6989FE250C66332F001B9A11 /* ERS210Info.h */,
+				6989FE260C66332F001B9A11 /* ERS220Info.h */,
+				694F65AA0C738675005A6654 /* CreateInfo.h */,
+				6989FE280C66332F001B9A11 /* LynxArm6Info.h */,
+				6989FE290C66332F001B9A11 /* QBotPlusInfo.h */,
+				6989FE2A0C66332F001B9A11 /* QwerkInfo.h */,
+				6989FE2B0C66332F001B9A11 /* Regis1Info.h */,
+			);
+			name = RobotInfos;
+			sourceTree = "<group>";
+		};
 		6994F3C907D4D35F003A7628 /* IPC */ = {
 			isa = PBXGroup;
 			children = (
@@ -1475,8 +2754,8 @@
 				69D5F82809BBDF0C000602D2 /* MessageQueueStatusThread.h */,
 				69AA7D690860898300185BA2 /* MessageReceiver.cc */,
 				6994F3CD07D4D35F003A7628 /* MessageReceiver.h */,
-				6994F3CE07D4D35F003A7628 /* MutexLock.h */,
 				6942757707E0DCDD003DE3D9 /* MutexLock.cc */,
+				6994F3CE07D4D35F003A7628 /* MutexLock.h */,
 				69A7EBE909C7162E003DDD18 /* PollThread.cc */,
 				69A7EBEA09C7162E003DDD18 /* PollThread.h */,
 				6994F3D107D4D35F003A7628 /* ProcessID.cc */,
@@ -1552,12 +2831,22 @@
 			isa = PBXGroup;
 			children = (
 				6994F5B807D68E41003A7628 /* Makefile.local */,
-				6976B20E0ACC669F00BA657B /* EntryPoint.h */,
-				6976B20F0ACC669F00BA657B /* LoadFileThread.cc */,
-				6976B2100ACC669F00BA657B /* LoadFileThread.h */,
-				6976B2110ACC669F00BA657B /* LoadImageThread.cc */,
-				6976B2120ACC669F00BA657B /* LoadImageThread.h */,
-				690564F20819531A00613A0E /* minisim.h */,
+				69A5E2F30BBD9C37006D6EED /* minisim.h */,
+				69DE81090BE98C840045DCEE /* CommPort.h */,
+				69401C860C1291F000FE900C /* CommPorts */,
+				69A5E2E60BBD9C37006D6EED /* DataSource.h */,
+				69401CA50C12922400FE900C /* DataSources */,
+				69DE80FD0BE98C790045DCEE /* DeviceDriver.h */,
+				69401CAA0C12922400FE900C /* DeviceDrivers */,
+				69A5E2E70BBD9C37006D6EED /* EntryPoint.h */,
+				69A5E2EE0BBD9C37006D6EED /* LoadDataThread.cc */,
+				69A5E2EF0BBD9C37006D6EED /* LoadDataThread.h */,
+				69A5E2F40BBD9C37006D6EED /* MotionHook.h */,
+				69401CAF0C12922400FE900C /* MotionHooks */,
+				69A5E2F70BBD9C37006D6EED /* SoundPlayThread.cc */,
+				69A5E2F80BBD9C37006D6EED /* SoundPlayThread.h */,
+				693AD5870C205BE80053F7DE /* tekkotsu */,
+				692E74C60B9E7CA200816584 /* terk */,
 			);
 			path = local;
 			sourceTree = "<group>";
@@ -1599,40 +2888,6 @@
 			name = "Tekkotsu Source";
 			sourceTree = TEKKOTSU_ROOT;
 		};
-		69E0A75107CBBF2D008493CA /* local */ = {
-			isa = PBXGroup;
-			children = (
-				69E0A75607CBD4A2008493CA /* sim */,
-			);
-			path = local;
-			sourceTree = TEKKOTSU_ROOT;
-		};
-		69E0A75607CBD4A2008493CA /* sim */ = {
-			isa = PBXGroup;
-			children = (
-				692CD63407F8C46B00604100 /* sim.cc */,
-				6934224207D408E600BB3331 /* sim.h */,
-				69E0A76F07CBD52D008493CA /* Main.cc */,
-				69E0A77007CBD52D008493CA /* Main.h */,
-				69E0A77107CBD52D008493CA /* Motion.cc */,
-				69E0A77207CBD52D008493CA /* Motion.h */,
-				69A7ED9909C88622003DDD18 /* MotionExecThread.cc */,
-				69A7ED9A09C88622003DDD18 /* MotionExecThread.h */,
-				69E0A77307CBD52D008493CA /* Process.cc */,
-				69E0A77407CBD52D008493CA /* Process.h */,
-				69E0A77607CBD52D008493CA /* SharedGlobals.cc */,
-				69E0A77707CBD52D008493CA /* SharedGlobals.h */,
-				69E6696407F3398F005F4FA9 /* SimConfig.h */,
-				69E0A77807CBD52D008493CA /* Simulator.cc */,
-				69E0A77907CBD52D008493CA /* Simulator.h */,
-				69E0A77A07CBD52D008493CA /* SoundPlay.cc */,
-				69E0A77B07CBD52D008493CA /* SoundPlay.h */,
-				69A7EC7909C79817003DDD18 /* TimerExecThread.cc */,
-				69A7EC7A09C79817003DDD18 /* TimerExecThread.h */,
-			);
-			path = sim;
-			sourceTree = "<group>";
-		};
 		69E0A78B07CBD6BF008493CA /* Behaviors */ = {
 			isa = PBXGroup;
 			children = (
@@ -1663,6 +2918,8 @@
 				69E0A79407CBD6BF008493CA /* BehaviorReportControl.h */,
 				69E0A79507CBD6BF008493CA /* BehaviorSwitchActivatorControl.h */,
 				69E0A79607CBD6BF008493CA /* BehaviorSwitchControl.h */,
+				6975CDCE0B6D67B800B2FAC9 /* ConfigurationEditor.cc */,
+				6975CDCF0B6D67B800B2FAC9 /* ConfigurationEditor.h */,
 				69E0A79707CBD6BF008493CA /* ControlBase.cc */,
 				69E0A79807CBD6BF008493CA /* ControlBase.h */,
 				69E0A79907CBD6C0008493CA /* DumpFileControl.h */,
@@ -1698,6 +2955,8 @@
 				69E0A7B607CBD6C0008493CA /* StringInputControl.cc */,
 				69E0A7B707CBD6C0008493CA /* StringInputControl.h */,
 				69E0A7B807CBD6C0008493CA /* ToggleControl.h */,
+				69E62FE50BAB422A009D8FC0 /* TorqueCalibrate.cc */,
+				69E62FEA0BAB4234009D8FC0 /* TorqueCalibrate.h */,
 				69E0A7B907CBD6C0008493CA /* ValueEditControl.h */,
 				69E0A7BA07CBD6C0008493CA /* ValueSetControl.h */,
 				69E0A7BB07CBD6C0008493CA /* WalkCalibration.cc */,
@@ -1730,11 +2989,11 @@
 				69E0A7D207CBD6C0008493CA /* FollowHeadBehavior.h */,
 				69E0A7D307CBD6C0008493CA /* FreezeTestBehavior.h */,
 				69E0A7D407CBD6C0008493CA /* GroundPlaneBehavior.h */,
-				69E0A7D507CBD6C0008493CA /* HeadLevelBehavior.h */,
 				69E0A7D607CBD6C0008493CA /* HelloWorldBehavior.h */,
 				69E0A7D707CBD6C0008493CA /* karmedbandit.h */,
 				69E0A7D807CBD6C0008493CA /* KinematicSampleBehavior.h */,
 				69E0A7D907CBD6C0008493CA /* KinematicSampleBehavior2.h */,
+				69846B500B84F4C20011B614 /* LocalizationBehavior.h */,
 				69970AC4083DB2C60069D95C /* LogTestMachine.h */,
 				69B8DDBD0AC44586003EC54A /* LookAtPointBehavior.h */,
 				69E0A7DA07CBD6C0008493CA /* LookForSoundBehavior.h */,
@@ -1777,12 +3036,12 @@
 				69E0A7F307CBD6C0008493CA /* RawCamBehavior.h */,
 				693D801208ABF46D00AC993E /* RegionCamBehavior.cc */,
 				693D801308ABF46D00AC993E /* RegionCamBehavior.h */,
+				693D0B1A0C52687D00A56175 /* RoverControllerBehavior.cc */,
+				693D0B1B0C52687D00A56175 /* RoverControllerBehavior.h */,
 				69E0A7F407CBD6C0008493CA /* SegCamBehavior.cc */,
 				69E0A7F507CBD6C0008493CA /* SegCamBehavior.h */,
 				69E0A7F607CBD6C0008493CA /* SpeakerServer.cc */,
 				69E0A7F707CBD6C0008493CA /* SpeakerServer.h */,
-				69E0A7F807CBD6C0008493CA /* SpiderMachineBehavior.cc */,
-				69E0A7F907CBD6C0008493CA /* SpiderMachineBehavior.h */,
 				69970AC0083DB2760069D95C /* StewartPlatformBehavior.cc */,
 				69970AC3083DB2830069D95C /* StewartPlatformBehavior.h */,
 				69FA4901084C39230003A261 /* UPennWalkControllerBehavior.cc */,
@@ -1804,15 +3063,17 @@
 				69E0A80207CBD6C0008493CA /* GroupNode.h */,
 				69E0A80307CBD6C0008493CA /* HeadPointerNode.h */,
 				69E0A80407CBD6C0008493CA /* LedNode.h */,
+				6966753B0926558A00405769 /* MCNode.cc */,
+				693C86E7090EE6F00058EE92 /* MCNode.h */,
 				69E0A80507CBD6C0008493CA /* MotionSequenceNode.h */,
 				69E0A80607CBD6C0008493CA /* OutputNode.h */,
+				695FC79B0CE62E4300069A68 /* PostureNode.h */,
 				69E0A80807CBD6C0008493CA /* SoundNode.h */,
 				69E0A80907CBD6C0008493CA /* TailWagNode.h */,
 				69E0A80A07CBD6C0008493CA /* WalkNode.h */,
 				69E0A80B07CBD6C0008493CA /* WalkToTargetNode.cc */,
 				69E0A80C07CBD6C0008493CA /* WalkToTargetNode.h */,
-				693C86E7090EE6F00058EE92 /* MCNode.h */,
-				6966753B0926558A00405769 /* MCNode.cc */,
+				695FC7B30CE62E9500069A68 /* WaypointWalkNode.h */,
 			);
 			path = Nodes;
 			sourceTree = "<group>";
@@ -1845,6 +3106,8 @@
 				69E0A82207CBD6C0008493CA /* EventGeneratorBase.cc */,
 				69E0A82307CBD6C0008493CA /* EventGeneratorBase.h */,
 				69E0A82407CBD6C0008493CA /* EventListener.h */,
+				69AA824B0CC19D3E00DD162A /* EventProxy.cc */,
+				69AA824C0CC19D3E00DD162A /* EventProxy.h */,
 				69E0A82507CBD6C0008493CA /* EventRouter.cc */,
 				69E0A82607CBD6C0008493CA /* EventRouter.h */,
 				69E0A82707CBD6C0008493CA /* EventTranslator.cc */,
@@ -1855,8 +3118,13 @@
 				69E0A82C07CBD6C0008493CA /* LocomotionEvent.h */,
 				6962F2E90A917E33002DDEC9 /* LookoutEvents.cc */,
 				6962F2EA0A917E33002DDEC9 /* LookoutEvents.h */,
+				694252380CC7E98D00129C8D /* NetworkBuffer.h */,
 				694E67E40AC308290087EC83 /* PitchEvent.cc */,
 				694E67E50AC308290087EC83 /* PitchEvent.h */,
+				69AA82280CC19CEE00DD162A /* RemoteEvents.cc */,
+				69AA82290CC19CEE00DD162A /* RemoteEvents.h */,
+				69AA822A0CC19CEE00DD162A /* RemoteRouter.cc */,
+				69AA822B0CC19CEE00DD162A /* RemoteRouter.h */,
 				69E0A82D07CBD6C0008493CA /* SegmentedColorFilterBankEvent.h */,
 				69E0A82E07CBD6C0008493CA /* TextMsgEvent.cc */,
 				69E0A82F07CBD6C0008493CA /* TextMsgEvent.h */,
@@ -1878,6 +3146,8 @@
 				69E0A83707CBD6C0008493CA /* gvector.h */,
 				69E0A83807CBD6C0008493CA /* HeadPointerMC.cc */,
 				69E0A83907CBD6C0008493CA /* HeadPointerMC.h */,
+				69EE785D0B68024A00202E66 /* HolonomicMotionModel.cc */,
+				69EE785E0B68024A00202E66 /* HolonomicMotionModel.h */,
 				69E0A83A07CBD6C0008493CA /* Kinematics.cc */,
 				69E0A83B07CBD6C0008493CA /* Kinematics.h */,
 				69E0A83C07CBD6C0008493CA /* LedEngine.cc */,
@@ -1892,8 +3162,6 @@
 				69E0A84507CBD6C0008493CA /* MotionSequenceEngine.cc */,
 				69E0A84607CBD6C0008493CA /* MotionSequenceEngine.h */,
 				69E0A84707CBD6C0008493CA /* MotionSequenceMC.h */,
-				69E0A84807CBD6C0008493CA /* OldHeadPointerMC.cc */,
-				69E0A84907CBD6C0008493CA /* OldHeadPointerMC.h */,
 				69E0A84A07CBD6C0008493CA /* OldKinematics.cc */,
 				69E0A84B07CBD6C0008493CA /* OldKinematics.h */,
 				69E0A84C07CBD6C0008493CA /* OutputCmd.cc */,
@@ -1961,30 +3229,43 @@
 		69E0A89107CBD6C0008493CA /* Shared */ = {
 			isa = PBXGroup;
 			children = (
+				6989FE1C0C6632AE001B9A11 /* RobotInfos */,
 				69A7EF6F09C9FE5B003DDD18 /* attributes.h */,
 				691C805508255F6300E8E256 /* Base64.cc */,
 				691C805C08255F6D00E8E256 /* Base64.h */,
 				69E0A89207CBD6C0008493CA /* Buffer.cc */,
 				69E0A89307CBD6C0008493CA /* Buffer.h */,
 				698A06D10955F0E4001A13D5 /* Cloneable.h */,
+				691FC35E0B4EDCF600246924 /* CommonERSInfo.h */,
 				69E0A89407CBD6C0008493CA /* CommonInfo.h */,
 				69E0A89507CBD6C0008493CA /* Config.cc */,
 				69E0A89607CBD6C0008493CA /* Config.h */,
+				694F657F0C738659005A6654 /* CreateInfo.h */,
 				69E0A89707CBD6C0008493CA /* debuget.h */,
 				69E0A89807CBD6C0008493CA /* ERS210Info.h */,
 				69E0A89907CBD6C0008493CA /* ERS220Info.h */,
 				69E0A89A07CBD6C0008493CA /* ERS2xxInfo.h */,
 				69E0A89B07CBD6C0008493CA /* ERS7Info.h */,
+				693E65710BF3C04400A5D8B8 /* Factories.h */,
 				69E0A89C07CBD6C0008493CA /* Factory.h */,
+				693E649F0BF113FA00A5D8B8 /* FamilyFactory.h */,
 				69E0A89D07CBD6C0008493CA /* get_time.cc */,
 				69E0A89E07CBD6C0008493CA /* get_time.h */,
+				69A5E2350BBD6CC8006D6EED /* ImageUtil.cc */,
+				69A5E2360BBD6CC8006D6EED /* ImageUtil.h */,
+				693E673A0BF5185500A5D8B8 /* InstanceTracker.h */,
 				69E0A89F07CBD6C0008493CA /* jpeg-6b */,
 				69E0A8F807CBD6C1008493CA /* LoadSave.cc */,
 				69E0A8F907CBD6C1008493CA /* LoadSave.h */,
+				69EF73450B57F42500FF5476 /* LocalizationParticle.h */,
+				69F7556E0B9BA9D300FBA370 /* LynxArm6Info.h */,
 				69EB5B540A41CCD700415C6B /* MarkScope.h */,
 				69E0A8FB07CBD6C1008493CA /* mathutils.h */,
+				69EF74820B59EC7200FF5476 /* Measures.cc */,
+				69EF74830B59EC7200FF5476 /* Measures.h */,
 				69E0A8FD07CBD6C1008493CA /* newmat */,
 				69E0A95707CBD6C1008493CA /* ODataFormats.h */,
+				69EF732B0B57E28800FF5476 /* ParticleFilter.h */,
 				69E666BB07F0CE51005F4FA9 /* plist.cc */,
 				69E666B607F0CE3A005F4FA9 /* plist.h */,
 				698A071B09575F41001A13D5 /* plistBase.cc */,
@@ -1997,10 +3278,16 @@
 				69E0A95B07CBD6C1008493CA /* Profiler.h */,
 				69E0A95C07CBD6C1008493CA /* ProjectInterface.cc */,
 				69E0A95D07CBD6C1008493CA /* ProjectInterface.h */,
+				693688250C594E3900D54726 /* QBotPlusInfo.h */,
+				6917A76E0BB1BCCA00F0B40B /* QwerkInfo.h */,
 				69E0A96007CBD6C1008493CA /* ReferenceCounter.h */,
+				693D09D50C525FA000A56175 /* Regis1Info.h */,
+				69AA82650CC19D8600DD162A /* RemoteState.cc */,
+				69AA82660CC19D8600DD162A /* RemoteState.h */,
 				69EB5B530A41CCD700415C6B /* Resource.cc */,
 				69F6038C0A40800F0052ECA1 /* Resource.h */,
 				69EB5B2C0A41C8DE00415C6B /* ResourceAccessor.h */,
+				69BE86B00C2F72440046EEAD /* RobotInfo.cc */,
 				69E0A96107CBD6C1008493CA /* RobotInfo.h */,
 				69E78D0109F6C114000385E9 /* StackTrace.cc */,
 				69E78D0209F6C114000385E9 /* StackTrace.h */,
@@ -2017,6 +3304,10 @@
 				6958D68A0A5EE5AB00D46050 /* WorldStatePool.h */,
 				69E6674707F1E23A005F4FA9 /* XMLLoadSave.cc */,
 				69E6674807F1E23A005F4FA9 /* XMLLoadSave.h */,
+				69EF73230B57E27500FF5476 /* zignor.cc */,
+				69EF73240B57E27500FF5476 /* zignor.h */,
+				69EF73250B57E27500FF5476 /* zigrandom.cc */,
+				69EF73260B57E27500FF5476 /* zigrandom.h */,
 			);
 			path = Shared;
 			sourceTree = "<group>";
@@ -2024,6 +3315,8 @@
 		69E0A89F07CBD6C0008493CA /* jpeg-6b */ = {
 			isa = PBXGroup;
 			children = (
+				693D09C70C525F7E00A56175 /* jpeg_istream_src.cc */,
+				693D09C80C525F7E00A56175 /* jpeg_istream_src.h */,
 				69E0A8DE07CBD6C1008493CA /* jpeg_mem_dest.cc */,
 				69E0A8DF07CBD6C1008493CA /* jpeg_mem_dest.h */,
 				694B36560A190FE2002ABC4C /* jpeg_mem_src.cc */,
@@ -2123,6 +3416,7 @@
 				69E0A97B07CBD6C1008493CA /* cmv_threshold.h */,
 				69E0A97C07CBD6C1008493CA /* cmv_types.h */,
 				69E0A97D07CBD6C1008493CA /* cmvision.h */,
+				6959FAC20B08FF4D006F08BB /* colors.cc */,
 				69E0A97E07CBD6C1008493CA /* colors.h */,
 				69E0A97F07CBD6C1008493CA /* FilterBankGenerator.cc */,
 				69E0A98007CBD6C1008493CA /* FilterBankGenerator.h */,
@@ -2153,8 +3447,11 @@
 				69E0A98F07CBD6C1008493CA /* DummySocket.h */,
 				69B8DDC00AC44735003EC54A /* LGmixin.cc */,
 				69B8DDC10AC44735003EC54A /* LGmixin.h */,
+				69BE64950BF979A800BC9A15 /* netstream.cc */,
+				69BE64960BF979A800BC9A15 /* netstream.h */,
 				69E0A99107CBD6C1008493CA /* Socket.cc */,
 				69E0A99207CBD6C1008493CA /* Socket.h */,
+				6942521E0CC7E8DC00129C8D /* SocketListener.h */,
 				69E0A99307CBD6C1008493CA /* Wireless.cc */,
 				69E0A99407CBD6C1008493CA /* Wireless.h */,
 			);
@@ -2164,9 +3461,12 @@
 		69E0AD5D07CBDE11008493CA /* Products */ = {
 			isa = PBXGroup;
 			children = (
-				69E0AD5C07CBDE11008493CA /* sim-ERS210 */,
-				69E0AFA807CBF79B008493CA /* sim-ERS7 */,
-				69A6D61007CD2C7700CB4720 /* sim-ERS7 */,
+				69E0AD5C07CBDE11008493CA /* tekkotsu-ERS210 */,
+				69E0AFA807CBF79B008493CA /* tekkotsu-ERS7 */,
+				69A6D61007CD2C7700CB4720 /* tekkotsu-ERS7 */,
+				69E6662F0B4D822A00575707 /* tekkotsu-LYNXARM6 */,
+				692E74920B9E77C100816584 /* tekkotsu-QBOTPLUS */,
+				693D0AF50C52643E00A56175 /* tekkotsu-REGIS1 */,
 			);
 			name = Products;
 			sourceTree = "<group>";
@@ -2191,9 +3491,43 @@
 /* End PBXLegacyTarget section */
 
 /* Begin PBXNativeTarget section */
-		69E0AB9A07CBDE11008493CA /* sim (ERS-210) */ = {
+		692E73990B9E77C100816584 /* tekkotsu-QBotPlus */ = {
 			isa = PBXNativeTarget;
-			buildConfigurationList = 69FD50320881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-210)" */;
+			buildConfigurationList = 692E748F0B9E77C100816584 /* Build configuration list for PBXNativeTarget "tekkotsu-QBotPlus" */;
+			buildPhases = (
+				692E739A0B9E77C100816584 /* Sources */,
+				692E74870B9E77C100816584 /* Frameworks */,
+			);
+			buildRules = (
+			);
+			dependencies = (
+			);
+			name = "tekkotsu-QBotPlus";
+			productInstallPath = "$(HOME)/bin";
+			productName = sim;
+			productReference = 692E74920B9E77C100816584 /* tekkotsu-QBOTPLUS */;
+			productType = "com.apple.product-type.tool";
+		};
+		693D09E50C52643E00A56175 /* tekkotsu-Regis1 */ = {
+			isa = PBXNativeTarget;
+			buildConfigurationList = 693D0AF20C52643E00A56175 /* Build configuration list for PBXNativeTarget "tekkotsu-Regis1" */;
+			buildPhases = (
+				693D09E60C52643E00A56175 /* Sources */,
+				693D0AE60C52643E00A56175 /* Frameworks */,
+			);
+			buildRules = (
+			);
+			dependencies = (
+			);
+			name = "tekkotsu-Regis1";
+			productInstallPath = "$(HOME)/bin";
+			productName = sim;
+			productReference = 693D0AF50C52643E00A56175 /* tekkotsu-REGIS1 */;
+			productType = "com.apple.product-type.tool";
+		};
+		69E0AB9A07CBDE11008493CA /* tekkotsu-ERS210 */ = {
+			isa = PBXNativeTarget;
+			buildConfigurationList = 69FD50320881E74900E825BA /* Build configuration list for PBXNativeTarget "tekkotsu-ERS210" */;
 			buildPhases = (
 				69E0AB9B07CBDE11008493CA /* Sources */,
 				69E0AC5A07CBDE11008493CA /* Frameworks */,
@@ -2202,15 +3536,15 @@
 			);
 			dependencies = (
 			);
-			name = "sim (ERS-210)";
+			name = "tekkotsu-ERS210";
 			productInstallPath = "$(HOME)/bin";
 			productName = sim;
-			productReference = 69E0AD5C07CBDE11008493CA /* sim-ERS210 */;
+			productReference = 69E0AD5C07CBDE11008493CA /* tekkotsu-ERS210 */;
 			productType = "com.apple.product-type.tool";
 		};
-		69E0AFA707CBF79B008493CA /* sim (ERS-7) Light */ = {
+		69E0AFA707CBF79B008493CA /* tekkotsu-ERS7 Light */ = {
 			isa = PBXNativeTarget;
-			buildConfigurationList = 69FD502E0881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-7) Light" */;
+			buildConfigurationList = 69FD502E0881E74900E825BA /* Build configuration list for PBXNativeTarget "tekkotsu-ERS7 Light" */;
 			buildPhases = (
 				69E0AFA507CBF79B008493CA /* Sources */,
 				69E0AFA607CBF79B008493CA /* Frameworks */,
@@ -2219,14 +3553,31 @@
 			);
 			dependencies = (
 			);
-			name = "sim (ERS-7) Light";
+			name = "tekkotsu-ERS7 Light";
 			productName = "sim (ERS-7) Light";
-			productReference = 69E0AFA807CBF79B008493CA /* sim-ERS7 */;
+			productReference = 69E0AFA807CBF79B008493CA /* tekkotsu-ERS7 */;
 			productType = "com.apple.product-type.tool";
 		};
-		8DD76F620486A84900D96B5E /* sim (ERS-7) */ = {
+		69E6653E0B4D822A00575707 /* tekkotsu-LynxArm6 */ = {
 			isa = PBXNativeTarget;
-			buildConfigurationList = 69FD502A0881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-7)" */;
+			buildConfigurationList = 69E6662C0B4D822A00575707 /* Build configuration list for PBXNativeTarget "tekkotsu-LynxArm6" */;
+			buildPhases = (
+				69E6653F0B4D822A00575707 /* Sources */,
+				69E666240B4D822A00575707 /* Frameworks */,
+			);
+			buildRules = (
+			);
+			dependencies = (
+			);
+			name = "tekkotsu-LynxArm6";
+			productInstallPath = "$(HOME)/bin";
+			productName = sim;
+			productReference = 69E6662F0B4D822A00575707 /* tekkotsu-LYNXARM6 */;
+			productType = "com.apple.product-type.tool";
+		};
+		8DD76F620486A84900D96B5E /* tekkotsu-ERS7 */ = {
+			isa = PBXNativeTarget;
+			buildConfigurationList = 69FD502A0881E74900E825BA /* Build configuration list for PBXNativeTarget "tekkotsu-ERS7" */;
 			buildPhases = (
 				8DD76F640486A84900D96B5E /* Sources */,
 				8DD76F660486A84900D96B5E /* Frameworks */,
@@ -2235,10 +3586,10 @@
 			);
 			dependencies = (
 			);
-			name = "sim (ERS-7)";
+			name = "tekkotsu-ERS7";
 			productInstallPath = "$(HOME)/bin";
 			productName = sim;
-			productReference = 69A6D61007CD2C7700CB4720 /* sim-ERS7 */;
+			productReference = 69A6D61007CD2C7700CB4720 /* tekkotsu-ERS7 */;
 			productType = "com.apple.product-type.tool";
 		};
 /* End PBXNativeTarget section */
@@ -2253,14 +3604,577 @@
 			projectDirPath = "";
 			targets = (
 				693D800E08ABBB4200AC993E /* Aperios Build */,
-				69E0AFA707CBF79B008493CA /* sim (ERS-7) Light */,
-				8DD76F620486A84900D96B5E /* sim (ERS-7) */,
-				69E0AB9A07CBDE11008493CA /* sim (ERS-210) */,
+				69E0AFA707CBF79B008493CA /* tekkotsu-ERS7 Light */,
+				8DD76F620486A84900D96B5E /* tekkotsu-ERS7 */,
+				69E0AB9A07CBDE11008493CA /* tekkotsu-ERS210 */,
+				69E6653E0B4D822A00575707 /* tekkotsu-LynxArm6 */,
+				693D09E50C52643E00A56175 /* tekkotsu-Regis1 */,
+				692E73990B9E77C100816584 /* tekkotsu-QBotPlus */,
 			);
 		};
 /* End PBXProject section */
 
 /* Begin PBXSourcesBuildPhase section */
+		692E739A0B9E77C100816584 /* Sources */ = {
+			isa = PBXSourcesBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				692E739B0B9E77C100816584 /* plistBase.cc in Sources */,
+				692E739C0B9E77C100816584 /* plistCollections.cc in Sources */,
+				692E739D0B9E77C100816584 /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */,
+				692E739E0B9E77C100816584 /* StartupBehavior_SetupFileAccess.cc in Sources */,
+				692E739F0B9E77C100816584 /* StartupBehavior_SetupModeSwitch.cc in Sources */,
+				692E73A00B9E77C100816584 /* StartupBehavior_SetupStatusReports.cc in Sources */,
+				692E73A10B9E77C100816584 /* StartupBehavior_SetupTekkotsuMon.cc in Sources */,
+				692E73A30B9E77C100816584 /* StartupBehavior_SetupWalkEdit.cc in Sources */,
+				692E73A40B9E77C100816584 /* StartupBehavior.cc in Sources */,
+				692E73AB0B9E77C100816584 /* BehaviorBase.cc in Sources */,
+				692E73AC0B9E77C100816584 /* Controller.cc in Sources */,
+				692E73AD0B9E77C100816584 /* ControlBase.cc in Sources */,
+				692E73AE0B9E77C100816584 /* EventLogger.cc in Sources */,
+				692E73AF0B9E77C100816584 /* FileBrowserControl.cc in Sources */,
+				692E73B00B9E77C100816584 /* FreeMemReportControl.cc in Sources */,
+				692E73B10B9E77C100816584 /* HelpControl.cc in Sources */,
+				692E73B20B9E77C100816584 /* PostureEditor.cc in Sources */,
+				692E73B30B9E77C100816584 /* RebootControl.cc in Sources */,
+				692E73B40B9E77C100816584 /* SensorObserverControl.cc in Sources */,
+				692E73B50B9E77C100816584 /* ShutdownControl.cc in Sources */,
+				692E73B60B9E77C100816584 /* StringInputControl.cc in Sources */,
+				692E73B70B9E77C100816584 /* WalkCalibration.cc in Sources */,
+				692E73B80B9E77C100816584 /* WaypointWalkControl.cc in Sources */,
+				692E73B90B9E77C100816584 /* ASCIIVisionBehavior.cc in Sources */,
+				692E73BA0B9E77C100816584 /* CameraBehavior.cc in Sources */,
+				692E73BB0B9E77C100816584 /* ChaseBallBehavior.cc in Sources */,
+				692E73BC0B9E77C100816584 /* DriveMeBehavior.cc in Sources */,
+				692E73BD0B9E77C100816584 /* ExploreMachine.cc in Sources */,
+				692E73BE0B9E77C100816584 /* FollowHeadBehavior.cc in Sources */,
+				692E73BF0B9E77C100816584 /* PaceTargetsMachine.cc in Sources */,
+				692E73C00B9E77C100816584 /* StareAtBallBehavior.cc in Sources */,
+				692E73C10B9E77C100816584 /* WallTestBehavior.cc in Sources */,
+				692E73C20B9E77C100816584 /* EStopControllerBehavior.cc in Sources */,
+				692E73C30B9E77C100816584 /* HeadPointControllerBehavior.cc in Sources */,
+				692E73C40B9E77C100816584 /* MicrophoneServer.cc in Sources */,
+				692E73C50B9E77C100816584 /* RawCamBehavior.cc in Sources */,
+				692E73C60B9E77C100816584 /* SegCamBehavior.cc in Sources */,
+				692E73C70B9E77C100816584 /* SpeakerServer.cc in Sources */,
+				692E73C80B9E77C100816584 /* WalkControllerBehavior.cc in Sources */,
+				692E73C90B9E77C100816584 /* WMMonitorBehavior.cc in Sources */,
+				692E73CA0B9E77C100816584 /* WorldStateSerializerBehavior.cc in Sources */,
+				692E73CB0B9E77C100816584 /* WalkToTargetNode.cc in Sources */,
+				692E73CC0B9E77C100816584 /* StateNode.cc in Sources */,
+				692E73CD0B9E77C100816584 /* Transition.cc in Sources */,
+				692E73CE0B9E77C100816584 /* RandomTrans.cc in Sources */,
+				692E73CF0B9E77C100816584 /* EventBase.cc in Sources */,
+				692E73D00B9E77C100816584 /* EventGeneratorBase.cc in Sources */,
+				692E73D10B9E77C100816584 /* EventRouter.cc in Sources */,
+				692E73D20B9E77C100816584 /* EventTranslator.cc in Sources */,
+				692E73D30B9E77C100816584 /* LocomotionEvent.cc in Sources */,
+				692E73D40B9E77C100816584 /* TextMsgEvent.cc in Sources */,
+				692E73D50B9E77C100816584 /* VisionObjectEvent.cc in Sources */,
+				692E73D60B9E77C100816584 /* EmergencyStopMC.cc in Sources */,
+				692E73D70B9E77C100816584 /* HeadPointerMC.cc in Sources */,
+				692E73D80B9E77C100816584 /* Kinematics.cc in Sources */,
+				692E73D90B9E77C100816584 /* LedEngine.cc in Sources */,
+				692E73DA0B9E77C100816584 /* MotionCommand.cc in Sources */,
+				692E73DB0B9E77C100816584 /* MotionManager.cc in Sources */,
+				692E73DC0B9E77C100816584 /* MotionSequenceEngine.cc in Sources */,
+				692E73DE0B9E77C100816584 /* OldKinematics.cc in Sources */,
+				692E73DF0B9E77C100816584 /* OutputCmd.cc in Sources */,
+				692E73E00B9E77C100816584 /* PostureEngine.cc in Sources */,
+				692E73E10B9E77C100816584 /* PostureMC.cc in Sources */,
+				692E73E20B9E77C100816584 /* clik.cpp in Sources */,
+				692E73E30B9E77C100816584 /* comp_dq.cpp in Sources */,
+				692E73E40B9E77C100816584 /* comp_dqp.cpp in Sources */,
+				692E73E50B9E77C100816584 /* config.cpp in Sources */,
+				692E73E60B9E77C100816584 /* control_select.cpp in Sources */,
+				692E73E70B9E77C100816584 /* controller.cpp in Sources */,
+				692E73E80B9E77C100816584 /* delta_t.cpp in Sources */,
+				692E73E90B9E77C100816584 /* dynamics.cpp in Sources */,
+				692E73EA0B9E77C100816584 /* dynamics_sim.cpp in Sources */,
+				692E73EB0B9E77C100816584 /* gnugraph.cpp in Sources */,
+				692E73EC0B9E77C100816584 /* homogen.cpp in Sources */,
+				692E73ED0B9E77C100816584 /* invkine.cpp in Sources */,
+				692E73EE0B9E77C100816584 /* kinemat.cpp in Sources */,
+				692E73EF0B9E77C100816584 /* quaternion.cpp in Sources */,
+				692E73F00B9E77C100816584 /* sensitiv.cpp in Sources */,
+				692E73F10B9E77C100816584 /* trajectory.cpp in Sources */,
+				692E73F20B9E77C100816584 /* utils.cpp in Sources */,
+				692E73F30B9E77C100816584 /* WalkMC.cc in Sources */,
+				692E73F40B9E77C100816584 /* Buffer.cc in Sources */,
+				692E73F50B9E77C100816584 /* Config.cc in Sources */,
+				692E73F60B9E77C100816584 /* get_time.cc in Sources */,
+				692E73F70B9E77C100816584 /* jpeg_mem_dest.cc in Sources */,
+				692E73F80B9E77C100816584 /* LoadSave.cc in Sources */,
+				692E73F90B9E77C100816584 /* bandmat.cpp in Sources */,
+				692E73FA0B9E77C100816584 /* cholesky.cpp in Sources */,
+				692E73FB0B9E77C100816584 /* evalue.cpp in Sources */,
+				692E73FC0B9E77C100816584 /* fft.cpp in Sources */,
+				692E73FD0B9E77C100816584 /* hholder.cpp in Sources */,
+				692E73FE0B9E77C100816584 /* jacobi.cpp in Sources */,
+				692E73FF0B9E77C100816584 /* myexcept.cpp in Sources */,
+				692E74000B9E77C100816584 /* newfft.cpp in Sources */,
+				692E74010B9E77C100816584 /* newmat1.cpp in Sources */,
+				692E74020B9E77C100816584 /* newmat2.cpp in Sources */,
+				692E74030B9E77C100816584 /* newmat3.cpp in Sources */,
+				692E74040B9E77C100816584 /* newmat4.cpp in Sources */,
+				692E74050B9E77C100816584 /* newmat5.cpp in Sources */,
+				692E74060B9E77C100816584 /* newmat6.cpp in Sources */,
+				692E74070B9E77C100816584 /* newmat7.cpp in Sources */,
+				692E74080B9E77C100816584 /* newmat8.cpp in Sources */,
+				692E74090B9E77C100816584 /* newmat9.cpp in Sources */,
+				692E740A0B9E77C100816584 /* newmatex.cpp in Sources */,
+				692E740B0B9E77C100816584 /* newmatnl.cpp in Sources */,
+				692E740C0B9E77C100816584 /* newmatrm.cpp in Sources */,
+				692E740D0B9E77C100816584 /* sort.cpp in Sources */,
+				692E740E0B9E77C100816584 /* submat.cpp in Sources */,
+				692E740F0B9E77C100816584 /* svd.cpp in Sources */,
+				692E74100B9E77C100816584 /* Profiler.cc in Sources */,
+				692E74110B9E77C100816584 /* ProjectInterface.cc in Sources */,
+				692E74120B9E77C100816584 /* string_util.cc in Sources */,
+				692E74130B9E77C100816584 /* TimeET.cc in Sources */,
+				692E74140B9E77C100816584 /* WMclass.cc in Sources */,
+				692E74150B9E77C100816584 /* WorldState.cc in Sources */,
+				692E74160B9E77C100816584 /* SoundManager.cc in Sources */,
+				692E74170B9E77C100816584 /* WAV.cc in Sources */,
+				692E74180B9E77C100816584 /* BallDetectionGenerator.cc in Sources */,
+				692E74190B9E77C100816584 /* CDTGenerator.cc in Sources */,
+				692E741A0B9E77C100816584 /* FilterBankGenerator.cc in Sources */,
+				692E741B0B9E77C100816584 /* InterleavedYUVGenerator.cc in Sources */,
+				692E741C0B9E77C100816584 /* JPEGGenerator.cc in Sources */,
+				692E741D0B9E77C100816584 /* RawCameraGenerator.cc in Sources */,
+				692E741E0B9E77C100816584 /* RegionGenerator.cc in Sources */,
+				692E741F0B9E77C100816584 /* RLEGenerator.cc in Sources */,
+				692E74200B9E77C100816584 /* SegmentedColorGenerator.cc in Sources */,
+				692E74210B9E77C100816584 /* Socket.cc in Sources */,
+				692E74220B9E77C100816584 /* Wireless.cc in Sources */,
+				692E74230B9E77C100816584 /* SemaphoreManager.cc in Sources */,
+				692E74240B9E77C100816584 /* ProcessID.cc in Sources */,
+				692E74250B9E77C100816584 /* RCRegion.cc in Sources */,
+				692E74260B9E77C100816584 /* SharedObject.cc in Sources */,
+				692E74270B9E77C100816584 /* MutexLock.cc in Sources */,
+				692E74280B9E77C100816584 /* Thread.cc in Sources */,
+				692E74290B9E77C100816584 /* write_jpeg.cc in Sources */,
+				692E742A0B9E77C100816584 /* plist.cc in Sources */,
+				692E742B0B9E77C100816584 /* XMLLoadSave.cc in Sources */,
+				692E742D0B9E77C100816584 /* BufferedImageGenerator.cc in Sources */,
+				692E742E0B9E77C100816584 /* EchoBehavior.cc in Sources */,
+				692E742F0B9E77C100816584 /* Base64.cc in Sources */,
+				692E74300B9E77C100816584 /* StewartPlatformBehavior.cc in Sources */,
+				692E74310B9E77C100816584 /* UPennWalkMC.cc in Sources */,
+				692E74320B9E77C100816584 /* Graphics.cc in Sources */,
+				692E74330B9E77C100816584 /* UPennWalkControllerBehavior.cc in Sources */,
+				692E74340B9E77C100816584 /* MessageReceiver.cc in Sources */,
+				692E74350B9E77C100816584 /* StareAtPawBehavior2.cc in Sources */,
+				692E74360B9E77C100816584 /* robot.cpp in Sources */,
+				692E74370B9E77C100816584 /* RegionCamBehavior.cc in Sources */,
+				692E74380B9E77C100816584 /* CameraStreamBehavior.cc in Sources */,
+				692E74390B9E77C100816584 /* MCNode.cc in Sources */,
+				692E743A0B9E77C100816584 /* AgentData.cc in Sources */,
+				692E743B0B9E77C100816584 /* BaseData.cc in Sources */,
+				692E743C0B9E77C100816584 /* BlobData.cc in Sources */,
+				692E743D0B9E77C100816584 /* BrickData.cc in Sources */,
+				692E743E0B9E77C100816584 /* EllipseData.cc in Sources */,
+				692E743F0B9E77C100816584 /* EndPoint.cc in Sources */,
+				692E74400B9E77C100816584 /* LineData.cc in Sources */,
+				692E74410B9E77C100816584 /* Lookout.cc in Sources */,
+				692E74420B9E77C100816584 /* MapBuilder.cc in Sources */,
+				692E74430B9E77C100816584 /* ParticleShapes.cc in Sources */,
+				692E74440B9E77C100816584 /* Point.cc in Sources */,
+				692E74450B9E77C100816584 /* PointData.cc in Sources */,
+				692E74460B9E77C100816584 /* PolygonData.cc in Sources */,
+				692E74470B9E77C100816584 /* Region.cc in Sources */,
+				692E74480B9E77C100816584 /* ShapeAgent.cc in Sources */,
+				692E74490B9E77C100816584 /* ShapeBlob.cc in Sources */,
+				692E744A0B9E77C100816584 /* ShapeBrick.cc in Sources */,
+				692E744B0B9E77C100816584 /* ShapeEllipse.cc in Sources */,
+				692E744C0B9E77C100816584 /* ShapeFuns.cc in Sources */,
+				692E744D0B9E77C100816584 /* ShapeLine.cc in Sources */,
+				692E744E0B9E77C100816584 /* ShapePoint.cc in Sources */,
+				692E744F0B9E77C100816584 /* ShapePolygon.cc in Sources */,
+				692E74500B9E77C100816584 /* ShapeRoot.cc in Sources */,
+				692E74510B9E77C100816584 /* ShapeSpace.cc in Sources */,
+				692E74520B9E77C100816584 /* ShapeSphere.cc in Sources */,
+				692E74540B9E77C100816584 /* Sketch.cc in Sources */,
+				692E74550B9E77C100816584 /* SketchDataRoot.cc in Sources */,
+				692E74560B9E77C100816584 /* SketchIndices.cc in Sources */,
+				692E74570B9E77C100816584 /* SketchRoot.cc in Sources */,
+				692E74580B9E77C100816584 /* SketchSpace.cc in Sources */,
+				692E74590B9E77C100816584 /* SphereData.cc in Sources */,
+				692E745A0B9E77C100816584 /* susan.cc in Sources */,
+				692E745B0B9E77C100816584 /* ViewerConnection.cc in Sources */,
+				692E745C0B9E77C100816584 /* visops.cc in Sources */,
+				692E745D0B9E77C100816584 /* VisualRoutinesBehavior.cc in Sources */,
+				692E745E0B9E77C100816584 /* VRmixin.cc in Sources */,
+				692E745F0B9E77C100816584 /* VisualRoutinesStateNode.cc in Sources */,
+				692E74600B9E77C100816584 /* MessageQueue.cc in Sources */,
+				692E74610B9E77C100816584 /* MessageQueueStatusThread.cc in Sources */,
+				692E74620B9E77C100816584 /* PollThread.cc in Sources */,
+				692E74650B9E77C100816584 /* plistPrimitives.cc in Sources */,
+				692E74660B9E77C100816584 /* StackTrace.cc in Sources */,
+				692E74670B9E77C100816584 /* SketchPoolRoot.cc in Sources */,
+				692E74680B9E77C100816584 /* jpeg_mem_src.cc in Sources */,
+				692E74690B9E77C100816584 /* Resource.cc in Sources */,
+				692E746A0B9E77C100816584 /* PNGGenerator.cc in Sources */,
+				692E746B0B9E77C100816584 /* WorldStatePool.cc in Sources */,
+				692E746C0B9E77C100816584 /* PyramidData.cc in Sources */,
+				692E746D0B9E77C100816584 /* ShapePyramid.cc in Sources */,
+				692E746E0B9E77C100816584 /* BrickOps.cc in Sources */,
+				692E746F0B9E77C100816584 /* LookoutEvents.cc in Sources */,
+				692E74700B9E77C100816584 /* Aibo3DControllerBehavior.cc in Sources */,
+				692E74710B9E77C100816584 /* LookoutRequests.cc in Sources */,
+				692E74720B9E77C100816584 /* TestBehaviors.cc in Sources */,
+				692E74730B9E77C100816584 /* TimerEvent.cc in Sources */,
+				692E74740B9E77C100816584 /* FlashIPAddrBehavior.cc in Sources */,
+				692E74750B9E77C100816584 /* PitchEvent.cc in Sources */,
+				692E74760B9E77C100816584 /* PitchDetector.cc in Sources */,
+				692E74770B9E77C100816584 /* LGmixin.cc in Sources */,
+				692E747A0B9E77C100816584 /* colors.cc in Sources */,
+				692E747B0B9E77C100816584 /* zignor.cc in Sources */,
+				692E747C0B9E77C100816584 /* zigrandom.cc in Sources */,
+				692E747D0B9E77C100816584 /* Measures.cc in Sources */,
+				692E747E0B9E77C100816584 /* HolonomicMotionModel.cc in Sources */,
+				692E747F0B9E77C100816584 /* ConfigurationEditor.cc in Sources */,
+				692E74810B9E77C100816584 /* LocalizationParticleData.cc in Sources */,
+				692E74820B9E77C100816584 /* ShapeLocalizationParticle.cc in Sources */,
+				692E74830B9E77C100816584 /* Pilot.cc in Sources */,
+				692E74840B9E77C100816584 /* PilotRequest.cc in Sources */,
+				692E74850B9E77C100816584 /* PFShapeLocalization.cc in Sources */,
+				692E74860B9E77C100816584 /* PFShapeSLAM.cc in Sources */,
+				692E74E10B9E7CDD00816584 /* ImageCache.cc in Sources */,
+				692E74E20B9E7CDD00816584 /* ObjectPingThread.cc in Sources */,
+				692E74E30B9E7CDD00816584 /* PropertyManagerI.cc in Sources */,
+				692E74E40B9E7CDD00816584 /* QwerkBot.cc in Sources */,
+				692E74E70B9E7CDD00816584 /* TerkUserI.cc in Sources */,
+				692E751F0B9E821800816584 /* MRPLPeer.cc in Sources */,
+				692E75210B9E825700816584 /* TeRKPeerCommon.cc in Sources */,
+				69E62FE90BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */,
+				69A5E2380BBD6CC8006D6EED /* ImageUtil.cc in Sources */,
+				69A5E3060BBD9C37006D6EED /* LoadDataThread.cc in Sources */,
+				69A5E3090BBD9C37006D6EED /* SoundPlayThread.cc in Sources */,
+				69CB30400BCED185002F46DC /* SerialIO.cc in Sources */,
+				693A55F30BE1474500509F85 /* TargetData.cc in Sources */,
+				693A55F90BE1478100509F85 /* ShapeTypes.cc in Sources */,
+				693A55FF0BE1479800509F85 /* ShapeTarget.cc in Sources */,
+				69BE64970BF979A800BC9A15 /* netstream.cc in Sources */,
+				69401C9B0C1291F000FE900C /* ExecutableCommPort.cc in Sources */,
+				69401C9C0C1291F000FE900C /* FileSystemCommPort.cc in Sources */,
+				69401C9D0C1291F000FE900C /* NetworkCommPort.cc in Sources */,
+				69401C9E0C1291F000FE900C /* RedirectionCommPort.cc in Sources */,
+				69401C9F0C1291F000FE900C /* SerialCommPort.cc in Sources */,
+				69401CBC0C12922400FE900C /* FileSystemDataSource.cc in Sources */,
+				69401CBD0C12922400FE900C /* FileSystemImageSource.cc in Sources */,
+				69401CBE0C12922400FE900C /* LoggedDataDriver.cc in Sources */,
+				69401CBF0C12922400FE900C /* SSC32Driver.cc in Sources */,
+				69401CC00C12922400FE900C /* IPCMotionHook.cc in Sources */,
+				693776710C17358C001E2C9E /* CameraSourceOSX.cc in Sources */,
+				693776780C17359B001E2C9E /* CameraDriverOSX.cc in Sources */,
+				693AD5BF0C205BE80053F7DE /* Main.cc in Sources */,
+				693AD5C00C205BE80053F7DE /* Motion.cc in Sources */,
+				693AD5C10C205BE80053F7DE /* MotionExecThread.cc in Sources */,
+				693AD5C20C205BE80053F7DE /* Process.cc in Sources */,
+				693AD5C30C205BE80053F7DE /* SharedGlobals.cc in Sources */,
+				693AD5C40C205BE80053F7DE /* sim.cc in Sources */,
+				693AD5C50C205BE80053F7DE /* Simulator.cc in Sources */,
+				693AD5C60C205BE80053F7DE /* SoundPlay.cc in Sources */,
+				693AD5C70C205BE80053F7DE /* TimerExecThread.cc in Sources */,
+				69BE87840C30215E0046EEAD /* RobotInfo.cc in Sources */,
+				693D09CA0C525F7E00A56175 /* jpeg_istream_src.cc in Sources */,
+				693D0B1D0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */,
+				693D0C6B0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */,
+				693D0E560C56632100A56175 /* TeRKDriver.cc in Sources */,
+				693D0E7C0C572C4C00A56175 /* DataCache.cc in Sources */,
+				6933B8810C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */,
+				693D23F10C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */,
+				69AA82340CC19CEE00DD162A /* RemoteEvents.cc in Sources */,
+				69AA82350CC19CEE00DD162A /* RemoteRouter.cc in Sources */,
+				69AA82510CC19D3E00DD162A /* EventProxy.cc in Sources */,
+				69AA826B0CC19D8600DD162A /* RemoteState.cc in Sources */,
+				694252190CC7E65B00129C8D /* Dynamixel.cc in Sources */,
+				694252610CC7EB2300129C8D /* SerialPort.cc in Sources */,
+				69A6E5DF0CDA51BE00039162 /* CreateDriver.cc in Sources */,
+				695FCB370CE8BFBD00069A68 /* PathPlanner.cc in Sources */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+		693D09E60C52643E00A56175 /* Sources */ = {
+			isa = PBXSourcesBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				693D09E70C52643E00A56175 /* plistBase.cc in Sources */,
+				693D09E80C52643E00A56175 /* plistCollections.cc in Sources */,
+				693D09E90C52643E00A56175 /* StartupBehavior.cc in Sources */,
+				693D09EA0C52643E00A56175 /* BehaviorBase.cc in Sources */,
+				693D09EB0C52643E00A56175 /* Controller.cc in Sources */,
+				693D09EC0C52643E00A56175 /* ControlBase.cc in Sources */,
+				693D09ED0C52643E00A56175 /* EventLogger.cc in Sources */,
+				693D09EE0C52643E00A56175 /* FileBrowserControl.cc in Sources */,
+				693D09EF0C52643E00A56175 /* FreeMemReportControl.cc in Sources */,
+				693D09F00C52643E00A56175 /* HelpControl.cc in Sources */,
+				693D09F10C52643E00A56175 /* PostureEditor.cc in Sources */,
+				693D09F20C52643E00A56175 /* RebootControl.cc in Sources */,
+				693D09F30C52643E00A56175 /* SensorObserverControl.cc in Sources */,
+				693D09F40C52643E00A56175 /* ShutdownControl.cc in Sources */,
+				693D09F50C52643E00A56175 /* StringInputControl.cc in Sources */,
+				693D09F60C52643E00A56175 /* WalkCalibration.cc in Sources */,
+				693D09F70C52643E00A56175 /* WaypointWalkControl.cc in Sources */,
+				693D09F80C52643E00A56175 /* ASCIIVisionBehavior.cc in Sources */,
+				693D09F90C52643E00A56175 /* ChaseBallBehavior.cc in Sources */,
+				693D09FA0C52643E00A56175 /* DriveMeBehavior.cc in Sources */,
+				693D09FB0C52643E00A56175 /* ExploreMachine.cc in Sources */,
+				693D09FC0C52643E00A56175 /* PaceTargetsMachine.cc in Sources */,
+				693D09FD0C52643E00A56175 /* StareAtBallBehavior.cc in Sources */,
+				693D09FE0C52643E00A56175 /* EStopControllerBehavior.cc in Sources */,
+				693D09FF0C52643E00A56175 /* HeadPointControllerBehavior.cc in Sources */,
+				693D0A000C52643E00A56175 /* MicrophoneServer.cc in Sources */,
+				693D0A010C52643E00A56175 /* RawCamBehavior.cc in Sources */,
+				693D0A020C52643E00A56175 /* SegCamBehavior.cc in Sources */,
+				693D0A030C52643E00A56175 /* SpeakerServer.cc in Sources */,
+				693D0A040C52643E00A56175 /* WalkControllerBehavior.cc in Sources */,
+				693D0A050C52643E00A56175 /* WMMonitorBehavior.cc in Sources */,
+				693D0A060C52643E00A56175 /* WorldStateSerializerBehavior.cc in Sources */,
+				693D0A070C52643E00A56175 /* WalkToTargetNode.cc in Sources */,
+				693D0A080C52643E00A56175 /* StateNode.cc in Sources */,
+				693D0A090C52643E00A56175 /* Transition.cc in Sources */,
+				693D0A0A0C52643E00A56175 /* RandomTrans.cc in Sources */,
+				693D0A0B0C52643E00A56175 /* EventBase.cc in Sources */,
+				693D0A0C0C52643E00A56175 /* EventGeneratorBase.cc in Sources */,
+				693D0A0D0C52643E00A56175 /* EventRouter.cc in Sources */,
+				693D0A0E0C52643E00A56175 /* EventTranslator.cc in Sources */,
+				693D0A0F0C52643E00A56175 /* LocomotionEvent.cc in Sources */,
+				693D0A100C52643E00A56175 /* TextMsgEvent.cc in Sources */,
+				693D0A110C52643E00A56175 /* VisionObjectEvent.cc in Sources */,
+				693D0A120C52643E00A56175 /* EmergencyStopMC.cc in Sources */,
+				693D0A130C52643E00A56175 /* HeadPointerMC.cc in Sources */,
+				693D0A140C52643E00A56175 /* Kinematics.cc in Sources */,
+				693D0A150C52643E00A56175 /* MotionCommand.cc in Sources */,
+				693D0A160C52643E00A56175 /* MotionManager.cc in Sources */,
+				693D0A170C52643E00A56175 /* MotionSequenceEngine.cc in Sources */,
+				693D0A180C52643E00A56175 /* OldKinematics.cc in Sources */,
+				693D0A190C52643E00A56175 /* OutputCmd.cc in Sources */,
+				693D0A1A0C52643E00A56175 /* PostureEngine.cc in Sources */,
+				693D0A1B0C52643E00A56175 /* PostureMC.cc in Sources */,
+				693D0A1C0C52643E00A56175 /* clik.cpp in Sources */,
+				693D0A1D0C52643E00A56175 /* comp_dq.cpp in Sources */,
+				693D0A1E0C52643E00A56175 /* comp_dqp.cpp in Sources */,
+				693D0A1F0C52643E00A56175 /* config.cpp in Sources */,
+				693D0A200C52643E00A56175 /* control_select.cpp in Sources */,
+				693D0A210C52643E00A56175 /* controller.cpp in Sources */,
+				693D0A220C52643E00A56175 /* delta_t.cpp in Sources */,
+				693D0A230C52643E00A56175 /* dynamics.cpp in Sources */,
+				693D0A240C52643E00A56175 /* dynamics_sim.cpp in Sources */,
+				693D0A250C52643E00A56175 /* gnugraph.cpp in Sources */,
+				693D0A260C52643E00A56175 /* homogen.cpp in Sources */,
+				693D0A270C52643E00A56175 /* invkine.cpp in Sources */,
+				693D0A280C52643E00A56175 /* kinemat.cpp in Sources */,
+				693D0A290C52643E00A56175 /* quaternion.cpp in Sources */,
+				693D0A2A0C52643E00A56175 /* sensitiv.cpp in Sources */,
+				693D0A2B0C52643E00A56175 /* trajectory.cpp in Sources */,
+				693D0A2C0C52643E00A56175 /* utils.cpp in Sources */,
+				693D0A2D0C52643E00A56175 /* WalkMC.cc in Sources */,
+				693D0A2E0C52643E00A56175 /* Buffer.cc in Sources */,
+				693D0A2F0C52643E00A56175 /* Config.cc in Sources */,
+				693D0A300C52643E00A56175 /* get_time.cc in Sources */,
+				693D0A310C52643E00A56175 /* jpeg_mem_dest.cc in Sources */,
+				693D0A320C52643E00A56175 /* LoadSave.cc in Sources */,
+				693D0A330C52643E00A56175 /* bandmat.cpp in Sources */,
+				693D0A340C52643E00A56175 /* cholesky.cpp in Sources */,
+				693D0A350C52643E00A56175 /* evalue.cpp in Sources */,
+				693D0A360C52643E00A56175 /* fft.cpp in Sources */,
+				693D0A370C52643E00A56175 /* hholder.cpp in Sources */,
+				693D0A380C52643E00A56175 /* jacobi.cpp in Sources */,
+				693D0A390C52643E00A56175 /* myexcept.cpp in Sources */,
+				693D0A3A0C52643E00A56175 /* newfft.cpp in Sources */,
+				693D0A3B0C52643E00A56175 /* newmat1.cpp in Sources */,
+				693D0A3C0C52643E00A56175 /* newmat2.cpp in Sources */,
+				693D0A3D0C52643E00A56175 /* newmat3.cpp in Sources */,
+				693D0A3E0C52643E00A56175 /* newmat4.cpp in Sources */,
+				693D0A3F0C52643E00A56175 /* newmat5.cpp in Sources */,
+				693D0A400C52643E00A56175 /* newmat6.cpp in Sources */,
+				693D0A410C52643E00A56175 /* newmat7.cpp in Sources */,
+				693D0A420C52643E00A56175 /* newmat8.cpp in Sources */,
+				693D0A430C52643E00A56175 /* newmat9.cpp in Sources */,
+				693D0A440C52643E00A56175 /* newmatex.cpp in Sources */,
+				693D0A450C52643E00A56175 /* newmatnl.cpp in Sources */,
+				693D0A460C52643E00A56175 /* newmatrm.cpp in Sources */,
+				693D0A470C52643E00A56175 /* sort.cpp in Sources */,
+				693D0A480C52643E00A56175 /* submat.cpp in Sources */,
+				693D0A490C52643E00A56175 /* svd.cpp in Sources */,
+				693D0A4A0C52643E00A56175 /* Profiler.cc in Sources */,
+				693D0A4B0C52643E00A56175 /* ProjectInterface.cc in Sources */,
+				693D0A4C0C52643E00A56175 /* string_util.cc in Sources */,
+				693D0A4D0C52643E00A56175 /* TimeET.cc in Sources */,
+				693D0A4E0C52643E00A56175 /* WMclass.cc in Sources */,
+				693D0A4F0C52643E00A56175 /* WorldState.cc in Sources */,
+				693D0A500C52643E00A56175 /* SoundManager.cc in Sources */,
+				693D0A510C52643E00A56175 /* WAV.cc in Sources */,
+				693D0A520C52643E00A56175 /* BallDetectionGenerator.cc in Sources */,
+				693D0A530C52643E00A56175 /* CDTGenerator.cc in Sources */,
+				693D0A540C52643E00A56175 /* FilterBankGenerator.cc in Sources */,
+				693D0A550C52643E00A56175 /* InterleavedYUVGenerator.cc in Sources */,
+				693D0A560C52643E00A56175 /* JPEGGenerator.cc in Sources */,
+				693D0A570C52643E00A56175 /* RawCameraGenerator.cc in Sources */,
+				693D0A580C52643E00A56175 /* RegionGenerator.cc in Sources */,
+				693D0A590C52643E00A56175 /* RLEGenerator.cc in Sources */,
+				693D0A5A0C52643E00A56175 /* SegmentedColorGenerator.cc in Sources */,
+				693D0A5B0C52643E00A56175 /* Socket.cc in Sources */,
+				693D0A5C0C52643E00A56175 /* Wireless.cc in Sources */,
+				693D0A5D0C52643E00A56175 /* SemaphoreManager.cc in Sources */,
+				693D0A5E0C52643E00A56175 /* ProcessID.cc in Sources */,
+				693D0A5F0C52643E00A56175 /* RCRegion.cc in Sources */,
+				693D0A600C52643E00A56175 /* SharedObject.cc in Sources */,
+				693D0A610C52643E00A56175 /* MutexLock.cc in Sources */,
+				693D0A620C52643E00A56175 /* Thread.cc in Sources */,
+				693D0A630C52643E00A56175 /* write_jpeg.cc in Sources */,
+				693D0A640C52643E00A56175 /* plist.cc in Sources */,
+				693D0A650C52643E00A56175 /* XMLLoadSave.cc in Sources */,
+				693D0A660C52643E00A56175 /* BufferedImageGenerator.cc in Sources */,
+				693D0A670C52643E00A56175 /* EchoBehavior.cc in Sources */,
+				693D0A680C52643E00A56175 /* Base64.cc in Sources */,
+				693D0A690C52643E00A56175 /* StewartPlatformBehavior.cc in Sources */,
+				693D0A6A0C52643E00A56175 /* UPennWalkMC.cc in Sources */,
+				693D0A6B0C52643E00A56175 /* Graphics.cc in Sources */,
+				693D0A6C0C52643E00A56175 /* UPennWalkControllerBehavior.cc in Sources */,
+				693D0A6D0C52643E00A56175 /* MessageReceiver.cc in Sources */,
+				693D0A6E0C52643E00A56175 /* robot.cpp in Sources */,
+				693D0A6F0C52643E00A56175 /* RegionCamBehavior.cc in Sources */,
+				693D0A700C52643E00A56175 /* CameraStreamBehavior.cc in Sources */,
+				693D0A710C52643E00A56175 /* MCNode.cc in Sources */,
+				693D0A720C52643E00A56175 /* AgentData.cc in Sources */,
+				693D0A730C52643E00A56175 /* BaseData.cc in Sources */,
+				693D0A740C52643E00A56175 /* BlobData.cc in Sources */,
+				693D0A750C52643E00A56175 /* BrickData.cc in Sources */,
+				693D0A760C52643E00A56175 /* EllipseData.cc in Sources */,
+				693D0A770C52643E00A56175 /* EndPoint.cc in Sources */,
+				693D0A780C52643E00A56175 /* LineData.cc in Sources */,
+				693D0A790C52643E00A56175 /* Lookout.cc in Sources */,
+				693D0A7A0C52643E00A56175 /* MapBuilder.cc in Sources */,
+				693D0A7B0C52643E00A56175 /* ParticleShapes.cc in Sources */,
+				693D0A7C0C52643E00A56175 /* Point.cc in Sources */,
+				693D0A7D0C52643E00A56175 /* PointData.cc in Sources */,
+				693D0A7E0C52643E00A56175 /* PolygonData.cc in Sources */,
+				693D0A7F0C52643E00A56175 /* Region.cc in Sources */,
+				693D0A800C52643E00A56175 /* ShapeAgent.cc in Sources */,
+				693D0A810C52643E00A56175 /* ShapeBlob.cc in Sources */,
+				693D0A820C52643E00A56175 /* ShapeBrick.cc in Sources */,
+				693D0A830C52643E00A56175 /* ShapeEllipse.cc in Sources */,
+				693D0A840C52643E00A56175 /* ShapeFuns.cc in Sources */,
+				693D0A850C52643E00A56175 /* ShapeLine.cc in Sources */,
+				693D0A860C52643E00A56175 /* ShapePoint.cc in Sources */,
+				693D0A870C52643E00A56175 /* ShapePolygon.cc in Sources */,
+				693D0A880C52643E00A56175 /* ShapeRoot.cc in Sources */,
+				693D0A890C52643E00A56175 /* ShapeSpace.cc in Sources */,
+				693D0A8A0C52643E00A56175 /* ShapeSphere.cc in Sources */,
+				693D0A8B0C52643E00A56175 /* Sketch.cc in Sources */,
+				693D0A8C0C52643E00A56175 /* SketchDataRoot.cc in Sources */,
+				693D0A8D0C52643E00A56175 /* SketchIndices.cc in Sources */,
+				693D0A8E0C52643E00A56175 /* SketchRoot.cc in Sources */,
+				693D0A8F0C52643E00A56175 /* SketchSpace.cc in Sources */,
+				693D0A900C52643E00A56175 /* SphereData.cc in Sources */,
+				693D0A910C52643E00A56175 /* susan.cc in Sources */,
+				693D0A920C52643E00A56175 /* ViewerConnection.cc in Sources */,
+				693D0A930C52643E00A56175 /* visops.cc in Sources */,
+				693D0A940C52643E00A56175 /* VisualRoutinesBehavior.cc in Sources */,
+				693D0A950C52643E00A56175 /* VRmixin.cc in Sources */,
+				693D0A960C52643E00A56175 /* VisualRoutinesStateNode.cc in Sources */,
+				693D0A970C52643E00A56175 /* MessageQueue.cc in Sources */,
+				693D0A980C52643E00A56175 /* MessageQueueStatusThread.cc in Sources */,
+				693D0A990C52643E00A56175 /* PollThread.cc in Sources */,
+				693D0A9A0C52643E00A56175 /* plistPrimitives.cc in Sources */,
+				693D0A9B0C52643E00A56175 /* StackTrace.cc in Sources */,
+				693D0A9C0C52643E00A56175 /* SketchPoolRoot.cc in Sources */,
+				693D0A9D0C52643E00A56175 /* jpeg_mem_src.cc in Sources */,
+				693D0A9E0C52643E00A56175 /* Resource.cc in Sources */,
+				693D0A9F0C52643E00A56175 /* PNGGenerator.cc in Sources */,
+				693D0AA00C52643E00A56175 /* WorldStatePool.cc in Sources */,
+				693D0AA10C52643E00A56175 /* PyramidData.cc in Sources */,
+				693D0AA20C52643E00A56175 /* ShapePyramid.cc in Sources */,
+				693D0AA30C52643E00A56175 /* BrickOps.cc in Sources */,
+				693D0AA40C52643E00A56175 /* LookoutEvents.cc in Sources */,
+				693D0AA50C52643E00A56175 /* Aibo3DControllerBehavior.cc in Sources */,
+				693D0AA60C52643E00A56175 /* LookoutRequests.cc in Sources */,
+				693D0AA70C52643E00A56175 /* TestBehaviors.cc in Sources */,
+				693D0AA80C52643E00A56175 /* TimerEvent.cc in Sources */,
+				693D0AA90C52643E00A56175 /* FlashIPAddrBehavior.cc in Sources */,
+				693D0AAA0C52643E00A56175 /* PitchEvent.cc in Sources */,
+				693D0AAB0C52643E00A56175 /* PitchDetector.cc in Sources */,
+				693D0AAC0C52643E00A56175 /* LGmixin.cc in Sources */,
+				693D0AAD0C52643E00A56175 /* colors.cc in Sources */,
+				693D0AAE0C52643E00A56175 /* CameraBehavior.cc in Sources */,
+				693D0AAF0C52643E00A56175 /* FollowHeadBehavior.cc in Sources */,
+				693D0AB00C52643E00A56175 /* WallTestBehavior.cc in Sources */,
+				693D0AB20C52643E00A56175 /* LedEngine.cc in Sources */,
+				693D0AB30C52643E00A56175 /* zignor.cc in Sources */,
+				693D0AB40C52643E00A56175 /* zigrandom.cc in Sources */,
+				693D0AB50C52643E00A56175 /* Measures.cc in Sources */,
+				693D0AB60C52643E00A56175 /* LocalizationParticleData.cc in Sources */,
+				693D0AB70C52643E00A56175 /* PFShapeLocalization.cc in Sources */,
+				693D0AB80C52643E00A56175 /* PFShapeSLAM.cc in Sources */,
+				693D0AB90C52643E00A56175 /* Pilot.cc in Sources */,
+				693D0ABA0C52643E00A56175 /* ShapeLocalizationParticle.cc in Sources */,
+				693D0ABB0C52643E00A56175 /* HolonomicMotionModel.cc in Sources */,
+				693D0ABC0C52643E00A56175 /* ConfigurationEditor.cc in Sources */,
+				693D0ABD0C52643E00A56175 /* PilotRequest.cc in Sources */,
+				693D0ABF0C52643E00A56175 /* TorqueCalibrate.cc in Sources */,
+				693D0AC00C52643E00A56175 /* ImageUtil.cc in Sources */,
+				693D0AC10C52643E00A56175 /* LoadDataThread.cc in Sources */,
+				693D0AC20C52643E00A56175 /* SoundPlayThread.cc in Sources */,
+				693D0AC30C52643E00A56175 /* TargetData.cc in Sources */,
+				693D0AC40C52643E00A56175 /* ShapeTypes.cc in Sources */,
+				693D0AC50C52643E00A56175 /* ShapeTarget.cc in Sources */,
+				693D0AC60C52643E00A56175 /* netstream.cc in Sources */,
+				693D0AC70C52643E00A56175 /* ExecutableCommPort.cc in Sources */,
+				693D0AC80C52643E00A56175 /* FileSystemCommPort.cc in Sources */,
+				693D0AC90C52643E00A56175 /* NetworkCommPort.cc in Sources */,
+				693D0ACA0C52643E00A56175 /* RedirectionCommPort.cc in Sources */,
+				693D0ACB0C52643E00A56175 /* SerialCommPort.cc in Sources */,
+				693D0ACC0C52643E00A56175 /* FileSystemDataSource.cc in Sources */,
+				693D0ACD0C52643E00A56175 /* FileSystemImageSource.cc in Sources */,
+				693D0ACE0C52643E00A56175 /* LoggedDataDriver.cc in Sources */,
+				693D0ACF0C52643E00A56175 /* SSC32Driver.cc in Sources */,
+				693D0AD00C52643E00A56175 /* IPCMotionHook.cc in Sources */,
+				693D0AD20C52643E00A56175 /* ImageCache.cc in Sources */,
+				693D0AD30C52643E00A56175 /* ObjectPingThread.cc in Sources */,
+				693D0AD40C52643E00A56175 /* PropertyManagerI.cc in Sources */,
+				693D0AD50C52643E00A56175 /* QwerkBot.cc in Sources */,
+				693D0AD60C52643E00A56175 /* SerialIO.cc in Sources */,
+				693D0AD70C52643E00A56175 /* TeRKPeerCommon.cc in Sources */,
+				693D0AD80C52643E00A56175 /* TerkUserI.cc in Sources */,
+				693D0AD90C52643E00A56175 /* CameraSourceOSX.cc in Sources */,
+				693D0ADA0C52643E00A56175 /* CameraDriverOSX.cc in Sources */,
+				693D0ADB0C52643E00A56175 /* Main.cc in Sources */,
+				693D0ADC0C52643E00A56175 /* Motion.cc in Sources */,
+				693D0ADD0C52643E00A56175 /* MotionExecThread.cc in Sources */,
+				693D0ADE0C52643E00A56175 /* Process.cc in Sources */,
+				693D0ADF0C52643E00A56175 /* SharedGlobals.cc in Sources */,
+				693D0AE00C52643E00A56175 /* sim.cc in Sources */,
+				693D0AE10C52643E00A56175 /* Simulator.cc in Sources */,
+				693D0AE20C52643E00A56175 /* SoundPlay.cc in Sources */,
+				693D0AE30C52643E00A56175 /* TimerExecThread.cc in Sources */,
+				693D0AE40C52643E00A56175 /* RobotInfo.cc in Sources */,
+				693D0AE50C52643E00A56175 /* jpeg_istream_src.cc in Sources */,
+				693D0C790C53036300A56175 /* RoverControllerBehavior.cc in Sources */,
+				693D0C990C5304CA00A56175 /* ImageStreamDriver.cc in Sources */,
+				693D0E5A0C56632100A56175 /* TeRKDriver.cc in Sources */,
+				693D0E800C572C4C00A56175 /* DataCache.cc in Sources */,
+				6933B7FB0C6527B100A23CE9 /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */,
+				6933B7FC0C6527B100A23CE9 /* StartupBehavior_SetupFileAccess.cc in Sources */,
+				6933B7FD0C6527B100A23CE9 /* StartupBehavior_SetupModeSwitch.cc in Sources */,
+				6933B7FE0C6527B100A23CE9 /* StartupBehavior_SetupStatusReports.cc in Sources */,
+				6933B7FF0C6527B100A23CE9 /* StartupBehavior_SetupTekkotsuMon.cc in Sources */,
+				6933B8010C6527B100A23CE9 /* StartupBehavior_SetupWalkEdit.cc in Sources */,
+				6933BE480C65974300A23CE9 /* StartupBehavior_SetupVision.cc in Sources */,
+				693D23F00C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */,
+				69AA82320CC19CEE00DD162A /* RemoteEvents.cc in Sources */,
+				69AA82330CC19CEE00DD162A /* RemoteRouter.cc in Sources */,
+				69AA82500CC19D3E00DD162A /* EventProxy.cc in Sources */,
+				69AA826A0CC19D8600DD162A /* RemoteState.cc in Sources */,
+				6942521B0CC7E65B00129C8D /* Dynamixel.cc in Sources */,
+				694252630CC7EB2300129C8D /* SerialPort.cc in Sources */,
+				69A6E5E10CDA51BE00039162 /* CreateDriver.cc in Sources */,
+				695FCB360CE8BFBD00069A68 /* PathPlanner.cc in Sources */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
 		69E0AB9B07CBDE11008493CA /* Sources */ = {
 			isa = PBXSourcesBuildPhase;
 			buildActionMask = 2147483647;
@@ -2270,15 +4184,8 @@
 				69E0AB9E07CBDE11008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */,
 				69E0AB9F07CBDE11008493CA /* StartupBehavior_SetupStatusReports.cc in Sources */,
 				69E0ABA007CBDE11008493CA /* StartupBehavior_SetupTekkotsuMon.cc in Sources */,
-				69E0ABA107CBDE11008493CA /* StartupBehavior_SetupVision.cc in Sources */,
 				69E0ABA207CBDE11008493CA /* StartupBehavior_SetupWalkEdit.cc in Sources */,
 				69E0ABA307CBDE11008493CA /* StartupBehavior.cc in Sources */,
-				69E0ABA507CBDE11008493CA /* Main.cc in Sources */,
-				69E0ABA607CBDE11008493CA /* Motion.cc in Sources */,
-				69E0ABA707CBDE11008493CA /* Process.cc in Sources */,
-				69E0ABA807CBDE11008493CA /* SharedGlobals.cc in Sources */,
-				69E0ABA907CBDE11008493CA /* Simulator.cc in Sources */,
-				69E0ABAA07CBDE11008493CA /* SoundPlay.cc in Sources */,
 				69E0ABAB07CBDE11008493CA /* BehaviorBase.cc in Sources */,
 				69E0ABAC07CBDE11008493CA /* Controller.cc in Sources */,
 				69E0ABAD07CBDE11008493CA /* ControlBase.cc in Sources */,
@@ -2308,7 +4215,6 @@
 				69E0ABC607CBDE11008493CA /* RawCamBehavior.cc in Sources */,
 				69E0ABC707CBDE11008493CA /* SegCamBehavior.cc in Sources */,
 				69E0ABC807CBDE11008493CA /* SpeakerServer.cc in Sources */,
-				69E0ABC907CBDE11008493CA /* SpiderMachineBehavior.cc in Sources */,
 				69E0ABCA07CBDE11008493CA /* WalkControllerBehavior.cc in Sources */,
 				69E0ABCB07CBDE11008493CA /* WMMonitorBehavior.cc in Sources */,
 				69E0ABCC07CBDE11008493CA /* WorldStateSerializerBehavior.cc in Sources */,
@@ -2330,7 +4236,6 @@
 				69E0ABDC07CBDE11008493CA /* MotionCommand.cc in Sources */,
 				69E0ABDD07CBDE11008493CA /* MotionManager.cc in Sources */,
 				69E0ABDE07CBDE11008493CA /* MotionSequenceEngine.cc in Sources */,
-				69E0ABDF07CBDE11008493CA /* OldHeadPointerMC.cc in Sources */,
 				69E0ABE007CBDE11008493CA /* OldKinematics.cc in Sources */,
 				69E0ABE107CBDE11008493CA /* OutputCmd.cc in Sources */,
 				69E0ABE207CBDE11008493CA /* PostureEngine.cc in Sources */,
@@ -2410,7 +4315,6 @@
 				69A323C507E35665009D94E1 /* write_jpeg.cc in Sources */,
 				69E666BD07F0CE51005F4FA9 /* plist.cc in Sources */,
 				69E6674907F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */,
-				692CD63507F8C46B00604100 /* sim.cc in Sources */,
 				695F1ACB0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */,
 				69A19960080ED8A200540970 /* EchoBehavior.cc in Sources */,
 				691C805708255F6300E8E256 /* Base64.cc in Sources */,
@@ -2434,9 +4338,6 @@
 				69469FFA09AA1D2100D1EC14 /* LineData.cc in Sources */,
 				69469FFC09AA1D2100D1EC14 /* Lookout.cc in Sources */,
 				69469FFD09AA1D2100D1EC14 /* MapBuilder.cc in Sources */,
-				69469FFE09AA1D2100D1EC14 /* Measures.cc in Sources */,
-				69469FFF09AA1D2100D1EC14 /* Particle.cc in Sources */,
-				6946A00009AA1D2100D1EC14 /* ParticleFilter.cc in Sources */,
 				6946A00109AA1D2100D1EC14 /* ParticleShapes.cc in Sources */,
 				6946A00309AA1D2100D1EC14 /* Point.cc in Sources */,
 				6946A00409AA1D2100D1EC14 /* PointData.cc in Sources */,
@@ -2453,7 +4354,6 @@
 				6946A00F09AA1D2100D1EC14 /* ShapeRoot.cc in Sources */,
 				6946A01009AA1D2100D1EC14 /* ShapeSpace.cc in Sources */,
 				6946A01109AA1D2100D1EC14 /* ShapeSphere.cc in Sources */,
-				6946A01209AA1D2100D1EC14 /* ShapeTypes.cc in Sources */,
 				6946A01309AA1D2100D1EC14 /* Sketch.cc in Sources */,
 				6946A01409AA1D2100D1EC14 /* SketchDataRoot.cc in Sources */,
 				6946A01509AA1D2100D1EC14 /* SketchIndices.cc in Sources */,
@@ -2469,8 +4369,6 @@
 				69D5F7BE09BB4DC9000602D2 /* MessageQueue.cc in Sources */,
 				69D5F82A09BBDF0C000602D2 /* MessageQueueStatusThread.cc in Sources */,
 				69A7EBEB09C7162E003DDD18 /* PollThread.cc in Sources */,
-				69A7EC7C09C79818003DDD18 /* TimerExecThread.cc in Sources */,
-				69A7ED9B09C88623003DDD18 /* MotionExecThread.cc in Sources */,
 				69A7EF2809C9EA77003DDD18 /* plistPrimitives.cc in Sources */,
 				69E78D0409F6C115000385E9 /* StackTrace.cc in Sources */,
 				694B36570A190FE2002ABC4C /* jpeg_mem_src.cc in Sources */,
@@ -2489,8 +4387,62 @@
 				694E67E70AC308290087EC83 /* PitchEvent.cc in Sources */,
 				694E68570AC33A120087EC83 /* PitchDetector.cc in Sources */,
 				69B8DDC30AC44736003EC54A /* LGmixin.cc in Sources */,
-				6976B2150ACC66A000BA657B /* LoadFileThread.cc in Sources */,
-				6976B2160ACC66A000BA657B /* LoadImageThread.cc in Sources */,
+				6959FAC40B08FF4D006F08BB /* colors.cc in Sources */,
+				69EF73290B57E27500FF5476 /* zignor.cc in Sources */,
+				69EF732A0B57E27500FF5476 /* zigrandom.cc in Sources */,
+				69EF74850B59EC7200FF5476 /* Measures.cc in Sources */,
+				69EE785F0B68024A00202E66 /* HolonomicMotionModel.cc in Sources */,
+				6975CDD10B6D67B800B2FAC9 /* ConfigurationEditor.cc in Sources */,
+				695984760B8BF72200AB633A /* LocalizationParticleData.cc in Sources */,
+				6959847B0B8BF76800AB633A /* ShapeLocalizationParticle.cc in Sources */,
+				69D0FBA00B8F82C900CC1DF1 /* Pilot.cc in Sources */,
+				69D0FBAE0B8F9B3500CC1DF1 /* PilotRequest.cc in Sources */,
+				69F74F0C0B98920D00FBA370 /* PFShapeLocalization.cc in Sources */,
+				69F74F0D0B98920D00FBA370 /* PFShapeSLAM.cc in Sources */,
+				69F755C20B9BB9B500FBA370 /* SketchPoolRoot.cc in Sources */,
+				69E62FE70BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */,
+				69A5E23A0BBD6CC8006D6EED /* ImageUtil.cc in Sources */,
+				69A5E3160BBD9C37006D6EED /* LoadDataThread.cc in Sources */,
+				69A5E3190BBD9C37006D6EED /* SoundPlayThread.cc in Sources */,
+				693A55ED0BE1474500509F85 /* TargetData.cc in Sources */,
+				693A55F60BE1478100509F85 /* ShapeTypes.cc in Sources */,
+				693A55FC0BE1479800509F85 /* ShapeTarget.cc in Sources */,
+				69BE649A0BF979A800BC9A15 /* netstream.cc in Sources */,
+				69401CA00C1291F000FE900C /* ExecutableCommPort.cc in Sources */,
+				69401CA10C1291F000FE900C /* FileSystemCommPort.cc in Sources */,
+				69401CA20C1291F000FE900C /* NetworkCommPort.cc in Sources */,
+				69401CA30C1291F000FE900C /* RedirectionCommPort.cc in Sources */,
+				69401CA40C1291F000FE900C /* SerialCommPort.cc in Sources */,
+				69401CC10C12922400FE900C /* FileSystemDataSource.cc in Sources */,
+				69401CC20C12922400FE900C /* FileSystemImageSource.cc in Sources */,
+				69401CC30C12922400FE900C /* LoggedDataDriver.cc in Sources */,
+				69401CC40C12922400FE900C /* SSC32Driver.cc in Sources */,
+				69401CC50C12922400FE900C /* IPCMotionHook.cc in Sources */,
+				6937766F0C17358C001E2C9E /* CameraSourceOSX.cc in Sources */,
+				693776760C17359B001E2C9E /* CameraDriverOSX.cc in Sources */,
+				693AD5AD0C205BE80053F7DE /* Main.cc in Sources */,
+				693AD5AE0C205BE80053F7DE /* Motion.cc in Sources */,
+				693AD5AF0C205BE80053F7DE /* MotionExecThread.cc in Sources */,
+				693AD5B00C205BE80053F7DE /* Process.cc in Sources */,
+				693AD5B10C205BE80053F7DE /* SharedGlobals.cc in Sources */,
+				693AD5B20C205BE80053F7DE /* sim.cc in Sources */,
+				693AD5B30C205BE80053F7DE /* Simulator.cc in Sources */,
+				693AD5B40C205BE80053F7DE /* SoundPlay.cc in Sources */,
+				693AD5B50C205BE80053F7DE /* TimerExecThread.cc in Sources */,
+				69BE87820C30215B0046EEAD /* RobotInfo.cc in Sources */,
+				693D09CB0C525F7E00A56175 /* jpeg_istream_src.cc in Sources */,
+				693D0B1E0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */,
+				693D0C6C0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */,
+				693D0E580C56632100A56175 /* TeRKDriver.cc in Sources */,
+				6933B8830C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */,
+				693D23EE0C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */,
+				69AA822E0CC19CEE00DD162A /* RemoteEvents.cc in Sources */,
+				69AA822F0CC19CEE00DD162A /* RemoteRouter.cc in Sources */,
+				69AA824E0CC19D3E00DD162A /* EventProxy.cc in Sources */,
+				69AA82680CC19D8600DD162A /* RemoteState.cc in Sources */,
+				6942521A0CC7E65B00129C8D /* Dynamixel.cc in Sources */,
+				69A6E5E00CDA51BE00039162 /* CreateDriver.cc in Sources */,
+				695FCB340CE8BFBD00069A68 /* PathPlanner.cc in Sources */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -2504,18 +4456,299 @@
 				69E0AFAD07CBF84D008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */,
 				69E0AFAE07CBF84E008493CA /* StartupBehavior_SetupStatusReports.cc in Sources */,
 				69E0AFAF07CBF84E008493CA /* StartupBehavior_SetupTekkotsuMon.cc in Sources */,
-				69E0AFB007CBF84F008493CA /* StartupBehavior_SetupVision.cc in Sources */,
 				69E0AFB107CBF850008493CA /* StartupBehavior_SetupWalkEdit.cc in Sources */,
-				69E0AFB307CBF85E008493CA /* Main.cc in Sources */,
-				69E0AFB407CBF85F008493CA /* Motion.cc in Sources */,
-				69E0AFB507CBF860008493CA /* Process.cc in Sources */,
-				69E0AFB607CBF862008493CA /* SharedGlobals.cc in Sources */,
-				69E0AFB707CBF862008493CA /* Simulator.cc in Sources */,
-				69E0AFB807CBF863008493CA /* SoundPlay.cc in Sources */,
-				692CD63707F8C46B00604100 /* sim.cc in Sources */,
-				69A7EC7D09C79818003DDD18 /* TimerExecThread.cc in Sources */,
-				69A7ED9D09C88623003DDD18 /* MotionExecThread.cc in Sources */,
 				694E68580AC33A130087EC83 /* PitchDetector.cc in Sources */,
+				6937766D0C17358C001E2C9E /* CameraSourceOSX.cc in Sources */,
+				693776740C17359B001E2C9E /* CameraDriverOSX.cc in Sources */,
+				693AD59B0C205BE80053F7DE /* Main.cc in Sources */,
+				693AD59C0C205BE80053F7DE /* Motion.cc in Sources */,
+				693AD59D0C205BE80053F7DE /* MotionExecThread.cc in Sources */,
+				693AD59E0C205BE80053F7DE /* Process.cc in Sources */,
+				693AD59F0C205BE80053F7DE /* SharedGlobals.cc in Sources */,
+				693AD5A00C205BE80053F7DE /* sim.cc in Sources */,
+				693AD5A10C205BE80053F7DE /* Simulator.cc in Sources */,
+				693AD5A20C205BE80053F7DE /* SoundPlay.cc in Sources */,
+				693AD5A30C205BE80053F7DE /* TimerExecThread.cc in Sources */,
+				6933B8860C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+		69E6653F0B4D822A00575707 /* Sources */ = {
+			isa = PBXSourcesBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				69E665400B4D822A00575707 /* plistBase.cc in Sources */,
+				69E665410B4D822A00575707 /* plistCollections.cc in Sources */,
+				69E665490B4D822A00575707 /* StartupBehavior.cc in Sources */,
+				69E665500B4D822A00575707 /* BehaviorBase.cc in Sources */,
+				69E665510B4D822A00575707 /* Controller.cc in Sources */,
+				69E665520B4D822A00575707 /* ControlBase.cc in Sources */,
+				69E665530B4D822A00575707 /* EventLogger.cc in Sources */,
+				69E665540B4D822A00575707 /* FileBrowserControl.cc in Sources */,
+				69E665550B4D822A00575707 /* FreeMemReportControl.cc in Sources */,
+				69E665560B4D822A00575707 /* HelpControl.cc in Sources */,
+				69E665570B4D822A00575707 /* PostureEditor.cc in Sources */,
+				69E665580B4D822A00575707 /* RebootControl.cc in Sources */,
+				69E665590B4D822A00575707 /* SensorObserverControl.cc in Sources */,
+				69E6655A0B4D822A00575707 /* ShutdownControl.cc in Sources */,
+				69E6655B0B4D822A00575707 /* StringInputControl.cc in Sources */,
+				69E6655C0B4D822A00575707 /* WalkCalibration.cc in Sources */,
+				69E6655D0B4D822A00575707 /* WaypointWalkControl.cc in Sources */,
+				69E6655E0B4D822A00575707 /* ASCIIVisionBehavior.cc in Sources */,
+				69E665600B4D822A00575707 /* ChaseBallBehavior.cc in Sources */,
+				69E665610B4D822A00575707 /* DriveMeBehavior.cc in Sources */,
+				69E665620B4D822A00575707 /* ExploreMachine.cc in Sources */,
+				69E665640B4D822A00575707 /* PaceTargetsMachine.cc in Sources */,
+				69E665650B4D822A00575707 /* StareAtBallBehavior.cc in Sources */,
+				69E665670B4D822A00575707 /* EStopControllerBehavior.cc in Sources */,
+				69E665680B4D822A00575707 /* HeadPointControllerBehavior.cc in Sources */,
+				69E665690B4D822A00575707 /* MicrophoneServer.cc in Sources */,
+				69E6656A0B4D822A00575707 /* RawCamBehavior.cc in Sources */,
+				69E6656B0B4D822A00575707 /* SegCamBehavior.cc in Sources */,
+				69E6656C0B4D822A00575707 /* SpeakerServer.cc in Sources */,
+				69E6656E0B4D822A00575707 /* WalkControllerBehavior.cc in Sources */,
+				69E6656F0B4D822A00575707 /* WMMonitorBehavior.cc in Sources */,
+				69E665700B4D822A00575707 /* WorldStateSerializerBehavior.cc in Sources */,
+				69E665710B4D822A00575707 /* WalkToTargetNode.cc in Sources */,
+				69E665720B4D822A00575707 /* StateNode.cc in Sources */,
+				69E665730B4D822A00575707 /* Transition.cc in Sources */,
+				69E665740B4D822A00575707 /* RandomTrans.cc in Sources */,
+				69E665750B4D822A00575707 /* EventBase.cc in Sources */,
+				69E665760B4D822A00575707 /* EventGeneratorBase.cc in Sources */,
+				69E665770B4D822A00575707 /* EventRouter.cc in Sources */,
+				69E665780B4D822A00575707 /* EventTranslator.cc in Sources */,
+				69E665790B4D822A00575707 /* LocomotionEvent.cc in Sources */,
+				69E6657A0B4D822A00575707 /* TextMsgEvent.cc in Sources */,
+				69E6657B0B4D822A00575707 /* VisionObjectEvent.cc in Sources */,
+				69E6657C0B4D822A00575707 /* EmergencyStopMC.cc in Sources */,
+				69E6657D0B4D822A00575707 /* HeadPointerMC.cc in Sources */,
+				69E6657E0B4D822A00575707 /* Kinematics.cc in Sources */,
+				69E665800B4D822A00575707 /* MotionCommand.cc in Sources */,
+				69E665810B4D822A00575707 /* MotionManager.cc in Sources */,
+				69E665820B4D822A00575707 /* MotionSequenceEngine.cc in Sources */,
+				69E665840B4D822A00575707 /* OldKinematics.cc in Sources */,
+				69E665850B4D822A00575707 /* OutputCmd.cc in Sources */,
+				69E665860B4D822A00575707 /* PostureEngine.cc in Sources */,
+				69E665870B4D822A00575707 /* PostureMC.cc in Sources */,
+				69E665880B4D822A00575707 /* clik.cpp in Sources */,
+				69E665890B4D822A00575707 /* comp_dq.cpp in Sources */,
+				69E6658A0B4D822A00575707 /* comp_dqp.cpp in Sources */,
+				69E6658B0B4D822A00575707 /* config.cpp in Sources */,
+				69E6658C0B4D822A00575707 /* control_select.cpp in Sources */,
+				69E6658D0B4D822A00575707 /* controller.cpp in Sources */,
+				69E6658E0B4D822A00575707 /* delta_t.cpp in Sources */,
+				69E6658F0B4D822A00575707 /* dynamics.cpp in Sources */,
+				69E665900B4D822A00575707 /* dynamics_sim.cpp in Sources */,
+				69E665910B4D822A00575707 /* gnugraph.cpp in Sources */,
+				69E665920B4D822A00575707 /* homogen.cpp in Sources */,
+				69E665930B4D822A00575707 /* invkine.cpp in Sources */,
+				69E665940B4D822A00575707 /* kinemat.cpp in Sources */,
+				69E665950B4D822A00575707 /* quaternion.cpp in Sources */,
+				69E665960B4D822A00575707 /* sensitiv.cpp in Sources */,
+				69E665970B4D822A00575707 /* trajectory.cpp in Sources */,
+				69E665980B4D822A00575707 /* utils.cpp in Sources */,
+				69E665990B4D822A00575707 /* WalkMC.cc in Sources */,
+				69E6659A0B4D822A00575707 /* Buffer.cc in Sources */,
+				69E6659B0B4D822A00575707 /* Config.cc in Sources */,
+				69E6659C0B4D822A00575707 /* get_time.cc in Sources */,
+				69E6659D0B4D822A00575707 /* jpeg_mem_dest.cc in Sources */,
+				69E6659E0B4D822A00575707 /* LoadSave.cc in Sources */,
+				69E6659F0B4D822A00575707 /* bandmat.cpp in Sources */,
+				69E665A00B4D822A00575707 /* cholesky.cpp in Sources */,
+				69E665A10B4D822A00575707 /* evalue.cpp in Sources */,
+				69E665A20B4D822A00575707 /* fft.cpp in Sources */,
+				69E665A30B4D822A00575707 /* hholder.cpp in Sources */,
+				69E665A40B4D822A00575707 /* jacobi.cpp in Sources */,
+				69E665A50B4D822A00575707 /* myexcept.cpp in Sources */,
+				69E665A60B4D822A00575707 /* newfft.cpp in Sources */,
+				69E665A70B4D822A00575707 /* newmat1.cpp in Sources */,
+				69E665A80B4D822A00575707 /* newmat2.cpp in Sources */,
+				69E665A90B4D822A00575707 /* newmat3.cpp in Sources */,
+				69E665AA0B4D822A00575707 /* newmat4.cpp in Sources */,
+				69E665AB0B4D822A00575707 /* newmat5.cpp in Sources */,
+				69E665AC0B4D822A00575707 /* newmat6.cpp in Sources */,
+				69E665AD0B4D822A00575707 /* newmat7.cpp in Sources */,
+				69E665AE0B4D822A00575707 /* newmat8.cpp in Sources */,
+				69E665AF0B4D822A00575707 /* newmat9.cpp in Sources */,
+				69E665B00B4D822A00575707 /* newmatex.cpp in Sources */,
+				69E665B10B4D822A00575707 /* newmatnl.cpp in Sources */,
+				69E665B20B4D822A00575707 /* newmatrm.cpp in Sources */,
+				69E665B30B4D822A00575707 /* sort.cpp in Sources */,
+				69E665B40B4D822A00575707 /* submat.cpp in Sources */,
+				69E665B50B4D822A00575707 /* svd.cpp in Sources */,
+				69E665B60B4D822A00575707 /* Profiler.cc in Sources */,
+				69E665B70B4D822A00575707 /* ProjectInterface.cc in Sources */,
+				69E665B80B4D822A00575707 /* string_util.cc in Sources */,
+				69E665B90B4D822A00575707 /* TimeET.cc in Sources */,
+				69E665BA0B4D822A00575707 /* WMclass.cc in Sources */,
+				69E665BB0B4D822A00575707 /* WorldState.cc in Sources */,
+				69E665BC0B4D822A00575707 /* SoundManager.cc in Sources */,
+				69E665BD0B4D822A00575707 /* WAV.cc in Sources */,
+				69E665BE0B4D822A00575707 /* BallDetectionGenerator.cc in Sources */,
+				69E665BF0B4D822A00575707 /* CDTGenerator.cc in Sources */,
+				69E665C00B4D822A00575707 /* FilterBankGenerator.cc in Sources */,
+				69E665C10B4D822A00575707 /* InterleavedYUVGenerator.cc in Sources */,
+				69E665C20B4D822A00575707 /* JPEGGenerator.cc in Sources */,
+				69E665C30B4D822A00575707 /* RawCameraGenerator.cc in Sources */,
+				69E665C40B4D822A00575707 /* RegionGenerator.cc in Sources */,
+				69E665C50B4D822A00575707 /* RLEGenerator.cc in Sources */,
+				69E665C60B4D822A00575707 /* SegmentedColorGenerator.cc in Sources */,
+				69E665C70B4D822A00575707 /* Socket.cc in Sources */,
+				69E665C80B4D822A00575707 /* Wireless.cc in Sources */,
+				69E665C90B4D822A00575707 /* SemaphoreManager.cc in Sources */,
+				69E665CA0B4D822A00575707 /* ProcessID.cc in Sources */,
+				69E665CB0B4D822A00575707 /* RCRegion.cc in Sources */,
+				69E665CC0B4D822A00575707 /* SharedObject.cc in Sources */,
+				69E665CD0B4D822A00575707 /* MutexLock.cc in Sources */,
+				69E665CE0B4D822A00575707 /* Thread.cc in Sources */,
+				69E665CF0B4D822A00575707 /* write_jpeg.cc in Sources */,
+				69E665D00B4D822A00575707 /* plist.cc in Sources */,
+				69E665D10B4D822A00575707 /* XMLLoadSave.cc in Sources */,
+				69E665D30B4D822A00575707 /* BufferedImageGenerator.cc in Sources */,
+				69E665D40B4D822A00575707 /* EchoBehavior.cc in Sources */,
+				69E665D50B4D822A00575707 /* Base64.cc in Sources */,
+				69E665D60B4D822A00575707 /* StewartPlatformBehavior.cc in Sources */,
+				69E665D70B4D822A00575707 /* UPennWalkMC.cc in Sources */,
+				69E665D80B4D822A00575707 /* Graphics.cc in Sources */,
+				69E665D90B4D822A00575707 /* UPennWalkControllerBehavior.cc in Sources */,
+				69E665DA0B4D822A00575707 /* MessageReceiver.cc in Sources */,
+				69E665DC0B4D822A00575707 /* robot.cpp in Sources */,
+				69E665DD0B4D822A00575707 /* RegionCamBehavior.cc in Sources */,
+				69E665DE0B4D822A00575707 /* CameraStreamBehavior.cc in Sources */,
+				69E665DF0B4D822A00575707 /* MCNode.cc in Sources */,
+				69E665E00B4D822A00575707 /* AgentData.cc in Sources */,
+				69E665E10B4D822A00575707 /* BaseData.cc in Sources */,
+				69E665E20B4D822A00575707 /* BlobData.cc in Sources */,
+				69E665E30B4D822A00575707 /* BrickData.cc in Sources */,
+				69E665E40B4D822A00575707 /* EllipseData.cc in Sources */,
+				69E665E50B4D822A00575707 /* EndPoint.cc in Sources */,
+				69E665E60B4D822A00575707 /* LineData.cc in Sources */,
+				69E665E70B4D822A00575707 /* Lookout.cc in Sources */,
+				69E665E80B4D822A00575707 /* MapBuilder.cc in Sources */,
+				69E665EC0B4D822A00575707 /* ParticleShapes.cc in Sources */,
+				69E665ED0B4D822A00575707 /* Point.cc in Sources */,
+				69E665EE0B4D822A00575707 /* PointData.cc in Sources */,
+				69E665EF0B4D822A00575707 /* PolygonData.cc in Sources */,
+				69E665F00B4D822A00575707 /* Region.cc in Sources */,
+				69E665F10B4D822A00575707 /* ShapeAgent.cc in Sources */,
+				69E665F20B4D822A00575707 /* ShapeBlob.cc in Sources */,
+				69E665F30B4D822A00575707 /* ShapeBrick.cc in Sources */,
+				69E665F40B4D822A00575707 /* ShapeEllipse.cc in Sources */,
+				69E665F50B4D822A00575707 /* ShapeFuns.cc in Sources */,
+				69E665F60B4D822A00575707 /* ShapeLine.cc in Sources */,
+				69E665F70B4D822A00575707 /* ShapePoint.cc in Sources */,
+				69E665F80B4D822A00575707 /* ShapePolygon.cc in Sources */,
+				69E665F90B4D822A00575707 /* ShapeRoot.cc in Sources */,
+				69E665FA0B4D822A00575707 /* ShapeSpace.cc in Sources */,
+				69E665FB0B4D822A00575707 /* ShapeSphere.cc in Sources */,
+				69E665FD0B4D822A00575707 /* Sketch.cc in Sources */,
+				69E665FE0B4D822A00575707 /* SketchDataRoot.cc in Sources */,
+				69E665FF0B4D822A00575707 /* SketchIndices.cc in Sources */,
+				69E666000B4D822A00575707 /* SketchRoot.cc in Sources */,
+				69E666010B4D822A00575707 /* SketchSpace.cc in Sources */,
+				69E666020B4D822A00575707 /* SphereData.cc in Sources */,
+				69E666030B4D822A00575707 /* susan.cc in Sources */,
+				69E666040B4D822A00575707 /* ViewerConnection.cc in Sources */,
+				69E666050B4D822A00575707 /* visops.cc in Sources */,
+				69E666060B4D822A00575707 /* VisualRoutinesBehavior.cc in Sources */,
+				69E666070B4D822A00575707 /* VRmixin.cc in Sources */,
+				69E666080B4D822A00575707 /* VisualRoutinesStateNode.cc in Sources */,
+				69E666090B4D822A00575707 /* MessageQueue.cc in Sources */,
+				69E6660A0B4D822A00575707 /* MessageQueueStatusThread.cc in Sources */,
+				69E6660B0B4D822A00575707 /* PollThread.cc in Sources */,
+				69E6660E0B4D822A00575707 /* plistPrimitives.cc in Sources */,
+				69E6660F0B4D822A00575707 /* StackTrace.cc in Sources */,
+				69E666100B4D822A00575707 /* SketchPoolRoot.cc in Sources */,
+				69E666110B4D822A00575707 /* jpeg_mem_src.cc in Sources */,
+				69E666120B4D822A00575707 /* Resource.cc in Sources */,
+				69E666130B4D822A00575707 /* PNGGenerator.cc in Sources */,
+				69E666140B4D822A00575707 /* WorldStatePool.cc in Sources */,
+				69E666150B4D822A00575707 /* PyramidData.cc in Sources */,
+				69E666160B4D822A00575707 /* ShapePyramid.cc in Sources */,
+				69E666170B4D822A00575707 /* BrickOps.cc in Sources */,
+				69E666180B4D822A00575707 /* LookoutEvents.cc in Sources */,
+				69E666190B4D822A00575707 /* Aibo3DControllerBehavior.cc in Sources */,
+				69E6661A0B4D822A00575707 /* LookoutRequests.cc in Sources */,
+				69E6661B0B4D822A00575707 /* TestBehaviors.cc in Sources */,
+				69E6661C0B4D822A00575707 /* TimerEvent.cc in Sources */,
+				69E6661D0B4D822A00575707 /* FlashIPAddrBehavior.cc in Sources */,
+				69E6661E0B4D822A00575707 /* PitchEvent.cc in Sources */,
+				69E6661F0B4D822A00575707 /* PitchDetector.cc in Sources */,
+				69E666200B4D822A00575707 /* LGmixin.cc in Sources */,
+				69E666230B4D822A00575707 /* colors.cc in Sources */,
+				691FC36A0B4EE68700246924 /* CameraBehavior.cc in Sources */,
+				691FC36B0B4EE6F400246924 /* FollowHeadBehavior.cc in Sources */,
+				691FC36C0B4EE72100246924 /* WallTestBehavior.cc in Sources */,
+				691FC3790B4EF71900246924 /* LedEngine.cc in Sources */,
+				690B6C5D0B98C9CE005E6FE5 /* zignor.cc in Sources */,
+				690B6C5E0B98C9CE005E6FE5 /* zigrandom.cc in Sources */,
+				690B6C620B98C9E7005E6FE5 /* Measures.cc in Sources */,
+				690B6C650B98C9FB005E6FE5 /* LocalizationParticleData.cc in Sources */,
+				690B6C680B98CA03005E6FE5 /* PFShapeLocalization.cc in Sources */,
+				690B6C690B98CA03005E6FE5 /* PFShapeSLAM.cc in Sources */,
+				690B6C6D0B98CA12005E6FE5 /* Pilot.cc in Sources */,
+				690B6C700B98CA23005E6FE5 /* ShapeLocalizationParticle.cc in Sources */,
+				690B6C7C0B98CB61005E6FE5 /* HolonomicMotionModel.cc in Sources */,
+				690B6C7D0B98CB7E005E6FE5 /* ConfigurationEditor.cc in Sources */,
+				690B6C810B98CBAB005E6FE5 /* PilotRequest.cc in Sources */,
+				69E62FE80BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */,
+				69A5E2370BBD6CC8006D6EED /* ImageUtil.cc in Sources */,
+				69A5E2FE0BBD9C37006D6EED /* LoadDataThread.cc in Sources */,
+				69A5E3010BBD9C37006D6EED /* SoundPlayThread.cc in Sources */,
+				693A55F10BE1474500509F85 /* TargetData.cc in Sources */,
+				693A55F80BE1478100509F85 /* ShapeTypes.cc in Sources */,
+				693A55FE0BE1479800509F85 /* ShapeTarget.cc in Sources */,
+				69BE64980BF979A800BC9A15 /* netstream.cc in Sources */,
+				69401C910C1291F000FE900C /* ExecutableCommPort.cc in Sources */,
+				69401C920C1291F000FE900C /* FileSystemCommPort.cc in Sources */,
+				69401C930C1291F000FE900C /* NetworkCommPort.cc in Sources */,
+				69401C940C1291F000FE900C /* RedirectionCommPort.cc in Sources */,
+				69401C950C1291F000FE900C /* SerialCommPort.cc in Sources */,
+				69401CB20C12922400FE900C /* FileSystemDataSource.cc in Sources */,
+				69401CB30C12922400FE900C /* FileSystemImageSource.cc in Sources */,
+				69401CB40C12922400FE900C /* LoggedDataDriver.cc in Sources */,
+				69401CB50C12922400FE900C /* SSC32Driver.cc in Sources */,
+				69401CB60C12922400FE900C /* IPCMotionHook.cc in Sources */,
+				69401DCD0C131F0400FE900C /* ImageCache.cc in Sources */,
+				69401DCE0C131F0400FE900C /* ObjectPingThread.cc in Sources */,
+				69401DCF0C131F0400FE900C /* PropertyManagerI.cc in Sources */,
+				69401DD00C131F0400FE900C /* QwerkBot.cc in Sources */,
+				69401DD10C131F0400FE900C /* SerialIO.cc in Sources */,
+				69401DD20C131F0400FE900C /* TeRKPeerCommon.cc in Sources */,
+				69401DD30C131F0400FE900C /* TerkUserI.cc in Sources */,
+				693776700C17358C001E2C9E /* CameraSourceOSX.cc in Sources */,
+				693776770C17359B001E2C9E /* CameraDriverOSX.cc in Sources */,
+				693AD5B60C205BE80053F7DE /* Main.cc in Sources */,
+				693AD5B70C205BE80053F7DE /* Motion.cc in Sources */,
+				693AD5B80C205BE80053F7DE /* MotionExecThread.cc in Sources */,
+				693AD5B90C205BE80053F7DE /* Process.cc in Sources */,
+				693AD5BA0C205BE80053F7DE /* SharedGlobals.cc in Sources */,
+				693AD5BB0C205BE80053F7DE /* sim.cc in Sources */,
+				693AD5BC0C205BE80053F7DE /* Simulator.cc in Sources */,
+				693AD5BD0C205BE80053F7DE /* SoundPlay.cc in Sources */,
+				693AD5BE0C205BE80053F7DE /* TimerExecThread.cc in Sources */,
+				69BE86B10C2F72440046EEAD /* RobotInfo.cc in Sources */,
+				693D09C90C525F7E00A56175 /* jpeg_istream_src.cc in Sources */,
+				693D0B1C0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */,
+				693D0C6A0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */,
+				693D0E570C56632100A56175 /* TeRKDriver.cc in Sources */,
+				693D0E7D0C572C4C00A56175 /* DataCache.cc in Sources */,
+				6933B7F40C6527B000A23CE9 /* StartupBehavior_SetupBackgroundBehaviors.cc in Sources */,
+				6933B7F50C6527B000A23CE9 /* StartupBehavior_SetupFileAccess.cc in Sources */,
+				6933B7F60C6527B000A23CE9 /* StartupBehavior_SetupModeSwitch.cc in Sources */,
+				6933B7F70C6527B000A23CE9 /* StartupBehavior_SetupStatusReports.cc in Sources */,
+				6933B7F80C6527B000A23CE9 /* StartupBehavior_SetupTekkotsuMon.cc in Sources */,
+				6933B7FA0C6527B000A23CE9 /* StartupBehavior_SetupWalkEdit.cc in Sources */,
+				6933B8820C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */,
+				693D23EF0C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */,
+				69AA82300CC19CEE00DD162A /* RemoteEvents.cc in Sources */,
+				69AA82310CC19CEE00DD162A /* RemoteRouter.cc in Sources */,
+				69AA824F0CC19D3E00DD162A /* EventProxy.cc in Sources */,
+				69AA82690CC19D8600DD162A /* RemoteState.cc in Sources */,
+				694252170CC7E65B00129C8D /* Dynamixel.cc in Sources */,
+				6942525F0CC7EB2300129C8D /* SerialPort.cc in Sources */,
+				69A6E5DD0CDA51BE00039162 /* CreateDriver.cc in Sources */,
+				695FCB350CE8BFBD00069A68 /* PathPlanner.cc in Sources */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
@@ -2530,15 +4763,8 @@
 				69E0A76607CBD4F9008493CA /* StartupBehavior_SetupModeSwitch.cc in Sources */,
 				69E0A76707CBD4F9008493CA /* StartupBehavior_SetupStatusReports.cc in Sources */,
 				69E0A76807CBD4F9008493CA /* StartupBehavior_SetupTekkotsuMon.cc in Sources */,
-				69E0A76907CBD4F9008493CA /* StartupBehavior_SetupVision.cc in Sources */,
 				69E0A76A07CBD4F9008493CA /* StartupBehavior_SetupWalkEdit.cc in Sources */,
 				69E0A76B07CBD4F9008493CA /* StartupBehavior.cc in Sources */,
-				69E0A77D07CBD52D008493CA /* Main.cc in Sources */,
-				69E0A77F07CBD52D008493CA /* Motion.cc in Sources */,
-				69E0A78107CBD52D008493CA /* Process.cc in Sources */,
-				69E0A78407CBD52D008493CA /* SharedGlobals.cc in Sources */,
-				69E0A78607CBD52D008493CA /* Simulator.cc in Sources */,
-				69E0A78807CBD52D008493CA /* SoundPlay.cc in Sources */,
 				69E0A99507CBD6C1008493CA /* BehaviorBase.cc in Sources */,
 				69E0A99807CBD6C1008493CA /* Controller.cc in Sources */,
 				69E0A99F07CBD6C1008493CA /* ControlBase.cc in Sources */,
@@ -2568,7 +4794,6 @@
 				69E0A9F807CBD6C1008493CA /* RawCamBehavior.cc in Sources */,
 				69E0A9FA07CBD6C1008493CA /* SegCamBehavior.cc in Sources */,
 				69E0A9FC07CBD6C1008493CA /* SpeakerServer.cc in Sources */,
-				69E0A9FE07CBD6C1008493CA /* SpiderMachineBehavior.cc in Sources */,
 				69E0AA0107CBD6C2008493CA /* WalkControllerBehavior.cc in Sources */,
 				69E0AA0307CBD6C2008493CA /* WMMonitorBehavior.cc in Sources */,
 				69E0AA0507CBD6C2008493CA /* WorldStateSerializerBehavior.cc in Sources */,
@@ -2590,7 +4815,6 @@
 				69E0AA4207CBD6C2008493CA /* MotionCommand.cc in Sources */,
 				69E0AA4407CBD6C2008493CA /* MotionManager.cc in Sources */,
 				69E0AA4707CBD6C2008493CA /* MotionSequenceEngine.cc in Sources */,
-				69E0AA4A07CBD6C2008493CA /* OldHeadPointerMC.cc in Sources */,
 				69E0AA4C07CBD6C2008493CA /* OldKinematics.cc in Sources */,
 				69E0AA4E07CBD6C2008493CA /* OutputCmd.cc in Sources */,
 				69E0AA5307CBD6C2008493CA /* PostureEngine.cc in Sources */,
@@ -2669,7 +4893,6 @@
 				69A323C207E3564F009D94E1 /* write_jpeg.cc in Sources */,
 				69E666BC07F0CE51005F4FA9 /* plist.cc in Sources */,
 				69E6674A07F1E23A005F4FA9 /* XMLLoadSave.cc in Sources */,
-				692CD63607F8C46B00604100 /* sim.cc in Sources */,
 				695F1ACA0804A81800ACB3D7 /* BufferedImageGenerator.cc in Sources */,
 				69A1995F080ED8A200540970 /* EchoBehavior.cc in Sources */,
 				691C805608255F6300E8E256 /* Base64.cc in Sources */,
@@ -2692,9 +4915,6 @@
 				69469FCF09AA1D2100D1EC14 /* LineData.cc in Sources */,
 				69469FD109AA1D2100D1EC14 /* Lookout.cc in Sources */,
 				69469FD209AA1D2100D1EC14 /* MapBuilder.cc in Sources */,
-				69469FD309AA1D2100D1EC14 /* Measures.cc in Sources */,
-				69469FD409AA1D2100D1EC14 /* Particle.cc in Sources */,
-				69469FD509AA1D2100D1EC14 /* ParticleFilter.cc in Sources */,
 				69469FD609AA1D2100D1EC14 /* ParticleShapes.cc in Sources */,
 				69469FD809AA1D2100D1EC14 /* Point.cc in Sources */,
 				69469FD909AA1D2100D1EC14 /* PointData.cc in Sources */,
@@ -2711,7 +4931,6 @@
 				69469FE409AA1D2100D1EC14 /* ShapeRoot.cc in Sources */,
 				69469FE509AA1D2100D1EC14 /* ShapeSpace.cc in Sources */,
 				69469FE609AA1D2100D1EC14 /* ShapeSphere.cc in Sources */,
-				69469FE709AA1D2100D1EC14 /* ShapeTypes.cc in Sources */,
 				69469FE809AA1D2100D1EC14 /* Sketch.cc in Sources */,
 				69469FE909AA1D2100D1EC14 /* SketchDataRoot.cc in Sources */,
 				69469FEA09AA1D2100D1EC14 /* SketchIndices.cc in Sources */,
@@ -2727,8 +4946,6 @@
 				69D5F7BD09BB4DC9000602D2 /* MessageQueue.cc in Sources */,
 				69D5F82909BBDF0C000602D2 /* MessageQueueStatusThread.cc in Sources */,
 				69A7EBEC09C7162E003DDD18 /* PollThread.cc in Sources */,
-				69A7EC7B09C79817003DDD18 /* TimerExecThread.cc in Sources */,
-				69A7ED9C09C88623003DDD18 /* MotionExecThread.cc in Sources */,
 				69A7EF2909C9EA77003DDD18 /* plistPrimitives.cc in Sources */,
 				69E78D0309F6C114000385E9 /* StackTrace.cc in Sources */,
 				694B2B200A0FC983002ABC4C /* SketchPoolRoot.cc in Sources */,
@@ -2748,14 +4965,226 @@
 				694E67E60AC308290087EC83 /* PitchEvent.cc in Sources */,
 				694E68560AC33A120087EC83 /* PitchDetector.cc in Sources */,
 				69B8DDC20AC44735003EC54A /* LGmixin.cc in Sources */,
-				6976B2130ACC669F00BA657B /* LoadFileThread.cc in Sources */,
-				6976B2140ACC66A000BA657B /* LoadImageThread.cc in Sources */,
+				6959FAC30B08FF4D006F08BB /* colors.cc in Sources */,
+				69EF73270B57E27500FF5476 /* zignor.cc in Sources */,
+				69EF73280B57E27500FF5476 /* zigrandom.cc in Sources */,
+				69EF74840B59EC7200FF5476 /* Measures.cc in Sources */,
+				69EE78600B68024A00202E66 /* HolonomicMotionModel.cc in Sources */,
+				6975CDD00B6D67B800B2FAC9 /* ConfigurationEditor.cc in Sources */,
+				695984750B8BF72200AB633A /* LocalizationParticleData.cc in Sources */,
+				6959847A0B8BF76800AB633A /* ShapeLocalizationParticle.cc in Sources */,
+				69D0FBA10B8F82C900CC1DF1 /* Pilot.cc in Sources */,
+				69D0FBAF0B8F9B3500CC1DF1 /* PilotRequest.cc in Sources */,
+				69F74F0E0B98920D00FBA370 /* PFShapeLocalization.cc in Sources */,
+				69F74F0F0B98920D00FBA370 /* PFShapeSLAM.cc in Sources */,
+				69E62FE60BAB422A009D8FC0 /* TorqueCalibrate.cc in Sources */,
+				69A5E2390BBD6CC8006D6EED /* ImageUtil.cc in Sources */,
+				69A5E30E0BBD9C37006D6EED /* LoadDataThread.cc in Sources */,
+				69A5E3110BBD9C37006D6EED /* SoundPlayThread.cc in Sources */,
+				693A55EF0BE1474500509F85 /* TargetData.cc in Sources */,
+				693A55F70BE1478100509F85 /* ShapeTypes.cc in Sources */,
+				693A55FD0BE1479800509F85 /* ShapeTarget.cc in Sources */,
+				69BE64990BF979A800BC9A15 /* netstream.cc in Sources */,
+				69401C960C1291F000FE900C /* ExecutableCommPort.cc in Sources */,
+				69401C970C1291F000FE900C /* FileSystemCommPort.cc in Sources */,
+				69401C980C1291F000FE900C /* NetworkCommPort.cc in Sources */,
+				69401C990C1291F000FE900C /* RedirectionCommPort.cc in Sources */,
+				69401C9A0C1291F000FE900C /* SerialCommPort.cc in Sources */,
+				69401CB70C12922400FE900C /* FileSystemDataSource.cc in Sources */,
+				69401CB80C12922400FE900C /* FileSystemImageSource.cc in Sources */,
+				69401CB90C12922400FE900C /* LoggedDataDriver.cc in Sources */,
+				69401CBA0C12922400FE900C /* SSC32Driver.cc in Sources */,
+				69401CBB0C12922400FE900C /* IPCMotionHook.cc in Sources */,
+				6937766E0C17358C001E2C9E /* CameraSourceOSX.cc in Sources */,
+				693776750C17359B001E2C9E /* CameraDriverOSX.cc in Sources */,
+				693AD5A40C205BE80053F7DE /* Main.cc in Sources */,
+				693AD5A50C205BE80053F7DE /* Motion.cc in Sources */,
+				693AD5A60C205BE80053F7DE /* MotionExecThread.cc in Sources */,
+				693AD5A70C205BE80053F7DE /* Process.cc in Sources */,
+				693AD5A80C205BE80053F7DE /* SharedGlobals.cc in Sources */,
+				693AD5A90C205BE80053F7DE /* sim.cc in Sources */,
+				693AD5AA0C205BE80053F7DE /* Simulator.cc in Sources */,
+				693AD5AB0C205BE80053F7DE /* SoundPlay.cc in Sources */,
+				693AD5AC0C205BE80053F7DE /* TimerExecThread.cc in Sources */,
+				69BE87830C30215C0046EEAD /* RobotInfo.cc in Sources */,
+				693D09CC0C525F7E00A56175 /* jpeg_istream_src.cc in Sources */,
+				693D0B1F0C52687D00A56175 /* RoverControllerBehavior.cc in Sources */,
+				693D0C6D0C52FE6D00A56175 /* ImageStreamDriver.cc in Sources */,
+				693D0E590C56632100A56175 /* TeRKDriver.cc in Sources */,
+				6933B8840C6596CE00A23CE9 /* StartupBehavior_SetupVision.cc in Sources */,
+				693D23ED0C91B9C3006D6505 /* CameraDriverV4L.cc in Sources */,
+				69AA822C0CC19CEE00DD162A /* RemoteEvents.cc in Sources */,
+				69AA822D0CC19CEE00DD162A /* RemoteRouter.cc in Sources */,
+				69AA824D0CC19D3E00DD162A /* EventProxy.cc in Sources */,
+				69AA82670CC19D8600DD162A /* RemoteState.cc in Sources */,
+				694252180CC7E65B00129C8D /* Dynamixel.cc in Sources */,
+				69A6E5DE0CDA51BE00039162 /* CreateDriver.cc in Sources */,
+				695FCB330CE8BFBD00069A68 /* PathPlanner.cc in Sources */,
 			);
 			runOnlyForDeploymentPostprocessing = 0;
 		};
 /* End PBXSourcesBuildPhase section */
 
 /* Begin XCBuildConfiguration section */
+		692E74900B9E77C100816584 /* . */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = NO;
+				DEPLOYMENT_LOCATION = NO;
+				GCC_DYNAMIC_NO_PIC = NO;
+				GCC_ENABLE_FIX_AND_CONTINUE = YES;
+				GCC_ENABLE_PASCAL_STRINGS = NO;
+				GCC_GENERATE_DEBUGGING_SYMBOLS = YES;
+				GCC_OPTIMIZATION_LEVEL = 0;
+				GCC_PRECOMPILE_PREFIX_HEADER = YES;
+				GCC_PREFIX_HEADER = "$(TEKKOTSU_ROOT)/common.h";
+				GCC_PREPROCESSOR_DEFINITIONS = (
+					PLATFORM_LOCAL,
+					DEBUG,
+					HAVE_READDIR_R,
+				);
+				GCC_USE_GCC3_PFE_SUPPORT = YES;
+				GCC_WARN_ABOUT_MISSING_PROTOTYPES = YES;
+				GCC_WARN_ABOUT_RETURN_TYPE = NO;
+				GCC_WARN_CHECK_SWITCH_STATEMENTS = YES;
+				GCC_WARN_HIDDEN_VIRTUAL_FUNCTIONS = YES;
+				GCC_WARN_INITIALIZER_NOT_FULLY_BRACKETED = YES;
+				GCC_WARN_MISSING_PARENTHESES = YES;
+				GCC_WARN_NON_VIRTUAL_DESTRUCTOR = YES;
+				GCC_WARN_SIGN_COMPARE = YES;
+				GCC_WARN_TYPECHECK_CALLS_TO_PRINTF = YES;
+				GCC_WARN_UNUSED_FUNCTION = YES;
+				GCC_WARN_UNUSED_LABEL = YES;
+				GCC_WARN_UNUSED_PARAMETER = YES;
+				GCC_WARN_UNUSED_VALUE = YES;
+				GCC_WARN_UNUSED_VARIABLE = YES;
+				HEADER_SEARCH_PATHS = (
+					"$(TEKKOTSU_ROOT)",
+					/usr/include/libxml2,
+					"$(ICE_ROOT)/include",
+				);
+				INSTALL_PATH = "$(HOME)/bin";
+				LIBRARY_SEARCH_PATHS = "$(ICE_ROOT)/lib";
+				OBJROOT = build;
+				OTHER_CPLUSPLUSFLAGS = (
+					"-DTGT_QBOTPLUS",
+					"$(HAVE_ICE)",
+				);
+				PREBINDING = NO;
+				PRECOMPS_INCLUDE_HEADERS_FROM_BUILT_PRODUCTS_DIR = NO;
+				PRODUCT_NAME = "tekkotsu-QBOTPLUS";
+				SYMROOT = .;
+				UNSTRIPPED_PRODUCT = YES;
+				WARNING_CFLAGS = (
+					"-Wall",
+					"-Wpointer-arith",
+					"-Wcast-qual",
+					"-Woverloaded-virtual",
+					"-Wdeprecated",
+				);
+			};
+			name = .;
+		};
+		692E74910B9E77C100816584 /* Deployment */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = YES;
+				GCC_ENABLE_FIX_AND_CONTINUE = NO;
+				GCC_ENABLE_PASCAL_STRINGS = NO;
+				GCC_PRECOMPILE_PREFIX_HEADER = YES;
+				GCC_PREFIX_HEADER = "$(TEKKOTSU_ROOT)/common.h";
+				GCC_PREPROCESSOR_DEFINITIONS = PLATFORM_LOCAL;
+				GCC_WARN_UNINITIALIZED_AUTOS = YES;
+				HEADER_SEARCH_PATHS = (
+					"$(TEKKOTSU_ROOT)",
+					/usr/include/libxml2,
+					/usr/local/Ice/include,
+				);
+				INSTALL_PATH = "$(HOME)/bin";
+				LIBRARY_SEARCH_PATHS = /usr/local/Ice/lib;
+				OTHER_CPLUSPLUSFLAGS = "-DTGT_QWERK";
+				PRODUCT_NAME = "sim-qwerk";
+				ZERO_LINK = NO;
+			};
+			name = Deployment;
+		};
+		693D0AF30C52643E00A56175 /* . */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = NO;
+				DEPLOYMENT_LOCATION = NO;
+				GCC_DYNAMIC_NO_PIC = NO;
+				GCC_ENABLE_FIX_AND_CONTINUE = YES;
+				GCC_ENABLE_PASCAL_STRINGS = NO;
+				GCC_GENERATE_DEBUGGING_SYMBOLS = YES;
+				GCC_OPTIMIZATION_LEVEL = 0;
+				GCC_PRECOMPILE_PREFIX_HEADER = YES;
+				GCC_PREFIX_HEADER = "$(TEKKOTSU_ROOT)/common.h";
+				GCC_PREPROCESSOR_DEFINITIONS = (
+					PLATFORM_LOCAL,
+					DEBUG,
+					HAVE_READDIR_R,
+				);
+				GCC_USE_GCC3_PFE_SUPPORT = YES;
+				GCC_WARN_ABOUT_MISSING_PROTOTYPES = YES;
+				GCC_WARN_ABOUT_RETURN_TYPE = NO;
+				GCC_WARN_CHECK_SWITCH_STATEMENTS = YES;
+				GCC_WARN_HIDDEN_VIRTUAL_FUNCTIONS = YES;
+				GCC_WARN_INITIALIZER_NOT_FULLY_BRACKETED = YES;
+				GCC_WARN_MISSING_PARENTHESES = YES;
+				GCC_WARN_NON_VIRTUAL_DESTRUCTOR = YES;
+				GCC_WARN_TYPECHECK_CALLS_TO_PRINTF = YES;
+				GCC_WARN_UNUSED_FUNCTION = YES;
+				GCC_WARN_UNUSED_LABEL = YES;
+				GCC_WARN_UNUSED_PARAMETER = YES;
+				GCC_WARN_UNUSED_VALUE = YES;
+				GCC_WARN_UNUSED_VARIABLE = YES;
+				HEADER_SEARCH_PATHS = (
+					"$(TEKKOTSU_ROOT)",
+					/usr/include/libxml2,
+					"$(ICE_ROOT)/include",
+				);
+				INSTALL_PATH = "$(HOME)/bin";
+				LIBRARY_SEARCH_PATHS = "$(ICE_ROOT)/lib";
+				OBJROOT = build;
+				OTHER_CPLUSPLUSFLAGS = "-DTGT_REGIS1";
+				PREBINDING = NO;
+				PRECOMPS_INCLUDE_HEADERS_FROM_BUILT_PRODUCTS_DIR = NO;
+				PRODUCT_NAME = "tekkotsu-REGIS1";
+				SYMROOT = .;
+				UNSTRIPPED_PRODUCT = YES;
+				WARNING_CFLAGS = (
+					"-Wall",
+					"-Wpointer-arith",
+					"-Wcast-qual",
+					"-Woverloaded-virtual",
+					"-Wdeprecated",
+				);
+			};
+			name = .;
+		};
+		693D0AF40C52643E00A56175 /* Deployment */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = YES;
+				GCC_ENABLE_FIX_AND_CONTINUE = NO;
+				GCC_ENABLE_PASCAL_STRINGS = NO;
+				GCC_PRECOMPILE_PREFIX_HEADER = YES;
+				GCC_PREFIX_HEADER = "$(TEKKOTSU_ROOT)/common.h";
+				GCC_PREPROCESSOR_DEFINITIONS = PLATFORM_LOCAL;
+				GCC_WARN_UNINITIALIZED_AUTOS = YES;
+				HEADER_SEARCH_PATHS = "$(TEKKOTSU_ROOT)";
+				INSTALL_PATH = "$(HOME)/bin";
+				LIBRARY_SEARCH_PATHS = (
+					"$(inherited)",
+					/usr/local/Ice/lib,
+				);
+				OTHER_CPLUSPLUSFLAGS = "-DTGT_LYNXARM6";
+				PRODUCT_NAME = "sim-lynxarm6";
+				ZERO_LINK = NO;
+			};
+			name = Deployment;
+		};
 		693D801008ABBB6100AC993E /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
@@ -2785,7 +5214,7 @@
 			};
 			name = Deployment;
 		};
-		69FD502B0881E74900E825BA /* . */ = {
+		69E6662D0B4D822A00575707 /* . */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
 				COPY_PHASE_STRIP = NO;
@@ -2817,22 +5246,22 @@
 				GCC_WARN_UNUSED_PARAMETER = YES;
 				GCC_WARN_UNUSED_VALUE = YES;
 				GCC_WARN_UNUSED_VARIABLE = YES;
-				GENERATE_PROFILING_CODE = YES;
 				HEADER_SEARCH_PATHS = (
 					"$(TEKKOTSU_ROOT)",
 					/usr/include/libxml2,
+					"$(ICE_ROOT)/include",
 				);
 				INSTALL_PATH = "$(HOME)/bin";
+				LIBRARY_SEARCH_PATHS = "$(ICE_ROOT)/lib";
 				OBJROOT = build;
-				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
+				OTHER_CPLUSPLUSFLAGS = "-DTGT_LYNXARM6";
 				PREBINDING = NO;
 				PRECOMPS_INCLUDE_HEADERS_FROM_BUILT_PRODUCTS_DIR = NO;
-				PRODUCT_NAME = "sim-ERS7";
+				PRODUCT_NAME = "tekkotsu-LYNXARM6";
 				SYMROOT = .;
 				UNSTRIPPED_PRODUCT = YES;
 				WARNING_CFLAGS = (
 					"-Wall",
-					"-W",
 					"-Wpointer-arith",
 					"-Wcast-qual",
 					"-Woverloaded-virtual",
@@ -2841,7 +5270,7 @@
 			};
 			name = .;
 		};
-		69FD502C0881E74900E825BA /* Deployment */ = {
+		69E6662E0B4D822A00575707 /* Deployment */ = {
 			isa = XCBuildConfiguration;
 			buildSettings = {
 				COPY_PHASE_STRIP = YES;
@@ -2853,8 +5282,118 @@
 				GCC_WARN_UNINITIALIZED_AUTOS = YES;
 				HEADER_SEARCH_PATHS = "$(TEKKOTSU_ROOT)";
 				INSTALL_PATH = "$(HOME)/bin";
+				LIBRARY_SEARCH_PATHS = (
+					"$(inherited)",
+					/usr/local/Ice/lib,
+				);
+				OTHER_CPLUSPLUSFLAGS = "-DTGT_LYNXARM6";
+				PRODUCT_NAME = "sim-lynxarm6";
+				ZERO_LINK = NO;
+			};
+			name = Deployment;
+		};
+		69FD502B0881E74900E825BA /* . */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = NO;
+				DEPLOYMENT_LOCATION = NO;
+				GCC_DYNAMIC_NO_PIC = NO;
+				GCC_ENABLE_FIX_AND_CONTINUE = YES;
+				GCC_ENABLE_PASCAL_STRINGS = NO;
+				GCC_GENERATE_DEBUGGING_SYMBOLS = YES;
+				GCC_OPTIMIZATION_LEVEL = 0;
+				GCC_PRECOMPILE_PREFIX_HEADER = YES;
+				GCC_PREFIX_HEADER = "$(TEKKOTSU_ROOT)/common.h";
+				GCC_PREPROCESSOR_DEFINITIONS = (
+					PLATFORM_LOCAL,
+					DEBUG,
+					HAVE_READDIR_R,
+					"TEKKOTSU_SHM_STYLE=NO_SHM",
+				);
+				GCC_WARN_ABOUT_MISSING_PROTOTYPES = YES;
+				GCC_WARN_ABOUT_RETURN_TYPE = YES;
+				GCC_WARN_CHECK_SWITCH_STATEMENTS = YES;
+				GCC_WARN_HIDDEN_VIRTUAL_FUNCTIONS = YES;
+				GCC_WARN_INITIALIZER_NOT_FULLY_BRACKETED = YES;
+				GCC_WARN_MISSING_PARENTHESES = YES;
+				GCC_WARN_NON_VIRTUAL_DESTRUCTOR = YES;
+				GCC_WARN_SIGN_COMPARE = YES;
+				GCC_WARN_TYPECHECK_CALLS_TO_PRINTF = YES;
+				GCC_WARN_UNINITIALIZED_AUTOS = NO;
+				GCC_WARN_UNUSED_FUNCTION = YES;
+				GCC_WARN_UNUSED_LABEL = YES;
+				GCC_WARN_UNUSED_PARAMETER = YES;
+				GCC_WARN_UNUSED_VALUE = YES;
+				GCC_WARN_UNUSED_VARIABLE = YES;
+				HEADER_SEARCH_PATHS = (
+					"$(TEKKOTSU_ROOT)",
+					/usr/include/libxml2,
+				);
+				INSTALL_PATH = "$(HOME)/bin";
+				OBJROOT = build;
+				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
+				PREBINDING = NO;
+				PRECOMPS_INCLUDE_HEADERS_FROM_BUILT_PRODUCTS_DIR = NO;
+				PRODUCT_NAME = "tekkotsu-ERS7";
+				SYMROOT = .;
+				UNSTRIPPED_PRODUCT = YES;
+				WARNING_CFLAGS = (
+					"-Wall",
+					"-Wpointer-arith",
+					"-Wcast-qual",
+					"-Woverloaded-virtual",
+					"-Wdeprecated",
+				);
+			};
+			name = .;
+		};
+		69FD502C0881E74900E825BA /* Deployment */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = YES;
+				GCC_AUTO_VECTORIZATION = YES;
+				GCC_ENABLE_FIX_AND_CONTINUE = NO;
+				GCC_ENABLE_PASCAL_STRINGS = NO;
+				GCC_ENABLE_SSE3_EXTENSIONS = YES;
+				GCC_PRECOMPILE_PREFIX_HEADER = YES;
+				GCC_PREFIX_HEADER = "$(TEKKOTSU_ROOT)/common.h";
+				GCC_PREPROCESSOR_DEFINITIONS = (
+					PLATFORM_LOCAL,
+					HAVE_READDIR_R,
+				);
+				GCC_WARN_ABOUT_MISSING_PROTOTYPES = YES;
+				GCC_WARN_ABOUT_RETURN_TYPE = YES;
+				GCC_WARN_CHECK_SWITCH_STATEMENTS = YES;
+				GCC_WARN_HIDDEN_VIRTUAL_FUNCTIONS = YES;
+				GCC_WARN_INITIALIZER_NOT_FULLY_BRACKETED = YES;
+				GCC_WARN_MISSING_PARENTHESES = YES;
+				GCC_WARN_NON_VIRTUAL_DESTRUCTOR = YES;
+				GCC_WARN_SHADOW = YES;
+				GCC_WARN_SIGN_COMPARE = YES;
+				GCC_WARN_TYPECHECK_CALLS_TO_PRINTF = YES;
+				GCC_WARN_UNINITIALIZED_AUTOS = YES;
+				GCC_WARN_UNUSED_FUNCTION = YES;
+				GCC_WARN_UNUSED_LABEL = YES;
+				GCC_WARN_UNUSED_PARAMETER = YES;
+				GCC_WARN_UNUSED_VALUE = YES;
+				GCC_WARN_UNUSED_VARIABLE = YES;
+				HEADER_SEARCH_PATHS = (
+					"$(TEKKOTSU_ROOT)",
+					/usr/include/libxml2,
+				);
+				INSTALL_PATH = "$(HOME)/bin";
 				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
+				PREBINDING = NO;
+				PRECOMPS_INCLUDE_HEADERS_FROM_BUILT_PRODUCTS_DIR = NO;
 				PRODUCT_NAME = "sim-ERS7";
+				WARNING_CFLAGS = (
+					"-Wall",
+					"-W",
+					"-Wpointer-arith",
+					"-Wcast-qual",
+					"-Woverloaded-virtual",
+					"-Wdeprecated",
+				);
 				ZERO_LINK = NO;
 			};
 			name = Deployment;
@@ -2889,7 +5428,6 @@
 				GCC_WARN_UNUSED_PARAMETER = YES;
 				GCC_WARN_UNUSED_VALUE = YES;
 				GCC_WARN_UNUSED_VARIABLE = YES;
-				GENERATE_PROFILING_CODE = YES;
 				HEADER_SEARCH_PATHS = (
 					"$(TEKKOTSU_ROOT)",
 					/usr/include/libxml2,
@@ -2903,11 +5441,10 @@
 				OBJROOT = build;
 				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS7";
 				PREBINDING = NO;
-				PRODUCT_NAME = "sim-ERS7";
+				PRODUCT_NAME = "tekkotsu-ERS7";
 				SYMROOT = .;
 				WARNING_CFLAGS = (
 					"-Wall",
-					"-W",
 					"-Wpointer-arith",
 					"-Wcast-qual",
 					"-Woverloaded-virtual",
@@ -2969,7 +5506,6 @@
 				GCC_WARN_UNUSED_PARAMETER = YES;
 				GCC_WARN_UNUSED_VALUE = YES;
 				GCC_WARN_UNUSED_VARIABLE = YES;
-				GENERATE_PROFILING_CODE = YES;
 				HEADER_SEARCH_PATHS = (
 					"$(TEKKOTSU_ROOT)",
 					/usr/include/libxml2,
@@ -2978,11 +5514,10 @@
 				OBJROOT = build;
 				OTHER_CPLUSPLUSFLAGS = "-DTGT_ERS210";
 				PREBINDING = NO;
-				PRODUCT_NAME = "sim-ERS210";
+				PRODUCT_NAME = "tekkotsu-ERS210";
 				SYMROOT = "";
 				WARNING_CFLAGS = (
 					"-Wall",
-					"-W",
 					"-Wpointer-arith",
 					"-Wcast-qual",
 					"-Woverloaded-virtual",
@@ -3028,6 +5563,24 @@
 /* End XCBuildConfiguration section */
 
 /* Begin XCConfigurationList section */
+		692E748F0B9E77C100816584 /* Build configuration list for PBXNativeTarget "tekkotsu-QBotPlus" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				692E74900B9E77C100816584 /* . */,
+				692E74910B9E77C100816584 /* Deployment */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = .;
+		};
+		693D0AF20C52643E00A56175 /* Build configuration list for PBXNativeTarget "tekkotsu-Regis1" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				693D0AF30C52643E00A56175 /* . */,
+				693D0AF40C52643E00A56175 /* Deployment */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = .;
+		};
 		693D800F08ABBB6100AC993E /* Build configuration list for PBXLegacyTarget "Aperios Build" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
@@ -3037,7 +5590,16 @@
 			defaultConfigurationIsVisible = 0;
 			defaultConfigurationName = .;
 		};
-		69FD502A0881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-7)" */ = {
+		69E6662C0B4D822A00575707 /* Build configuration list for PBXNativeTarget "tekkotsu-LynxArm6" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				69E6662D0B4D822A00575707 /* . */,
+				69E6662E0B4D822A00575707 /* Deployment */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = .;
+		};
+		69FD502A0881E74900E825BA /* Build configuration list for PBXNativeTarget "tekkotsu-ERS7" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
 				69FD502B0881E74900E825BA /* . */,
@@ -3046,7 +5608,7 @@
 			defaultConfigurationIsVisible = 0;
 			defaultConfigurationName = .;
 		};
-		69FD502E0881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-7) Light" */ = {
+		69FD502E0881E74900E825BA /* Build configuration list for PBXNativeTarget "tekkotsu-ERS7 Light" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
 				69FD502F0881E74900E825BA /* . */,
@@ -3055,7 +5617,7 @@
 			defaultConfigurationIsVisible = 0;
 			defaultConfigurationName = .;
 		};
-		69FD50320881E74900E825BA /* Build configuration list for PBXNativeTarget "sim (ERS-210)" */ = {
+		69FD50320881E74900E825BA /* Build configuration list for PBXNativeTarget "tekkotsu-ERS210" */ = {
 			isa = XCConfigurationList;
 			buildConfigurations = (
 				69FD50330881E74900E825BA /* . */,
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/Makefile ./project/Makefile
--- ../Tekkotsu_3.0/project/Makefile	2006-09-26 17:53:55.000000000 -0400
+++ ./project/Makefile	2007-11-18 01:44:57.000000000 -0500
@@ -12,13 +10,33 @@
 ##             ENVIRONMENT SETUP                 ##
 ###################################################
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(shell pwd | sed 's/ /\\ /g')/Environment.conf
-ifneq ($(filter sim%,$(MAKECMDGOALS)),)
+ifneq ($(filter sim% tekkotsu%,$(MAKECMDGOALS)),)
 	TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 	ifneq ($(filter sim-%,$(MAKECMDGOALS)),)
 		TEKKOTSU_TARGET_MODEL:=$(patsubst sim-%,TGT_%,$(filter sim-%,$(MAKECMDGOALS)))
 	endif
+	ifneq ($(filter tekkotsu-%,$(MAKECMDGOALS)),)
+		TEKKOTSU_TARGET_MODEL:=$(patsubst tekkotsu-%,TGT_%,$(filter tekkotsu-%,$(MAKECMDGOALS)))
+	endif
 endif
 include $(TEKKOTSU_ENVIRONMENT_CONFIGURATION)
+
+ifeq ($(MAKELEVEL),0)
+  $(shell echo "  ** Project 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
+$(if $(shell [ -d "$(TEKKOTSU_ROOT)" ] || echo "not found"),$(error Could not access TEKKOTSU_ROOT: $(TEKKOTSU_ROOT)))
+ifeq ($(filter clean%,$(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 $(PROJ_BD))
 
 
@@ -32,34 +50,44 @@
 # 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 $(TEKKOTSU_ROOT)/aperios/include \
-	  $(if $(TEKKOTSU_DEBUG),-DOPENR_DEBUG,) \
-	  `$(TEKKOTSU_ROOT)/aperios/bin/xml2-config --cflags`
-  LDFLAGS=-lObjectComm -lOPENR  -lInternet -lantMCOOP -lERA201D1 \
-	  `$(TEKKOTSU_ROOT)/aperios/bin/xml2-config --libs` -ljpeg -lpng
+	  $(if $(TEKKOTSU_DEBUG),-DOPENR_DEBUG,) -DLOADFILE_NO_MMAP \
+	  $(shell $(TEKKOTSU_ROOT)/aperios/bin/xml2-config --cflags)
+  LDFLAGS:=$(LDFLAGS) -lObjectComm -lOPENR  -lInternet -lantMCOOP -lERA201D1 \
+	  $(shell $(TEKKOTSU_ROOT)/aperios/bin/xml2-config --libs) -ljpeg -lpng -lregex
 else
-  PLATFORM_FLAGS=`xml2-config --cflags` -isystem /usr/include/libpng12
-  LDFLAGS=`xml2-config --libs` $(if $(shell locate librt.a),-lrt) -lreadline -lncurses -ljpeg -lpng12
+  PLATFORM_FLAGS:=$(shell xml2-config --cflags) -isystem /usr/include/libpng12 \
+	 $(shell if [ -d "$(ICE_ROOT)" ] ; then echo "-DHAVE_ICE -I$(ICE_ROOT)/include"; fi)
+  LDFLAGS:=$(LDFLAGS) $(shell xml2-config --libs) $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+          -lreadline -lncurses -ljpeg -lpng12 -lpthread \
+          $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+          $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 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. -I$(TEKKOTSU_ROOT) -I$(TEKKOTSU_ROOT)/Motion/roboop \
 	-I$(TEKKOTSU_ROOT)/Shared/newmat \
 	-isystem $(TEKKOTSU_ROOT)/Shared/jpeg-6b \
 	-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))
 
-TEKKOTSU_VERSION=Tekkotsu pre-3.0 CVS
+TEKKOTSU_VERSION=Tekkotsu 4.0 CVS
 
 ###################################################
 ##              SOURCE CODE LIST                 ##
@@ -70,12 +98,12 @@
 # You shouldn't need to change anything here unless you want to add
 # external libraries
 SRCSUFFIX=.cc
-SRCS:=$(patsubst ./%,%,$(shell find . -name "*$(SRCSUFFIX)" -or -name "$(PROJECT_BUILDDIR)" \! -prune -or -name "templates" \! -prune -or -name "aperios" \! -prune -or -name "local" \! -prune | xargs ls -t))
+SRCS:=$(patsubst ./%,%,$(shell find . -name "*$(SRCSUFFIX)" -or -name "$(PROJECT_BUILDDIR)" \! -prune -or -name "templates" \! -prune -or -name "aperios" \! -prune -or -name "local" \! -prune))
 
 # We can also link in third-party libraries
-USERLIBS:= $(TK_BD)/libtekkotsu.a \
-           $(TK_LIB_BD)/Motion/roboop/libroboop.a \
-           $(TK_LIB_BD)/Shared/newmat/libnewmat.a \
+USERLIBS:= $(TK_BD)/$(LIBTEKKOTSU) \
+           $(TK_LIB_BD)/Motion/roboop/libroboop$(suffix $(LIBTEKKOTSU)) \
+           $(TK_LIB_BD)/Shared/newmat/libnewmat$(suffix $(LIBTEKKOTSU)) \
 
 
 ###################################################
@@ -84,25 +112,17 @@
 # Hopefully, you shouldn't have to change anything down here,
 # except one or two little things ;)
 
-.PHONY: all compile clean cleanDeps cleanProj reportTarget checkLibs testEnv testLibs buildLibs sim
+.PHONY: all compile clean cleanDeps cleanProj checkLibs testLibs buildLibs sim tekkotsu
 
-sim all update install ftpupdate: reportTarget testEnv checkLibs
-	@$(MAKE) TEKKOTSU_TARGET_PLATFORM=$(TEKKOTSU_TARGET_PLATFORM) compile-$@
+sim all update install ftpupdate: %: checkLibs compile-%
 
+#DEFTARGET is set when using XCode to trigger 'update' instead of 'all'
 ifeq ($(TEKKOTSU_DEFTARGET),)
 compile-all: compile
-	@echo "Type: '$(MAKE) install' to compile and copy all files to the memory stick";
-	@echo "  or: '$(MAKE) update' to compile and copy only changed files";
-	@echo "  or: '$(MAKE) ftpupdate IPADDRESS=<ipaddr>' to compile and copy changed files over FTP";
-	@echo "     ('$(TEKKOTSU_ROOT)/tools/{ftpinstall,ftpupdate} <ipaddr> ms' might also be useful)";
-	@echo "Build successful."
 else
 compile-all: compile-$(TEKKOTSU_DEFTARGET) ;
 endif
 
-compile-sim: compile
-	@echo "Build successful."
-
 # Don't want to try to remake this - give an error if not found
 $(TEKKOTSU_ROOT)/project/Environment.conf:
 	@echo "Could not find Environment file - check the default project directory still exists"
@@ -110,21 +130,13 @@
 
 checkLibs: $(if $(TEKKOTSU_ALWAYS_BUILD),buildLibs,testLibs)
 
+$(TK_BD)/$(TEKKOTSU_PCH).gch $(TK_BD)/%.o: checkLibs
+
 ifeq ($(TEKKOTSU_ALWAYS_BUILD),)
-%/libtekkotsu.a:
-	echo "It appears that the framework itself has not been compiled."; \
-	echo "TEKKOTSU_ROOT = $(TEKKOTSU_ROOT)"; \
-	echo "TK_BD = $(TK_BD)"; \
-	echo "Press enter to compile it now, ctl-C to cancel."; \
-	read; \
-	export TEKKOTSU_ENVIRONMENT_CONFIGURATION=$(TEKKOTSU_ENVIRONMENT_CONFIGURATION); \
-	$(MAKE) TEKKOTSU_TARGET_MODEL=$(TEKKOTSU_TARGET_MODEL) TEKKOTSU_TARGET_PLATFORM=$(TEKKOTSU_TARGET_PLATFORM) -C "$(TEKKOTSU_ROOT)" compile ;
+$(TK_BD)/$(LIBTEKKOTSU): testLibs
 
 else
-%/libtekkotsu.a:
-	@echo "Updating framework build...";
-	@export TEKKOTSU_ENVIRONMENT_CONFIGURATION=$(TEKKOTSU_ENVIRONMENT_CONFIGURATION); \
-	$(MAKE) TEKKOTSU_TARGET_MODEL=$(TEKKOTSU_TARGET_MODEL) TEKKOTSU_TARGET_PLATFORM=$(TEKKOTSU_TARGET_PLATFORM) -C "$(TEKKOTSU_ROOT)" compile ; 
+$(TK_BD)/$(LIBTEKKOTSU): buildLibs
 
 endif
 
@@ -151,6 +163,15 @@
 	@export TEKKOTSU_ENVIRONMENT_CONFIGURATION=$(TEKKOTSU_ENVIRONMENT_CONFIGURATION); \
 	$(MAKE) TEKKOTSU_TARGET_MODEL=$(TEKKOTSU_TARGET_MODEL) TEKKOTSU_TARGET_PLATFORM=$(TEKKOTSU_TARGET_PLATFORM) -C "$(TEKKOTSU_ROOT)" compile ; 
 
+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 $(PROJ_BD)/,$(SRCS:$(SRCSUFFIX)=.o))
 
@@ -159,16 +180,6 @@
 # all in one place.
 DEPENDS:=$(addprefix $(PROJ_BD)/,$(SRCS:$(SRCSUFFIX)=.d))
 
-ifeq ($(TEKKOTSU_TARGET_PLATFORM),PLATFORM_APERIOS)
-
-include aperios/Makefile.aperios
-
-else
-
-include local/Makefile.local
-
-endif
-
 EMPTYDEPS:=$(shell find $(PROJ_BD) -type f -name "*\.d" -size 0 -print -exec rm \{\} \;)
 ifneq ($(EMPTYDEPS),)
 EMPTYDEPS:=$(shell echo "Empty dependency files detected: $(EMPTYDEPS)" > /dev/tty)
@@ -193,29 +204,6 @@
 	echo "$@..." | sed 's@$(PROJ_BD)/@Generating @'; \
 	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
 
-reportTarget:
-	@echo " ** Project 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)) ** ";
-
-testEnv:
-	$(testEnvScr)
-
-define testEnvScr
-@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;
-endef
-
 %.h :
 	@if [ "$(notdir $@)" = "def.h" -o "$(notdir $@)" = "entry.h" ] ; then \
 		echo "WARNING: You shouldn't be seeing this message.  Report that you did." ; \
@@ -238,6 +226,10 @@
 	echo "I don't know anything about `$*'";
 	exit 1;
 
+# Don't locally rebuild framework files
+# (sometimes platform_local targets want to doubly-compile the target specific object files... might be a make bug)
+$(TK_BD)/%.o: checkLibs
+	
 %.o: $(if $(TEKKOTSU_PCH),$(TK_BD)/$(TEKKOTSU_PCH).gch)
 	@mkdir -p $(dir $@)
 	@src=$(patsubst %.o,%$(SRCSUFFIX),$(if $(findstring $(TK_BD),$@),$(patsubst $(TK_BD)%,$(TEKKOTSU_ROOT)%,$@),$(patsubst $(PROJ_BD)/%,%,$@))); \
@@ -272,6 +264,7 @@
 	rm -f $(INSTALL_BINS)
 	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/project/StartupBehavior.cc ./project/StartupBehavior.cc
--- ../Tekkotsu_3.0/project/StartupBehavior.cc	2006-09-18 14:08:09.000000000 -0400
+++ ./project/StartupBehavior.cc	2007-08-05 12:16:05.000000000 -0400
@@ -1,7 +1,9 @@
 #include "StartupBehavior.h"
 
 #include "Behaviors/Controller.h"
-#include "Behaviors/Controls/BatteryCheckControl.h"
+#ifdef TGT_HAS_POWER_STATUS
+#  include "Behaviors/Controls/BatteryCheckControl.h"
+#endif
 #include "Behaviors/Controls/ControlBase.h"
 #include "Behaviors/Controls/HelpControl.h"
 #include "Behaviors/Controls/RebootControl.h"
@@ -66,12 +68,14 @@
 	stop_id=motman->addPersistentMotion(stop,MotionManager::kEmergencyPriority);
 	spawnedMC.push_back(stop_id);
 	
+#ifdef TGT_HAS_POWER_STATUS
 	//This displays the current battery conditions on the console
 	BatteryCheckControl batchk;
 	//	const SharedObject<LedMC> led;
 	//	batchk.activate(motman->addPrunableMotion(led,MotionManager::kEmergencyPriority+1),NULL);
 	batchk.activate(MotionManager::invalid_MC_ID,NULL);
 	batchk.deactivate();
+#endif
 
 	//This is what runs the menu system
 	Controller * controller=new Controller;
@@ -83,23 +87,18 @@
 	
 	sndman->playFile("roar.wav");
 
+#ifdef TGT_HAS_MOUTH
 	//This will close the mouth so it doesn't look stupid or get in the
 	//way of head motions (ERS-210 or ERS-7 only)
-	unsigned int mouthOffset=-1U;
-	if(state->robotDesign & WorldState::ERS210Mask)
-		mouthOffset=ERS210Info::MouthOffset;
-	if(state->robotDesign & WorldState::ERS7Mask)
-		mouthOffset=ERS7Info::MouthOffset;
-	if(mouthOffset!=-1U) {
-		SharedObject<TinyMotionSequenceMC> closeMouth;
-		closeMouth->advanceTime(3000); //take 3 seconds to close the mouth
-		closeMouth->setOutputCmd(mouthOffset,outputRanges[mouthOffset][MaxRange]);
-		closeMouth->advanceTime(500); //and hold it for another .5 seconds
-		closeMouth->setOutputCmd(mouthOffset,outputRanges[mouthOffset][MaxRange]);
-		MotionManager::MC_ID id=motman->addPrunableMotion(closeMouth,MotionManager::kEmergencyPriority+1);
-		erouter->addTimer(this,1,3250,false);
-		spawnedMC.push_back(id);
-	}
+	SharedObject<TinyMotionSequenceMC> closeMouth;
+	closeMouth->advanceTime(3000); //take 3 seconds to close the mouth
+	closeMouth->setOutputCmd(MouthOffset,outputRanges[MouthOffset][MaxRange]);
+	closeMouth->advanceTime(500); //and hold it for another .5 seconds
+	closeMouth->setOutputCmd(MouthOffset,outputRanges[MouthOffset][MaxRange]);
+	MotionManager::MC_ID id=motman->addPrunableMotion(closeMouth,MotionManager::kEmergencyPriority+1);
+	erouter->addTimer(this,1,3250,false);
+	spawnedMC.push_back(id);
+#endif
 	
 	//! we want to know if one of our MCs autoprunes (or is otherwise removed)
 	for(unsigned int i=0; i<spawnedMC.size(); i++)
@@ -155,20 +154,17 @@
 				//when this goes through, it will trigger the event handler below to follow through cleanup of the id
 				motman->removeMotion(pid_id);
 			}
+#ifdef TGT_HAS_MOUTH
 		} else if(event.getSourceID()==1) {
 			//we're done closing the mouth... set the mouth to closed in the estop too
 			//otherwise it might twitch a little when the MotionSequence expires and the estop takes over
 			// (little == +/-.1 radians, aka estop's threshold for resetting an "out of place" joint) (details, details)
-			unsigned int mouthOffset=-1U;
-			if(state->robotDesign & WorldState::ERS210Mask)
-				mouthOffset=ERS210Info::MouthOffset;
-			if(state->robotDesign & WorldState::ERS7Mask)
-				mouthOffset=ERS7Info::MouthOffset;
-			if(mouthOffset!=-1U) {
-				MMAccessor<EmergencyStopMC> estop(stop_id);
-				float weight=estop->getOutputCmd(mouthOffset).weight;
-				estop->setOutputCmd(mouthOffset,OutputCmd(outputRanges[mouthOffset][MaxRange],weight));
-			}
+			MMAccessor<EmergencyStopMC> estop(stop_id);
+			float weight=estop->getOutputCmd(MouthOffset).weight;
+			estop->setOutputCmd(MouthOffset,OutputCmd(outputRanges[MouthOffset][MaxRange],weight));
+#endif
+		} else {
+			cerr << "Warning: StartupBehavior got unknown timer event: " << event.getName() << endl;
 		}
 		
 	} else if(event.getGeneratorID()==EventBase::motmanEGID) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupBackgroundBehaviors.cc ./project/StartupBehavior_SetupBackgroundBehaviors.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupBackgroundBehaviors.cc	2006-09-21 17:26:08.000000000 -0400
+++ ./project/StartupBehavior_SetupBackgroundBehaviors.cc	2007-08-05 12:16:05.000000000 -0400
@@ -1,23 +1,33 @@
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Behaviors/Controls/ControlBase.h"
 #include "Behaviors/Controls/BehaviorSwitchControl.h"
 
-#include "Behaviors/Services/FlashIPAddrBehavior.h"
+#ifdef TGT_HAS_ACCELEROMETERS
+#  include "Behaviors/Services/AutoGetupBehavior.h"
+#endif
+#ifdef TGT_HAS_LEDS
+#  include "Behaviors/Services/FlashIPAddrBehavior.h"
+#endif
 #include "Behaviors/Demos/SimpleChaseBallBehavior.h"
 #include "Behaviors/Demos/StareAtBallBehavior.h"
-#include "Behaviors/Services/AutoGetupBehavior.h"
-#include "Behaviors/Services/BatteryMonitorBehavior.h"
-#include "Behaviors/Demos/HeadLevelBehavior.h"
+#ifdef TGT_HAS_POWER_STATUS
+#  include "Behaviors/Services/BatteryMonitorBehavior.h"
+#endif
 #include "Behaviors/Demos/ToggleHeadLightBehavior.h"
 #include "Behaviors/Demos/CrashTestBehavior.h"
 #include "Behaviors/Demos/FreezeTestBehavior.h"
 #include "Behaviors/Demos/RelaxBehavior.h"
 #include "Behaviors/Services/WorldStateVelDaemon.h"
 #include "Behaviors/Demos/CameraBehavior.h"
-#include "Behaviors/Demos/MotionStressTestBehavior.h"
+#ifdef TGT_HAS_LEGS
+#  include "Behaviors/Demos/MotionStressTestBehavior.h"
+#endif
 #include "Behaviors/Demos/ASCIIVisionBehavior.h"
-#include "Behaviors/Nodes/TailWagNode.h"
+#ifdef TGT_HAS_TAIL
+#  include "Behaviors/Nodes/TailWagNode.h"
+#endif
 #include "Sound/PitchDetector.h"
 
 #include "Behaviors/Demos/TestBehaviors.h"
@@ -29,17 +39,20 @@
 	{ 
 		addItem(new BehaviorSwitchControl<SimpleChaseBallBehavior>("Simple Chase Ball",false));
 		addItem(new BehaviorSwitchControl<StareAtBallBehavior>("Stare at Ball",false));
-		addItem(new BehaviorSwitchControl<HeadLevelBehavior>("Head Level",false));
-		if(state->robotDesign & WorldState::ERS220Mask)
+		if(RobotName==ERS220Info::TargetName)
 			addItem(new BehaviorSwitchControl<ToggleHeadLightBehavior>("Toggle Head Light",false));
+#ifdef TGT_HAS_TAIL
 		addItem(new BehaviorSwitchControl<TailWagNode>("Wag Tail",false));
+#endif
 		addItem(new BehaviorSwitchControl<RelaxBehavior>("Relax",false));
 		addItem(new BehaviorSwitchControl<CameraBehavior>("Camera",false));
 		addItem((new BehaviorSwitchControl<ASCIIVisionBehavior>("ASCIIVision",false)));
 		addItem(new ControlBase("Debugging Tests","Stress tests"));
 		startSubMenu();
 		{
+#ifdef TGT_HAS_LEGS
 			addItem(new BehaviorSwitchControl<MotionStressTestBehavior>("Motion Stress Test",false));
+#endif
 			addItem(new BehaviorSwitchControl<CrashTestBehavior>("Crash Test",false));
 			addItem(new BehaviorSwitchControl<FreezeTestBehavior>("Freeze Test",false));
 			// these following behaviors are all found in TestBehaviors.h, too small to warrant individual files
@@ -54,10 +67,16 @@
 		addItem(new ControlBase("System Daemons","Provide some common sensor or event processing"));
 		startSubMenu();
 		{
+#ifdef TGT_HAS_ACCELEROMETERS
 			addItem((new BehaviorSwitchControl<AutoGetupBehavior>("Auto Getup",false)));
+#endif
+#ifdef TGT_HAS_LEDS
 			addItem((new BehaviorSwitchControl<FlashIPAddrBehavior>("Flash IP Address",false))->start());
+#endif
 			addItem((new BehaviorSwitchControl<WorldStateVelDaemon>("World State Vel Daemon",false))->start());
+#ifdef TGT_HAS_POWER_STATUS
 			addItem((new BehaviorSwitchControl<BatteryMonitorBehavior>("Battery Monitor",false))->start());
+#endif
 			addItem((new BehaviorSwitchControl<PitchDetector>("Pitch Detection",false))->start());
 		}
 		endSubMenu();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupFileAccess.cc ./project/StartupBehavior_SetupFileAccess.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupFileAccess.cc	2005-06-06 19:05:59.000000000 -0400
+++ ./project/StartupBehavior_SetupFileAccess.cc	2007-08-05 12:16:05.000000000 -0400
@@ -1,4 +1,5 @@
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Behaviors/Controls/ControlBase.h"
 
@@ -9,19 +10,23 @@
 #include "Behaviors/Controls/WaypointWalkControl.h"
 #include "Behaviors/Controls/LoadPostureControl.h"
 #include "Behaviors/Controls/SavePostureControl.h"
+#include "Behaviors/Controls/ConfigurationEditor.h"
 
 ControlBase*
 StartupBehavior::SetupFileAccess() {
 	addItem(new ControlBase("File Access","Access/load files on the memory stick"));
 	startSubMenu();
 	{
+		addItem(new ConfigurationEditor("Tekkotsu Configuration"));
 		addItem(new LoadPostureControl("Load Posture",stop_id));
 		addItem(new SavePostureControl("Save Posture"));
 		addItem(new PostureEditor(stop_id));
 		addItem(new RunSequenceControl<XLargeMotionSequenceMC::CAPACITY>("Run Motion Sequence",stop_id));
 		addItem(new PlaySoundControl("Play Sound"));
 		addItem(new WaypointWalkControl());
+#ifdef TGT_HAS_LEGS
 		SetupWalkEdit();
+#endif
 		addItem(new DumpFileControl("Files",config->portPath("")));
 	}
 	return endSubMenu();
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupModeSwitch.cc ./project/StartupBehavior_SetupModeSwitch.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupModeSwitch.cc	2006-09-26 18:24:57.000000000 -0400
+++ ./project/StartupBehavior_SetupModeSwitch.cc	2007-11-21 19:06:52.000000000 -0500
@@ -1,25 +1,39 @@
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Behaviors/Controls/ControlBase.h"
 #include "Behaviors/Controls/BehaviorSwitchControl.h"
 
-#include "Behaviors/Demos/AlanBehavior.h"
 #include "Behaviors/Demos/ChaseBallBehavior.h"
-#include "Behaviors/Demos/FollowHeadBehavior.h"
 #include "Behaviors/Nodes/WalkToTargetNode.h"
 #include "Behaviors/Demos/HelloWorldBehavior.h"
-#include "Behaviors/Demos/BanditMachine.h"
-#include "Behaviors/Demos/SoundTestBehavior.h"
-#include "Behaviors/Demos/ExploreMachine.h"
-#include "Behaviors/Demos/PaceTargetsMachine.h"
-#include "Behaviors/Demos/StareAtPawBehavior2.h"
-#include "Behaviors/Demos/KinematicSampleBehavior.h"
-#include "Behaviors/Demos/KinematicSampleBehavior2.h"
-#include "Behaviors/Demos/GroundPlaneBehavior.h"
-#include "Behaviors/Demos/LookForSoundBehavior.h"
 #include "Behaviors/Demos/SimpleChaseBallBehavior.h"
-#include "Behaviors/Demos/StareAtBallBehavior.h"
-#include "Behaviors/Demos/WallTestBehavior.h"
+#ifdef TGT_HAS_HEAD
+#  include "Behaviors/Demos/StareAtBallBehavior.h"
+#  include "Behaviors/Demos/LookForSoundBehavior.h"
+#endif
+
+#ifdef TGT_HAS_BUTTONS
+#  ifdef TGT_HAS_HEAD
+#    include "Behaviors/Demos/FollowHeadBehavior.h"
+#  endif
+#  include "Behaviors/Demos/SoundTestBehavior.h"
+#  include "Behaviors/Demos/GroundPlaneBehavior.h"
+#endif
+
+#ifdef TGT_HAS_IR_DISTANCE
+#  include "Behaviors/Demos/ExploreMachine.h"
+#  include "Behaviors/Demos/PaceTargetsMachine.h"
+#  include "Behaviors/Demos/WallTestBehavior.h"
+#endif
+
+#ifdef TGT_HAS_LEGS
+#  include "Behaviors/Demos/AlanBehavior.h"
+#  include "Behaviors/Demos/StareAtPawBehavior2.h"
+#  include "Behaviors/Demos/KinematicSampleBehavior.h"
+#  include "Behaviors/Demos/KinematicSampleBehavior2.h"
+#  include "Behaviors/Demos/BanditMachine.h"
+#endif
 
 #include "Shared/ProjectInterface.h"
 
@@ -34,34 +48,50 @@
 
 		//put behaviors here:
 		addItem(new BehaviorSwitchControl<HelloWorldBehavior>("Hello World",false));
-		if(state->robotDesign&(WorldState::ERS210Mask|WorldState::ERS7Mask)) //this one only really works on the 210 or 7
-			addItem(new BehaviorSwitchControl<AlanBehavior>("Alan's Behavior",bg,false));
-		addItem(new BehaviorSwitchControl<FollowHeadBehavior>("Follow Head",bg,false));
+#ifdef TGT_HAS_LEGS
+		addItem(new BehaviorSwitchControl<AlanBehavior>("Alan's Behavior",bg,false));
+#endif
+#ifdef TGT_HAS_HEAD
 		addItem(new BehaviorSwitchControl<StareAtBallBehavior>("Stare at Pink Ball",bg,false));
+		addItem(new BehaviorSwitchControl<LookForSoundBehavior>("Look at Sound",bg,false));
+#endif
 		addItem(new BehaviorSwitchControl<SimpleChaseBallBehavior>("Simple Chase Ball",bg,false));
 		addItem(new BehaviorSwitchControl<ChaseBallBehavior>("Chase Ball",bg,false));
+#ifdef TGT_HAS_BUTTONS
+#  ifdef TGT_HAS_HEAD
+		addItem(new BehaviorSwitchControl<FollowHeadBehavior>("Follow Head",bg,false));
+#  endif
 		addItem(new BehaviorSwitchControl<SoundTestBehavior>("Sound Test",bg,false));
-		addItem(new BehaviorSwitchControl<LookForSoundBehavior>("Look at Sound",bg,false));
+#endif
 		addItem(new ControlBase("State Machine Demos","More fully developed demo applications"));
 		startSubMenu();
 		{
 			addItem(new BehaviorSwitchControlBase(new WalkToTargetNode("Walk To Target (ball)",ProjectInterface::visPinkBallSID),bg));
+#ifdef TGT_HAS_LEGS
 			addItem(new BehaviorSwitchControl<BanditMachine>("Bandit State Machine",bg,false));
+#endif
+#ifdef TGT_HAS_IR_DISTANCE
 			addItem(new BehaviorSwitchControl<ExploreMachine>("Explore State Machine",bg,false));
 			addItem(new BehaviorSwitchControl<PaceTargetsMachine>("Pace Targets State Machine",bg,false));
+#endif
 		}
 		endSubMenu();
 		addItem(new ControlBase("Kinematics Demos","Showcases some of the newly developed kinematics code"));
 		startSubMenu();
 		{
+#ifdef TGT_HAS_LEGS
 			addItem(new BehaviorSwitchControl<KinematicSampleBehavior>("Kinematic Sample 1",bg,false));
 			addItem(new BehaviorSwitchControl<KinematicSampleBehavior2>("Kinematic Sample 2",bg,false));
 			addItem(new BehaviorSwitchControl<StareAtPawBehavior2>("Stare at Paw",bg,false));
+#endif
+#ifdef TGT_HAS_BUTTONS
 			addItem(new BehaviorSwitchControl<GroundPlaneBehavior>("Ground Plane Test",bg,false));
+#endif
+#ifdef TGT_HAS_IR_DISTANCE
 			addItem(new BehaviorSwitchControl<WallTestBehavior>("Wall Test",bg,false));
+#endif
 		}
 		endSubMenu();
 	}
 	return endSubMenu();
 }
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupStatusReports.cc ./project/StartupBehavior_SetupStatusReports.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupStatusReports.cc	2005-01-12 17:37:26.000000000 -0500
+++ ./project/StartupBehavior_SetupStatusReports.cc	2007-08-05 12:16:06.000000000 -0400
@@ -1,8 +1,11 @@
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Behaviors/Controls/ControlBase.h"
 
-#include "Behaviors/Controls/BatteryCheckControl.h"
+#ifdef TGT_HAS_POWER_STATUS
+#  include "Behaviors/Controls/BatteryCheckControl.h"
+#endif
 #include "Behaviors/Controls/FreeMemReportControl.h"
 #include "Behaviors/Controls/ProfilerCheckControl.h"
 #include "Behaviors/Controls/EventLogger.h"
@@ -16,7 +19,9 @@
 	startSubMenu();
 	{
 		addItem(new BehaviorReportControl());
+#ifdef TGT_HAS_POWER_STATUS
 		addItem(new BatteryCheckControl());
+#endif
 		addItem(new ProfilerCheckControl());
 		addItem(new EventLogger());
 		addItem(new SensorObserverControl());
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupTekkotsuMon.cc ./project/StartupBehavior_SetupTekkotsuMon.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupTekkotsuMon.cc	2006-08-03 18:58:36.000000000 -0400
+++ ./project/StartupBehavior_SetupTekkotsuMon.cc	2007-11-21 15:57:12.000000000 -0500
@@ -1,48 +1,93 @@
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Behaviors/Controls/ControlBase.h"
 #include "Behaviors/Controls/BehaviorSwitchControl.h"
 
+#ifdef TGT_HAS_HEAD
+#  include "Behaviors/Mon/HeadPointControllerBehavior.h"
+#endif
+
+#if defined(TGT_HAS_LEGS) || defined(TGT_HAS_WHEELS)
+#  include "Behaviors/Mon/WalkControllerBehavior.h"
+#endif
+
+#ifdef TGT_HAS_LEGS
+#  include "Behaviors/Mon/UPennWalkControllerBehavior.h"
+#  include "Behaviors/Mon/StewartPlatformBehavior.h"
+#endif
+
+#ifdef TGT_HAS_CAMERA
+#  include "Behaviors/Mon/RawCamBehavior.h"
+#  include "Behaviors/Mon/SegCamBehavior.h"
+#  include "Behaviors/Mon/RegionCamBehavior.h"
+#endif
+
+#ifdef TGT_HAS_MICROPHONE
+#  include "Behaviors/Mon/MicrophoneServer.h"
+#endif
+
+#ifdef TGT_HAS_SPEAKERS
+#  include "Behaviors/Mon/SpeakerServer.h"
+#endif
+
+#if ( defined(TGT_HAS_ARMS) || defined(TGT_HAS_LEGS) ) && defined(TGT_HAS_HEAD)
+#  include "Behaviors/Mon/RoverControllerBehavior.h"
+#endif
+
 #include "Behaviors/Mon/ViewWMVarsBehavior.h"
-#include "Behaviors/Mon/WalkControllerBehavior.h"
-#include "Behaviors/Mon/UPennWalkControllerBehavior.h"
-#include "Behaviors/Mon/HeadPointControllerBehavior.h"
-#include "Behaviors/Mon/StewartPlatformBehavior.h"
-#include "Behaviors/Mon/Aibo3DControllerBehavior.h"
-#include "Behaviors/Mon/EStopControllerBehavior.h"
 #include "Behaviors/Mon/WMMonitorBehavior.h"
-#include "Behaviors/Mon/RawCamBehavior.h"
-#include "Behaviors/Mon/SegCamBehavior.h"
-#include "Behaviors/Mon/RegionCamBehavior.h"
+#include "Behaviors/Mon/EStopControllerBehavior.h"
+#include "Behaviors/Mon/Aibo3DControllerBehavior.h"
 #include "Behaviors/Mon/WorldStateSerializerBehavior.h"
-#include "Behaviors/Mon/MicrophoneServer.h"
-#include "Behaviors/Mon/SpeakerServer.h"
 #include "Behaviors/Mon/EchoBehavior.h"
-#include "Behaviors/Mon/SpiderMachineBehavior.h"
+
+template<class T>
+class SingletonFactory : public Factory0Arg<T> {
+public:
+	virtual T* operator()() { return &T::getInstance(); }
+};
 
 ControlBase*
 StartupBehavior::SetupTekkotsuMon() {
 	addItem(new ControlBase("TekkotsuMon","Servers for GUIs"));
 	startSubMenu();
 	{ 
+#ifdef TGT_HAS_HEAD
 		addItem((new BehaviorSwitchControl<HeadPointControllerBehavior>("Head Remote Control",false)));
+#endif
+#if defined(TGT_HAS_LEGS) || defined(TGT_HAS_WHEELS)
 		addItem((new BehaviorSwitchControl<WalkControllerBehavior>("Walk Remote Control",false)));
+#endif
+#ifdef TGT_HAS_LEGS
 		addItem((new BehaviorSwitchControl<UPennWalkControllerBehavior>("UPenn Walk Remote Control",false)));
+		addItem((new BehaviorSwitchControl<StewartPlatformBehavior>("Stewart Platform",false)));
+#endif
 		addItem((new BehaviorSwitchControl<ViewWMVarsBehavior>("View WMVars",false)));
 		addItem((new BehaviorSwitchControl<WMMonitorBehavior>("Watchable Memory Monitor",false))->start());
-		addItem((new BehaviorSwitchControl<StewartPlatformBehavior>("Stewart Platform",false)));
-		addItem((new BehaviorSwitchControl<Aibo3DControllerBehavior>("Aibo 3D",false)));
+		addItem((new BehaviorSwitchControlBase(new EStopControllerBehavior(stop_id)))->start());
 		BehaviorSwitchControlBase * wss=NULL;
+#if defined(TGT_ERS7) || defined(TGT_ERS210) || defined(TGT_ERS2xx)
+		// do this *before* WorldStateSerializer to avoid crash on shutdown (ugly, sorry)
+		addItem((new BehaviorSwitchControl<Aibo3DControllerBehavior>("Aibo 3D",false)));
+#endif
 		addItem((wss=new BehaviorSwitchControl<WorldStateSerializerBehavior>("World State Serializer",false)));
 		Aibo3DControllerBehavior::setSerializerControl(wss);
+#ifdef TGT_HAS_CAMERA
 		addItem((new BehaviorSwitchControl<RawCamBehavior>("Raw Cam Server",false)));
 		addItem((new BehaviorSwitchControl<SegCamBehavior>("Seg Cam Server",false)));
 		addItem((new BehaviorSwitchControl<RegionCamBehavior>("Region Cam Server",false)));
-		addItem((new BehaviorSwitchControlBase(new EStopControllerBehavior(stop_id)))->start());
-		addItem(new BehaviorSwitchControlBase(MicrophoneServer::GetInstance()));
-		addItem(new BehaviorSwitchControlBase(SpeakerServer::GetInstance()));
+#endif
+#ifdef TGT_HAS_MICROPHONE
+		addItem((new BehaviorSwitchControl<MicrophoneServer,SingletonFactory<MicrophoneServer> >("Microphone Server",false)));
+#endif
+#ifdef TGT_HAS_SPEAKERS
+		addItem((new BehaviorSwitchControl<SpeakerServer,SingletonFactory<SpeakerServer> >("Speaker Server",false)));
+#endif
+#if ( defined(TGT_HAS_ARMS) || defined(TGT_HAS_LEGS) ) && defined(TGT_HAS_HEAD)
+		addItem((new BehaviorSwitchControl<RoverControllerBehavior,SingletonFactory<RoverControllerBehavior> >("Rover Control",false)));
+#endif
 		addItem((new BehaviorSwitchControl<EchoBehavior>("Echo Client/Server",false)));
-		addItem((new BehaviorSwitchControl<SpiderMachineBehavior>("Spider State Machines Server",false)));
 	}
 	return endSubMenu();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupVision.cc ./project/StartupBehavior_SetupVision.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupVision.cc	2006-06-30 12:35:32.000000000 -0400
+++ ./project/StartupBehavior_SetupVision.cc	2007-08-05 12:16:06.000000000 -0400
@@ -1,4 +1,5 @@
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Shared/ProjectInterface.h"
 #include "Shared/Config.h"
@@ -23,7 +24,9 @@
 #include "Vision/CDTGenerator.h"
 
 #include "Behaviors/Demos/DrawVisObjBoundBehavior.h"
+#ifdef TGT_HAS_LEGS
 #include "Behaviors/Demos/DrawSkeletonBehavior.h"
+#endif
 
 using namespace ProjectInterface;
 
@@ -31,7 +34,7 @@
 BallDetectionGenerator * bball=NULL;
 BallDetectionGenerator * gball=NULL;
 BallDetectionGenerator * yball=NULL;
-BallDetectionGenerator * handball=NULL; //aka orange
+BallDetectionGenerator * oball=NULL; //aka orange
 
 /*! We set the default vision generators and source IDs here.
  *
@@ -106,7 +109,7 @@
 
 	// these names match up with /ms/config/default.col - the default
 	// color information... if that changes, these should change too
-	unsigned int threshChan=config->vision.segcam_channel;
+	unsigned int threshChan=config->vision.segcam.channel;
 
 	// higher value reduce false events, but increase reaction time [0-inf]
 	unsigned int noiseFiltering=1;
@@ -136,8 +139,8 @@
 	}
 	unsigned int skinIdx=segcol->getColorIndex("orange");
 	if(skinIdx!=-1U) {
-		handball = new BallDetectionGenerator(visHandSID,defRegionGenerator,skinIdx,threshChan,noiseFiltering,confidenceThreshold);
-		handball->setName("HandBallDetectionGenerator");
+		oball = new BallDetectionGenerator(visOrangeSID,defRegionGenerator,skinIdx,threshChan,noiseFiltering,confidenceThreshold);
+		oball->setName("OrangeBallDetectionGenerator");
 	}
 }
 
@@ -147,7 +150,9 @@
 	startSubMenu();
 	{ 
 		addItem((new BehaviorSwitchControl<DrawVisObjBoundBehavior>("Draw Object Boundaries",false)));
+#ifdef TGT_HAS_LEGS
 		addItem((new BehaviorSwitchControl<DrawSkeletonBehavior>("Draw Skeleton",false)));
+#endif
 #ifndef PLATFORM_APERIOS		
 		addItem(new SimulatorAdvanceFrameControl("Advance Frame"));
 #endif
@@ -205,10 +210,10 @@
 		else
 			addItem(new NullControl("Error: BlueBallDetectionGenerator","Color \"yellow\" is undefined"));
 
-		if(handball)
-			addItem((new BehaviorSwitchControlBase(handball))->start());
+		if(oball)
+			addItem((new BehaviorSwitchControlBase(oball))->start());
 		else
-			addItem(new NullControl("Error: HandBallDetectionGenerator","Color \"orange\" is undefined"));
+			addItem(new NullControl("Error: OrangeBallDetectionGenerator","Color \"orange\" is undefined"));
 	}
 	return endSubMenu();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/StartupBehavior_SetupWalkEdit.cc ./project/StartupBehavior_SetupWalkEdit.cc
--- ../Tekkotsu_3.0/project/StartupBehavior_SetupWalkEdit.cc	2005-09-22 17:54:17.000000000 -0400
+++ ./project/StartupBehavior_SetupWalkEdit.cc	2007-11-21 17:53:19.000000000 -0500
@@ -16,6 +16,7 @@
  */
 
 #include "StartupBehavior.h"
+#include "Shared/RobotInfo.h"
 
 #include "Behaviors/Controls/ControlBase.h"
 
@@ -32,6 +33,13 @@
 	addItem(new ControlBase("Walk Edit","Edit the walk parameters"));
 	startSubMenu();
 	{ 
+#if defined(TGT_ERS210) || defined(TGT_ERS220) || defined(TGT_ERS2xx)
+		// Replace this if section with an #if 1 to re-enable
+		// This functionality takes about 1MB of memory on the Aibo between loading the binary
+		// code and the actual control memory usage.
+		addItem(new ControlBase("Disabled to conserve memory"));
+#else
+		
 		//Use this instance of the GUI to try out changes you have made to parameters within this editor
 		//(the one in TekkotsuMon will load fresh parameters from walk.prm on disk and won't know about changes made here)
 		WalkControllerBehavior * walker = new WalkControllerBehavior();
@@ -46,8 +54,8 @@
 			addItem(new ValueEditControl<double>("Body Angle",&walker->getWalkMC()->getWP().body_angle));
 			addItem(new ValueEditControl<double>("Hop",&walker->getWalkMC()->getWP().hop));
 			addItem(new ValueEditControl<double>("Sway",&walker->getWalkMC()->getWP().sway));
-			addItem(new ValueEditControl<long>("Period",&walker->getWalkMC()->getWP().period));
-			addItem(new ValueEditControl<long>("Use Diff Drive",&walker->getWalkMC()->getWP().useDiffDrive));
+			addItem(new ValueEditControl<int>("Period",&walker->getWalkMC()->getWP().period));
+			addItem(new ValueEditControl<int>("Use Diff Drive",&walker->getWalkMC()->getWP().useDiffDrive));
 			addItem(new ValueEditControl<float>("Sag",&walker->getWalkMC()->getWP().sag));
 		}
 		endSubMenu();
@@ -144,6 +152,7 @@
 
 		addItem(new LoadWalkControl("Load Walk",walker->getWalkMC()));
 		addItem(new SaveWalkControl("Save Walk",walker->getWalkMC()));
+#endif
 	}
 	return endSubMenu();
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/aperios/Makefile.aperios ./project/aperios/Makefile.aperios
--- ../Tekkotsu_3.0/project/aperios/Makefile.aperios	2006-09-12 16:17:54.000000000 -0400
+++ ./project/aperios/Makefile.aperios	2007-11-07 18:27:01.000000000 -0500
@@ -7,8 +7,8 @@
 #Each directory represents a separate OObject aka process/thread
 #PROJ_OOBJECTS holds those defined in the project, OOBJECTS
 #holds those defined in either/both $(TEKKOTSU_ROOT) and project
-PROJ_OOBJECTS:=$(filter-out CVS bin include lib share man,$(subst aperios/,,$(shell find aperios -mindepth 1 -maxdepth 1 -type d -prune)))
-OOBJECTS:=$(sort $(PROJ_OOBJECTS) $(filter-out CVS bin include lib share man,$(subst $(TEKKOTSU_ROOT)/aperios/,,$(shell find $(TEKKOTSU_ROOT)/aperios -mindepth 1 -maxdepth 1 -type d -prune))))
+PROJ_OOBJECTS:=$(filter-out .svn CVS bin include lib share man,$(subst aperios/,,$(shell find aperios -mindepth 1 -maxdepth 1 -type d -prune)))
+OOBJECTS:=$(sort $(PROJ_OOBJECTS) $(filter-out .svn CVS bin include lib share man,$(subst $(TEKKOTSU_ROOT)/aperios/,,$(shell find $(TEKKOTSU_ROOT)/aperios -mindepth 1 -maxdepth 1 -type d -prune))))
 
 # Location of Aperios (the Aibo's OS) binary executables
 SYSTEM_BINARIES:=$(OPENRSDK_ROOT)/OPEN_R/MS_$(if $(findstring $(TEKKOTSU_TARGET_MODEL),TGT_ERS7),ERS7,ERS200)/WCONSOLE/nomemprot
@@ -74,9 +74,6 @@
 		fi; \
 	done;
 
-OSRCS:=$(shell find aperios -name "*$(SRCSUFFIX)")
-DEPENDS:=$(DEPENDS) $(addprefix $(PROJ_BD)/,$(OSRCS:$(SRCSUFFIX)=.d))
-
 #the touch at the end is because memsticks seem to round time to even seconds, which screws up updates.  Grr.
 compile: cleanTemps checkInstallBinTimestamp $(PROJ_BD)/installbin.timestamp
 	@image="$(PROJ_BD)/$(notdir $(MEMSTICK_ROOT))" ; \
@@ -90,7 +87,7 @@
 		chmod -R u+w "$$image" ; \
 		$(CONVERTCASE) -r $$image/*; \
 		rm -f "$$image/open-r/mw/conf/connect.cfg" "$$image/open-r/mw/conf/object.cfg" "$$image/open-r/system/conf/wlandflt.txt" ; \
-		find -d "$$image" -type d -empty -exec rmdir \{\} \; ; \
+		find "$$image" -depth -type d -empty -exec rmdir \{\} \; ; \
 		curt=`date +%Y%m%d%H%M`; \
 		find "$$image" -exec touch -ft $$curt \{\} \; ; \
 	fi;
@@ -125,6 +122,11 @@
 	printf "Target Model: $(patsubst TGT_%,%,$(TEKKOTSU_TARGET_MODEL))\n" >> $$bldinfo ; \
 	printf "Target Platform: $(patsubst PLATFORM_%,%,$(TEKKOTSU_TARGET_PLATFORM))\n" >> $$bldinfo ; \
 	printf "Project: %s\nFramework: %s\n" "`pwd`" "$(TEKKOTSU_ROOT)" >> $$bldinfo
+	@echo "Type: '$(MAKE) install' to compile and copy all files to the memory stick";
+	@echo "  or: '$(MAKE) update' to compile and copy only changed files";
+	@echo "  or: '$(MAKE) ftpupdate IPADDRESS=<ipaddr>' to compile and copy changed files over FTP";
+	@echo "     ('$(TEKKOTSU_ROOT)/tools/{ftpinstall,ftpupdate} <ipaddr> ms' might also be useful)";
+	@echo "Build successful."
 
 checkInstallBinTimestamp:
 	@if [ \! -d "$(MSIMGDIR)" ] ; then \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/defaults/hal-Create.plist ./project/defaults/hal-Create.plist
--- ../Tekkotsu_3.0/project/defaults/hal-Create.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./project/defaults/hal-Create.plist	2007-11-21 18:46:11.000000000 -0500
@@ -0,0 +1,37 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--======== CommPorts ========-->
+<!--Communication portals for use by device drivers-->
+<key>CommPorts</key> <dict></dict>
+
+<!--======== Drivers ========-->
+<!--Settings for device drivers-->
+<key>Drivers</key> <dict>
+	<!--======== Create ========-->
+	<key>Create</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>Create</string>
+		
+		<!--CommPort: The name of the comm port where output will be sent-->
+		<key>CommPort</key> <string>/dev/ttyAM1</string>
+	</dict>
+	
+	<!--======== TeRK ========-->
+	<key>TeRK</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>TeRK</string>
+	</dict>
+</dict>
+
+<!--======== Vision ========-->
+<!--Settings for the loading of camera frames-->
+<key>Vision</key> <dict>
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: TeRK.Camera -->
+	<key>Source</key> <string>TeRK</string>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/defaults/hal-LynxArm6.plist ./project/defaults/hal-LynxArm6.plist
--- ../Tekkotsu_3.0/project/defaults/hal-LynxArm6.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./project/defaults/hal-LynxArm6.plist	2007-07-19 16:36:28.000000000 -0400
@@ -0,0 +1,283 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--InitialRunlevel: Specifies how far startup should proceed before pausing for user interaction.
+This value only affects startup, and setting this value from the simulator command prompt will have no effect.  (Use the 'runlevel' command instead.)-->
+<key>InitialRunlevel</key> <string>RUNNING</string>
+
+<!--InitialTime: The value to initialize the simulator's clock (in milliseconds)-->
+<key>InitialTime</key> <integer>0</integer>
+
+<!--======== Motion ========-->
+<!--Parameters for motion simulation-->
+<key>Motion</key> <dict>
+	<!--FeedbackDelay: Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)-->
+	<key>FeedbackDelay</key> <integer>0</integer>
+	
+	<!--OverrideSensors: Allows motion feedback to override position values from sensor data loaded from disk.
+	If false, feedback is only provided when no other sensor data is being provided-->
+	<key>OverrideSensors</key> <false/>
+	
+	<!--Verbose: Report whenever motion commands are being processed or joints are updated
+	0 - nothing, 1 - errors, 2 - warnings (e.g. dropped frames), 3 - notification every frame-->
+	<key>Verbose</key> <integer>1</integer>
+	
+	<!--ZeroPIDFeedback: When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative-->
+	<key>ZeroPIDFeedback</key> <false/>
+</dict>
+
+<!--Multiprocess: The processing/threading model to use - true to use real process forks a la Aibo/Aperios, or false to just more threads like a sane person would do-->
+<key>Multiprocess</key> <false/>
+
+<!--Speed: The speed at which to run the simulation, as a multiple of "real-time".
+For example, '1' is normal, '0.5' is half-speed, '0' is paused.
+Any negative value requests non-realtime mode, where the clock is moved as fast as processing (or manual control) allows.-->
+<key>Speed</key> <real>1</real>
+
+<!--WaitForSensors: If true, wait for initial sensor readings before triggering the startup behavior or starting the motion polling thread.  On some platforms, sensed output values can be used to initialize output positions.  On others, you may be unable to get any feedback, or can only expect feedback if the robot was left running and the executable is reconnecting.-->
+<key>WaitForSensors</key> <false/>
+
+<!--======== CommPorts ========-->
+<!--Communication portals for use by device drivers-->
+<key>CommPorts</key> <dict>
+	<!--======== Net ========-->
+	<key>Net</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>NetworkCommPort</string>
+		
+		<!--Hostname to connect to, or interface to listen on (blank for INADDR_ANY)-->
+		<key>Host</key> <string></string>
+		
+		<!--Port number to connect to or listen on-->
+		<key>Port</key> <integer>0</integer>
+		
+		<!--Server: If true, should listen for incoming connections instead of making an outgoing one.-->
+		<key>Server</key> <false/>
+		
+		<!--Transport protocol to use-->
+		<key>Transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--======== Serial ========-->
+	<key>Serial</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>SerialCommPort</string>
+		
+		<!--Flags: Configuration string to pass to stty-->
+		<key>Flags</key> <string>115200 sane raw -echo</string>
+		
+		<!--Mode bitmask to pass to the open() call, defaults to 'w+b': in|out|trunc|binary (see std::ios_base::openmode)-->
+		<key>Mode</key> <integer>60</integer>
+		
+		<!--Path of file system object being accessed-->
+		<key>Path</key> <string>/dev/ttyS0</string>
+	</dict>
+</dict>
+
+<!--======== Drivers ========-->
+<!--Settings for device drivers-->
+<key>Drivers</key> <dict>
+	<!--======== SSC32 ========-->
+	<key>SSC32</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>SSC32</string>
+		
+		<!--======== ButtonMode ========-->
+		<!--Controls interpretation of the input pin.
+		False means directly measure voltage, true means test for high (1),
+		high now but low was detected in interval (0.5), or low (0).
+		Button mode implies interpreting inputMap value as a button index instead of sensor index.-->
+		<key>ButtonMode</key> <array>
+			<false/>
+			<false/>
+			<false/>
+			<false/>
+		</array>
+		
+		<!--CommPort: The name of the comm port where output will be sent-->
+		<key>CommPort</key> <string>Serial</string>
+		
+		<!--======== InputMap ========-->
+		<!--For each of the SSC32's input pins, lists the sensor index it should send its value to; -1 to mark unused-->
+		<key>InputMap</key> <array>
+			<integer>0</integer>
+			<integer>1</integer>
+			<integer>2</integer>
+			<integer>3</integer>
+		</array>
+		
+		<!--======== MaxPulseWidth ========-->
+		<!--The high end of the servo's legal pulse width range (may correspond to unreachable position, use RobotInfo's outputRange[] to limit motion, not this)-->
+		<key>MaxPulseWidth</key> <array>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+		</array>
+		
+		<!--======== MinPulseWidth ========-->
+		<!--The low end of the servo's legal pulse width range (may correspond to unreachable position, use RobotInfo's outputRange[] to limit motion, not this)-->
+		<key>MinPulseWidth</key> <array>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+		</array>
+		
+		<!--======== OutputMap ========-->
+		<!--For each of the SSC32's servo pins, lists the output index it should take its values from; -1 to mark unused-->
+		<key>OutputMap</key> <array>
+			<integer>0</integer>
+			<integer>1</integer>
+			<integer>2</integer>
+			<integer>3</integer>
+			<integer>4</integer>
+			<integer>5</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+		</array>
+		
+		<!--QueryServos: If set to true, will attempt to query the servo positions with each sensor update.
+		This may decrease the sampling frequency-->
+		<key>QueryServos</key> <false/>
+		
+		<!--SparseUpdates: If true, only send servo positions to SSC when they change, instead of all servos on every update (don't use a lossy transport like UDP if you turn this on!)-->
+		<key>SparseUpdates</key> <false/>
+	</dict>
+</dict>
+
+<!--======== Sensors ========-->
+<!--Settings for the loading of sensor values-->
+<key>Sensors</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>31.25</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: SSC32.Sensors -->
+	<key>Source</key> <string>SSC32</string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+
+<!--======== Vision ========-->
+<!--Settings for the loading of camera frames-->
+<key>Vision</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>30</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: (none available, see 'new' command to instantiate drivers)-->
+	<key>Source</key> <string></string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/defaults/hal-QBotPlus.plist ./project/defaults/hal-QBotPlus.plist
--- ../Tekkotsu_3.0/project/defaults/hal-QBotPlus.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./project/defaults/hal-QBotPlus.plist	2007-08-25 02:28:24.000000000 -0400
@@ -0,0 +1,106 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--InitialRunlevel: Specifies how far startup should proceed before pausing for user interaction.
+This value only affects startup, and setting this value from the simulator command prompt will have no effect.  (Use the 'runlevel' command instead.)-->
+<key>InitialRunlevel</key> <string>RUNNING</string>
+
+<!--InitialTime: The value to initialize the simulator's clock (in milliseconds)-->
+<key>InitialTime</key> <integer>0</integer>
+
+<!--======== Motion ========-->
+<!--Parameters for motion simulation-->
+<key>Motion</key> <dict>
+	<!--FeedbackDelay: Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)-->
+	<key>FeedbackDelay</key> <integer>0</integer>
+	
+	<!--OverrideSensors: Allows motion feedback to override position values from sensor data loaded from disk.
+	If false, feedback is only provided when no other sensor data is being provided-->
+	<key>OverrideSensors</key> <false/>
+	
+	<!--Verbose: Report whenever motion commands are being processed or joints are updated
+	0 - nothing, 1 - errors, 2 - warnings (e.g. dropped frames), 3 - notification every frame-->
+	<key>Verbose</key> <integer>1</integer>
+	
+	<!--ZeroPIDFeedback: When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative-->
+	<key>ZeroPIDFeedback</key> <false/>
+</dict>
+
+<!--Multiprocess: The processing/threading model to use - true to use real process forks a la Aibo/Aperios, or false to just more threads like a sane person would do-->
+<key>Multiprocess</key> <false/>
+
+<!--Speed: The speed at which to run the simulation, as a multiple of "real-time".
+For example, '1' is normal, '0.5' is half-speed, '0' is paused.
+Any negative value requests non-realtime mode, where the clock is moved as fast as processing (or manual control) allows.-->
+<key>Speed</key> <real>1</real>
+
+<!--WaitForSensors: If true, wait for initial sensor readings before triggering the startup behavior or starting the motion polling thread.  On some platforms, sensed output values can be used to initialize output positions.  On others, you may be unable to get any feedback, or can only expect feedback if the robot was left running and the executable is reconnecting.-->
+<key>WaitForSensors</key> <false/>
+
+<!--======== CommPorts ========-->
+<!--Communication portals for use by device drivers-->
+<key>CommPorts</key> <dict/>
+
+<!--======== Drivers ========-->
+<!--Settings for device drivers-->
+<key>Drivers</key> <dict>
+	<!--======== TeRK ========-->
+	<key>TeRK</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>TeRK</string>
+	</dict>
+</dict>
+
+<!--======== Sensors ========-->
+<!--Settings for the loading of sensor values-->
+<key>Sensors</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>66.6667</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: TeRK.Sensors -->
+	<key>Source</key> <string></string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+
+<!--======== Vision ========-->
+<!--Settings for the loading of camera frames-->
+<key>Vision</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>30</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: TeRK.Camera -->
+	<key>Source</key> <string>TeRK</string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/defaults/hal-Qwerk.plist ./project/defaults/hal-Qwerk.plist
--- ../Tekkotsu_3.0/project/defaults/hal-Qwerk.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./project/defaults/hal-Qwerk.plist	2007-08-20 17:31:15.000000000 -0400
@@ -0,0 +1,106 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--InitialRunlevel: Specifies how far startup should proceed before pausing for user interaction.
+This value only affects startup, and setting this value from the simulator command prompt will have no effect.  (Use the 'runlevel' command instead.)-->
+<key>InitialRunlevel</key> <string>RUNNING</string>
+
+<!--InitialTime: The value to initialize the simulator's clock (in milliseconds)-->
+<key>InitialTime</key> <integer>0</integer>
+
+<!--======== Motion ========-->
+<!--Parameters for motion simulation-->
+<key>Motion</key> <dict>
+	<!--FeedbackDelay: Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)-->
+	<key>FeedbackDelay</key> <integer>0</integer>
+	
+	<!--OverrideSensors: Allows motion feedback to override position values from sensor data loaded from disk.
+	If false, feedback is only provided when no other sensor data is being provided-->
+	<key>OverrideSensors</key> <false/>
+	
+	<!--Verbose: Report whenever motion commands are being processed or joints are updated
+	0 - nothing, 1 - errors, 2 - warnings (e.g. dropped frames), 3 - notification every frame-->
+	<key>Verbose</key> <integer>1</integer>
+	
+	<!--ZeroPIDFeedback: When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative-->
+	<key>ZeroPIDFeedback</key> <false/>
+</dict>
+
+<!--Multiprocess: The processing/threading model to use - true to use real process forks a la Aibo/Aperios, or false to just more threads like a sane person would do-->
+<key>Multiprocess</key> <false/>
+
+<!--Speed: The speed at which to run the simulation, as a multiple of "real-time".
+For example, '1' is normal, '0.5' is half-speed, '0' is paused.
+Any negative value requests non-realtime mode, where the clock is moved as fast as processing (or manual control) allows.-->
+<key>Speed</key> <real>1</real>
+
+<!--WaitForSensors: If true, wait for initial sensor readings before triggering the startup behavior or starting the motion polling thread.  On some platforms, sensed output values can be used to initialize output positions.  On others, you may be unable to get any feedback, or can only expect feedback if the robot was left running and the executable is reconnecting.-->
+<key>WaitForSensors</key> <false/>
+
+<!--======== CommPorts ========-->
+<!--Communication portals for use by device drivers-->
+<key>CommPorts</key> <dict/>
+
+<!--======== Drivers ========-->
+<!--Settings for device drivers-->
+<key>Drivers</key> <dict>
+	<!--======== TeRK ========-->
+	<key>TeRK</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>TeRK</string>
+	</dict>
+</dict>
+
+<!--======== Sensors ========-->
+<!--Settings for the loading of sensor values-->
+<key>Sensors</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>66.6667</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: TeRK.Sensors -->
+	<key>Source</key> <string></string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+
+<!--======== Vision ========-->
+<!--Settings for the loading of camera frames-->
+<key>Vision</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>30</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: TeRK.Camera -->
+	<key>Source</key> <string>TeRK</string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/defaults/hal-Regis1.plist ./project/defaults/hal-Regis1.plist
--- ../Tekkotsu_3.0/project/defaults/hal-Regis1.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./project/defaults/hal-Regis1.plist	2007-10-03 15:59:25.000000000 -0400
@@ -0,0 +1,301 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--InitialRunlevel: Specifies how far startup should proceed before pausing for user interaction.
+This value only affects startup, and setting this value from the simulator command prompt will have no effect.  (Use the 'runlevel' command instead.)-->
+<key>InitialRunlevel</key> <string>RUNNING</string>
+
+<!--InitialTime: The value to initialize the simulator's clock (in milliseconds)-->
+<key>InitialTime</key> <integer>0</integer>
+
+<!--======== Motion ========-->
+<!--Parameters for motion simulation-->
+<key>Motion</key> <dict>
+	<!--FeedbackDelay: Delay (in milliseconds) to apply to motion output before feeding back to sensor values (simulates (very roughly) inertia and system response time); 0 indicates instantaneous/perfect joint control, negative values indicate no feedback (only sensor data sets joint positions)-->
+	<key>FeedbackDelay</key> <integer>0</integer>
+	
+	<!--OverrideSensors: Allows motion feedback to override position values from sensor data loaded from disk.
+	If false, feedback is only provided when no other sensor data is being provided-->
+	<key>OverrideSensors</key> <false/>
+	
+	<!--Verbose: Report whenever motion commands are being processed or joints are updated
+	0 - nothing, 1 - errors, 2 - warnings (e.g. dropped frames), 3 - notification every frame-->
+	<key>Verbose</key> <integer>1</integer>
+	
+	<!--ZeroPIDFeedback: When set to false, if PIDs are set to zero, then sensor values are used to set joint positions; otherwise joint position sensors would only be used if FeedbackDelay is negative-->
+	<key>ZeroPIDFeedback</key> <false/>
+</dict>
+
+<!--Multiprocess: The processing/threading model to use - true to use real process forks a la Aibo/Aperios, or false to just more threads like a sane person would do-->
+<key>Multiprocess</key> <false/>
+
+<!--Speed: The speed at which to run the simulation, as a multiple of "real-time".
+For example, '1' is normal, '0.5' is half-speed, '0' is paused.
+Any negative value requests non-realtime mode, where the clock is moved as fast as processing (or manual control) allows.-->
+<key>Speed</key> <real>1</real>
+
+<!--WaitForSensors: If true, wait for initial sensor readings before triggering the startup behavior or starting the motion polling thread.  On some platforms, sensed output values can be used to initialize output positions.  On others, you may be unable to get any feedback, or can only expect feedback if the robot was left running and the executable is reconnecting.-->
+<key>WaitForSensors</key> <false/>
+
+<!--======== CommPorts ========-->
+<!--Communication portals for use by device drivers-->
+<key>CommPorts</key> <dict>
+	<!--======== net-image ========-->
+	<key>net-image</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>NetworkCommPort</string>
+		
+		<!--Hostname to connect to, or interface to listen on (blank for INADDR_ANY)-->
+		<key>Host</key> <string>172.16.1.9</string>
+		
+		<!--Port number to connect to or listen on-->
+		<key>Port</key> <integer>11001</integer>
+		
+		<!--Server: If true, should listen for incoming connections instead of making an outgoing one.-->
+		<key>Server</key> <false/>
+		
+		<!--Transport protocol to use-->
+		<key>Transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--======== net-image-motion ========-->
+	<key>net-image-motion</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>NetworkCommPort</string>
+		
+		<!--Hostname to connect to, or interface to listen on (blank for INADDR_ANY)-->
+		<key>Host</key> <string>172.16.1.9</string>
+		
+		<!--Port number to connect to or listen on-->
+		<key>Port</key> <integer>11000</integer>
+		
+		<!--Server: If true, should listen for incoming connections instead of making an outgoing one.-->
+		<key>Server</key> <false/>
+		
+		<!--Transport protocol to use-->
+		<key>Transport</key> <string>TCP</string>
+	</dict>
+</dict>
+
+<!--======== Drivers ========-->
+<!--Settings for device drivers-->
+<key>Drivers</key> <dict>
+	<!--======== SSC32 ========-->
+	<key>SSC32</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>SSC32</string>
+		
+		<!--======== ButtonMode ========-->
+		<!--Controls interpretation of the input pin.
+		False means directly measure voltage, true means test for high (1),
+		high now but low was detected in interval (0.5), or low (0).
+		Button mode implies interpreting inputMap value as a button index instead of sensor index.-->
+		<key>ButtonMode</key> <array>
+			<false/>
+			<false/>
+			<false/>
+			<false/>
+		</array>
+		
+		<!--CommPort: The name of the comm port where output will be sent-->
+		<key>CommPort</key> <string>net-image-motion</string>
+		
+		<!--======== InputMap ========-->
+		<!--For each of the SSC32's input pins, lists the sensor index it should send its value to; -1 to mark unused-->
+		<key>InputMap</key> <array>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+		</array>
+		
+		<!--======== MaxPulseWidth ========-->
+		<!--The high end of the servo's legal pulse width range (may correspond to unreachable position, use RobotInfo's outputRange[] to limit motion, not this)-->
+		<key>MaxPulseWidth</key> <array>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+			<integer>2500</integer>
+		</array>
+		
+		<!--======== MinPulseWidth ========-->
+		<!--The low end of the servo's legal pulse width range (may correspond to unreachable position, use RobotInfo's outputRange[] to limit motion, not this)-->
+		<key>MinPulseWidth</key> <array>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+			<integer>500</integer>
+		</array>
+		
+		<!--======== OutputMap ========-->
+		<!--For each of the SSC32's servo pins, lists the output index it should take its values from; -1 to mark unused-->
+		<key>OutputMap</key> <array>
+			<integer>0</integer>
+			<integer>1</integer>
+			<integer>2</integer>
+			<integer>3</integer>
+			<integer>4</integer>
+			<integer>5</integer>
+			<integer>6</integer>
+			<integer>7</integer>
+			<integer>8</integer>
+			<integer>9</integer>
+			<integer>10</integer>
+			<integer>11</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+			<integer>-1</integer>
+		</array>
+		
+		<!--QueryServos: If set to true, will attempt to query the servo positions with each sensor update.
+		This may decrease the sampling frequency-->
+		<key>QueryServos</key> <false/>
+		
+		<!--SparseUpdates: If true, only send servo positions to SSC when they change, instead of all servos on every update (don't use a lossy transport like UDP if you turn this on!)-->
+		<key>SparseUpdates</key> <true/>
+	</dict>
+	
+	<!--======== seq ========-->
+	<key>seq</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>ImageStream</string>
+		
+		<!--CommPort: The name of the comm port from which data will be read.-->
+		<key>CommPort</key> <string>net-image</string>
+		
+		<!--Format: The type of format to expect from the comm port.
+		'YUV' expects interleaved components 'CameraResolutionX' wide and 'CameraResolutionY' high
+		(defined in target's RobotInfo namespace)-->
+		<key>Format</key> <string>jpeg</string>
+	</dict>
+</dict>
+
+<!--======== Sensors ========-->
+<!--Settings for the loading of sensor values-->
+<key>Sensors</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>66.6667</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: SSC32.Sensors -->
+	<key>Source</key> <string></string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+
+<!--======== Vision ========-->
+<!--Settings for the loading of camera frames-->
+<key>Vision</key> <dict>
+	<!--Framerate: The rate at which images should be loaded.  This is passed as a hint to the source, which may be limited to multiples of its capture device frequency.-->
+	<key>Framerate</key> <real>30</real>
+	
+	<!--Frozen: If true, no frames will be sent, except via explicit 'advance' commands; if false, the thread will run and send messages at the requested times automatically-->
+	<key>Frozen</key> <false/>
+	
+	<!--Heartbeat: If enabled, an empty "heartbeat" message is sent at the appropriate framerate, even if no data is being processed (i.e. frozen, no data loaded, or out of frames); this will cause an update event within the simulator, repeating processing on the previous data.-->
+	<key>Heartbeat</key> <true/>
+	
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: (none available, see 'new' command to instantiate drivers)-->
+	<key>Source</key> <string>seq</string>
+	
+	<!--Verbose: Controls how much feedback to give on the console regarding progress
+	  0 - none
+	  1 - report when messages are dropped
+	  2 - also report when a message is sent
+	  3 - also report when heartbeat is sent/dropped, and when loop occurs
+	  4 - also report when each message is preloaded-->
+	<key>Verbose</key> <integer>0</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/defaults/hal-common.plist ./project/defaults/hal-common.plist
--- ../Tekkotsu_3.0/project/defaults/hal-common.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./project/defaults/hal-common.plist	2007-11-21 18:46:11.000000000 -0500
@@ -0,0 +1,31 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--======== Drivers ========-->
+<!--Settings for device drivers-->
+<key>Drivers</key> <dict>
+	
+	<!--======== Logged ========-->
+	<key>Logged</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>LoggedData</string>
+	</dict>
+	
+	<!--======== Camera ========-->
+	<key>Camera</key> <dict>
+		<!--.type: Stores the typename of the class so it can be re-instantiated on load.
+		** Do not edit ** -->
+		<key>.type</key> <string>Camera</string>
+	</dict>
+</dict>
+
+<!--======== Vision ========-->
+<!--Settings for the loading of camera frames-->
+<key>Vision</key> <dict>
+	<!--Source: Names a DeviceDriver instance from which data will be taken.
+	Can be either just the driver name (use first data source), or 'DriverName.QueueName'.
+	Available data sources: Camera.iSight Logged.Camera -->
+	<key>Source</key> <string>Camera</string>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/local/Makefile.local ./project/local/Makefile.local
--- ../Tekkotsu_3.0/project/local/Makefile.local	2006-05-10 17:36:23.000000000 -0400
+++ ./project/local/Makefile.local	2007-11-18 01:45:17.000000000 -0500
@@ -2,15 +2,28 @@
 $(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: 
+# Each directory which contains a source file of the same name is considered
+# a separate executable, and its subdirectory is specific to it
 
-#Each directory should represent a separate executable
-PROJ_EXECS:=$(filter-out CVS,$(subst local/,,$(shell find local -mindepth 1 -maxdepth 1 -type d -prune)))
-EXECS:=$(sort $(PROJ_EXECS) $(filter-out CVS,$(subst $(TEKKOTSU_ROOT)/local/,,$(shell find $(TEKKOTSU_ROOT)/local -mindepth 1 -maxdepth 1 -type d -prune))))
-TGTEXECS:=$(addsuffix $(subst TGT_,-,$(TEKKOTSU_TARGET_MODEL)),$(EXECS))
+# check project directory
+PROJ_EXECS:=$(patsubst local/%,%,$(shell find local -mindepth 1 -maxdepth 1 -type d -name '[a-z]*'))
+# check framework directory
+EXECS:=$(patsubst $(TEKKOTSU_ROOT)/local/%,%,$(shell find $(TEKKOTSU_ROOT)/local -mindepth 1 -maxdepth 1 -type d -name '[a-z]*'))
+EXECS:=$(filter-out terk,$(EXECS))
+EXECS:=$(sort $(PROJ_EXECS) $(EXECS))
 
-ESRCS:=$(shell find local -name "*$(SRCSUFFIX)")
-DEPENDS:=$(DEPENDS) $(addprefix $(PROJ_BD)/,$(ESRCS:$(SRCSUFFIX)=.d))
+$(EXECS): %: checkLibs %-$(subst TGT_,,$(TEKKOTSU_TARGET_MODEL))
+
+.PHONY: $(EXECS)
+
+ifeq ($(shell if [ -d "$(ICE_ROOT)" ] ; then echo HAVE_ICE; fi),HAVE_ICE)
+	PROJ_EXECS:=$(filter-out terk,$(PROJ_EXECS))
+endif
+LSRC_SKIP:=$(foreach x,$(PROJ_EXECS),\! -path local/$(x)/\*)
+LSRCS:=$(shell find local $(LSRC_SKIP) -name "*$(SRCSUFFIX)")
+SRCS:=$(SRCS) $(LSRCS)
+
+TGTEXECS:=$(addsuffix $(subst TGT_,-,$(TEKKOTSU_TARGET_MODEL)),$(EXECS))
 
 ifeq ($(shell uname | grep -ci cygwin),0)
   PLATFORM_FLAGS:=$(PLATFORM_FLAGS) -DHAVE_READDIR_R
@@ -36,10 +49,10 @@
 		echo >> $@ ; \
 	done;
 
-compile: $(TGTEXECS)
-	@echo "You probably now want to run './sim$(subst TGT_,-,$(TEKKOTSU_TARGET_MODEL))'";
+compile compile-sim: tekkotsu-$(subst TGT_,,$(TEKKOTSU_TARGET_MODEL))
+	@echo "Build successful."
 
-$(TGTEXECS): $(PROJ_BD)/project.a
+$(TGTEXECS): $(PROJ_BD)/project.a $(USERLIBS) 
 	@if [ -r dist_hosts.txt -a -r $(PROJ_BD)/joblist.txt ] ; then \
 		echo "Distributing compiles..."; \
 		../tools/pm.pl dist_hosts.txt $(PROJ_BD)/joblist.txt ; \
@@ -48,6 +61,7 @@
 	@echo "Creating executable binary..."
 	@objs="$($@_OBJS)" ; \
 	libs="$(PROJ_BD)/project.a $(USERLIBS) $(LDFLAGS)" ; \
+	undef=`nm -g "$(PROJ_BD)/project.a" $(filter %.a,$(USERLIBS)) | grep autoRegister | grep -v " *U" | cut -f 3 -d ' ' | sort -u | sed 's/^/-u /'`; \
 	echo "$@ <- $${objs} $${libs}" | sed 's@$(PROJ_BD)/@@g'; \
-	$(CXX) -o $@ $$objs $$libs  ; \
-
+	$(CXX) -o $@ $$undef $$objs $$libs  ;
+	@echo "You probably now want to run './$@'";
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/config/QBotPlus.kin ./project/ms/config/QBotPlus.kin
--- ../Tekkotsu_3.0/project/ms/config/QBotPlus.kin	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/QBotPlus.kin	2007-11-22 00:31:00.000000000 -0500
@@ -0,0 +1,81 @@
+# ----------------------------------------------------------
+# Robot Configuration File
+# ----------------------------------------------------------
+[Default]
+
+[Body]
+Name:       Body
+DH:         1
+Fix:        0
+MinPara:    0
+dof:        0
+Motor:      0
+Stl:        0
+
+[Camera]
+Name:       Camera
+DH:         1
+Fix:        0
+MinPara:    0
+dof:        2
+Motor:      0
+Stl:        0
+
+[Camera_LINK1]
+joint_type:	0
+immobile:   1
+theta:	0.0
+d:	0.0
+a:	-115.0
+alpha:	0.0
+theta_min:	0.0
+theta_max:	0.0
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera_LINK2]
+joint_type:	0
+theta:	0.0
+d:	55.0
+a:	151.0
+alpha:	1.57079632679
+theta_min:	-1.745329251
+theta_max:	1.745329251
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera_LINK3]
+joint_type:	0
+theta:	0.0
+d:	60.0
+a:	0.0
+alpha:	0.0
+theta_min:	-.174532925
+theta_max:	3.316125578
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/config/Regis1.kin ./project/ms/config/Regis1.kin
--- ../Tekkotsu_3.0/project/ms/config/Regis1.kin	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/Regis1.kin	2007-11-22 00:31:00.000000000 -0500
@@ -0,0 +1,242 @@
+# ----------------------------------------------------------
+# Robot Configuration File
+# ----------------------------------------------------------
+[Default]
+
+[Body]
+Name:       Body
+DH:         1
+Fix:        0
+MinPara:    0
+dof:        0
+Motor:      0
+Stl:        0
+
+[Arm]
+Name:       Arm
+DH:         1
+Fix:        0
+MinPara:    0
+dof:        6
+Motor:      0
+Stl:        0
+
+[Arm_LINK1]
+joint_type:	0
+immobile: 1
+theta:	1.57079632679
+d:	0.0
+a:	0.0
+alpha:	1.57079632679
+theta_min:	0.0
+theta_max:	0.0
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Arm_LINK2]
+joint_type:	0
+theta:	0.0
+d:	160.0
+a:	0.0
+alpha:	1.57079632679
+theta_min:	-1.57079632679
+theta_max:	1.57079632679
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Arm_LINK3]
+joint_type:	0
+theta:	1.57079632679
+d:	0.0
+a:	138.0
+alpha:	0.0
+theta_min:	-1.57079632679
+theta_max:	1.57079632679
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Arm_LINK4]
+joint_type:	0
+theta:	0.0
+d:	0.0
+a:	127.0
+alpha:	0.0
+theta_min:	-1.57079632679
+theta_max:	1.57079632679
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Arm_LINK5]
+joint_type:	0
+theta:	-1.57079632679
+d:	0.0
+a:	0.0
+alpha:	-1.57079632679
+theta_min:	0.0
+theta_max:	0.0
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Arm_LINK6]
+joint_type:	0
+theta:	-1.57079632679
+d:	105.0
+a:	0.0
+alpha:	0.0
+theta_min:	0.0
+theta_max:	0.0
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera]
+Name:       Camera
+DH:         1
+Fix:        0
+MinPara:    0
+dof:        5
+Motor:      0
+Stl:        0
+
+[Camera_LINK1]
+joint_type:	0
+theta:	0.0
+d:	-64.0
+a:	0.0
+alpha:	1.57079632679
+theta_min:	-1.745329251
+theta_max:	1.745329251
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera_LINK2]
+joint_type:	0
+theta:	0.0
+d:	0.0
+a:	151.0
+alpha:	0.0
+theta_min:	0.0
+theta_max:	0.0
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera_LINK3]
+joint_type:	0
+theta:	0.0
+d:	0.0
+a:	225.0
+alpha:	0.0
+theta_min:	-.174532925
+theta_max:	3.316125578
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera_LINK4]
+joint_type:	0
+immobile: 1
+theta:	-1.57079632679
+d:	0.0
+a:	0.0
+alpha:	-1.57079632679
+theta_min:	-2.443460952
+theta_max:	1.047197551
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
+
+[Camera_LINK5]
+joint_type:	0
+theta:	90.0
+d:	0.0
+a:	90.0
+alpha:	0.0
+theta_min:	-2.617993877
+theta_max:	0.872664625
+m:          0.0
+cx:         0.0
+cy:         0.0
+cz:         0.0
+Ixx:        0.0
+Ixy:        0.0
+Ixz:        0.0
+Iyy:        0.0
+Iyz:        0.0
+Izz:        0.0
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/config/sim_ovrd.cfg ./project/ms/config/sim_ovrd.cfg
--- ../Tekkotsu_3.0/project/ms/config/sim_ovrd.cfg	2006-07-05 16:17:18.000000000 -0400
+++ ./project/ms/config/sim_ovrd.cfg	1969-12-31 19:00:00.000000000 -0500
@@ -1,47 +0,0 @@
-##################################################################
-######################   Tekkotsu config   #######################
-##################################################################
-##################### $Name: tekkotsu-3_0 $ ######################
-####################### $Revision: 1.1 $ ########################
-################## $Date: 2006/07/05 20:17:18 $ ##################
-##################################################################
-#
-# See tekkotsu.cfg for format documentation.
-# 
-# This file contains overrides for settings that should be applied when running in the simulator.
-# This is not a complete list of available parameters, just those which should be redefined.
-#
-# These are not settings which control the simulator itself, these are simply different values
-# for settings which are normally applied when running on the robot.  The simulator has its
-# own set of configuration parameters, by default stored in 'simulator.plist' in the same
-# directory as the simulator executable.
-#
-##################################################################
-
-
-
-##################################################################
-##################################################################
-[Vision]
-##################################################################
-##################################################################
-
-### Image Streaming Format ###
-# These parameters control the video stream over wireless ethernet
-# transport can be either 'udp' or 'tcp'
-rawcam_transport=tcp
-segcam_transport=tcp
-
-# compression       none | jpeg | png
-rawcam_compression=none
-
-# log_2 of number of pixels to skip, 0 sends reconstructed double
-#   resolution (mainly useful for Y channel, others are just resampled)
-#   our eyes are more sensitive to intensity (y channel) so you might
-#   want to send the UV channels at a lower resolution (higher skip) as
-#   a form of compression
-# rawcam_y_skip is used when in sending single channel, regardless of
-#   which channel
-# valid values are 0-5
-rawcam_y_skip=1
-rawcam_uv_skip=1
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/config/sim_ovrd.xml ./project/ms/config/sim_ovrd.xml
--- ../Tekkotsu_3.0/project/ms/config/sim_ovrd.xml	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/sim_ovrd.xml	2007-11-22 00:31:00.000000000 -0500
@@ -0,0 +1,51 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict><!--
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+#########################   $Name: tekkotsu-4_0 $   ##########################
+#####################   $Revision: 1.2 $   ######################
+################   $Date: 2007/02/06 22:17:47 $   ################
+##################################################################
+
+This is an XML-based format using the Property List (plist) layout.
+
+See tekkotsu.xml for format documentation.
+
+This file contains overrides for settings that should be applied when running in 
+the simulator.  This is not a complete list of available parameters, just those 
+which should be redefined.
+
+These are not settings which control the simulator itself, these are simply 
+different values than those which are normally applied when running on the 
+robot.  The simulator has its own set of configuration parameters, by default 
+stored in 'simulator.plist' in the same directory as the simulator executable.
+-->
+
+<!--======== vision ========-->
+<key>vision</key> <dict>
+	<!--======== rawcam ========-->
+	<key>rawcam</key> <dict>
+		<!--compression: the type of compression to apply the image
+		Value is one of: { none | jpeg } -->
+		<key>compression</key> <string>none</string>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+		
+		<!--uv_skip: resolution level to transmit uv channel at when using 'color' encoding mode-->
+		<key>uv_skip</key> <integer>1</integer>
+		
+		<!--y_skip: resolution level to transmit y channel
+		Also used as the resolution level when in single-channel encoding mode -->
+		<key>y_skip</key> <integer>1</integer>
+	</dict>
+	
+	<!--======== segcam ========-->
+	<key>segcam</key> <dict>
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+	</dict>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/config/tekkotsu.cfg ./project/ms/config/tekkotsu.cfg
--- ../Tekkotsu_3.0/project/ms/config/tekkotsu.cfg	2006-09-21 17:26:09.000000000 -0400
+++ ./project/ms/config/tekkotsu.cfg	1969-12-31 19:00:00.000000000 -0500
@@ -1,420 +0,0 @@
-##################################################################
-######################   Tekkotsu config   #######################
-##################################################################
-##################### $Name: tekkotsu-3_0 $ ######################
-####################### $Revision: 1.71 $ ########################
-################## $Date: 2006/09/21 21:26:09 $ ##################
-##################################################################
-#
-# Format:
-#
-# * Comments are any line beginning with '#'
-#
-# * Model specific regions can be denoted with <MODELNAME>...</MODELNAME>
-#   - Wildcards can also be used: <ERS-2*>...</ERS-2*>
-#   - Anything not within a model region is read by all models (i.e. <*>..</*>)
-#   - Don't get fancy with the "tags" - one per line, the parser's not that smart
-#     (feel free to hack it if you want - it's in Config.cc)
-#
-# * Sections are demarcated with [SECTIONNAME]
-#   - A section is only ended by another section beginning
-#   - Section transitions within a model region will only be read by that model
-#   - Section names are case insensitive
-#
-# * Otherwise, each line is interpreted as: variable=value
-#   - this should correspond to Config::curSectionName_config::variable
-#   - interpretation is up to the code in Config.cc
-#   - some variables are lists (additional assignments push on the list),
-#     others are simply overwritten if a new value is assigned.
-#   - variable names are case insensitive
-#
-# * You can override these at run time from the Controller using the command:
-#   !set section_name.variable=value
-#   - Of course, whether or not the new value will be picked up depends on
-#     how it is being used...
-#
-# * Paths are assumed to be relative to the project/ms/ directory.
-#   For example, this file would be referenced as config/tekkotsu.cfg
-#
-##################################################################
-
-
-
-##################################################################
-##################################################################
-[Wireless]
-##################################################################
-##################################################################
-# unique id for Aibo (not used by Tekkotsu, but you might want it...)
-id=1
-
-
-
-##################################################################
-##################################################################
-[Vision]
-##################################################################
-##################################################################
-
-# white_balance  indoor | flourescent | outdoor
-<ERS-2*>
-white_balance=flourescent
-</ERS-2*>
-<ERS-7>
-white_balance=indoor
-</ERS-7>
-
-# gain           low | mid | high
-# higher gain will brighten the image, but increases noise
-gain=mid
-
-# shutter_speed  slow | mid | fast
-# slower shutter will brighten image, but increases motion blur
-<ERS-2*>
-shutter_speed=mid
-</ERS-2*>
-<ERS-7>
-shutter_speed=slow
-</ERS-7>
-
-# resolution     quarter | half | full
-# this is the resolution vision's object recognition system will run at
-resolution=full
-
-
-### Color Segmentation Threshold files ###
-# Threshold (.tm) files define the mapping from full color to indexed color
-# You can uncomment more than one of these - they will be loaded into
-# separate channels of the segmenter.  The only cost of loading multiple
-# threshold files is memory - the CPU cost of performing segmentation is
-# only done if/when the channel is actually accessed.
-
-# Included options for color threshold file:
-<ERS-2*>
-# 210pb.tm - pink and blue
-# 210phb.tm - pink, skin (hand), and blue
-#   note: "skin" is just of people who work in our lab - not a general sampling... :(
-# 210genrl.tm - general colors for the ERS-210
-# ball.tm - standard Sony pink ball definition
-thresh=config/210phb.tm
-thresh=config/210genrl.tm
-thresh=config/ball.tm
-</ERS-2*>
-<ERS-7>
-# 7general.tm - a general classification of a variety of colors for the ERS-7
-# 7red.tm - just a very broad pink/red/purple => "pink" color detection
-# ball.tm - standard Sony pink ball definition
-thresh=config/7general.tm
-</ERS-7>
-
-# the .col file gives names and a "typical" color for display
-# the indexes numbers it contains correspond to indexes in the .tm file
-# This file is common to all .tm files -- when doing new color segmentations,
-# make sure you define colors in the same order as listed here!
-colors=config/default.col
-
-
-### Image Streaming Format ###
-# These parameters control the video stream over wireless ethernet
-# transport can be either 'udp' or 'tcp'
-rawcam_port=10011
-rawcam_transport=udp
-segcam_port=10012
-segcam_transport=udp
-region_port=10013
-region_transport=tcp
-
-# pause between raw image grabs: 0 for fast-as-possible, 100 for 10 FPS, etc
-# in milliseconds
-segcam_interval=0
-
-# rawcam_encoding   color | y_only | uv_only | u_only | v_only | y_dx_only | y_dy_only | y_dxdy_only
-rawcam_encoding=color
-
-# compression       none | jpeg
-rawcam_compression=jpeg
-
-# quality of jpeg compression 0-100
-rawcam_compress_quality=85
-
-# pause between raw image grabs: 0 for fast-as-possible, 100 for 10 FPS
-# in milliseconds
-rawcam_interval=0
-
-# apparently someone at sony thinks it's a good idea to replace some
-# pixels in each camera image with information like the frame number
-# and CDT count.  if non-zero, will replace those pixels with the
-# actual image pixel value in RawCamGenerator
-restore_image=1
-
-# When true, this will fill in the CMVision::color_class_state::total_area
-# field for each color following region labeling.  If false, the total_area
-# will stay 0 (or whatever the last value was), but you save a little CPU.
-region_calc_total=1;
-
-# jpeg algorithm: 'islow' (integer, slow, but quality), 'ifast' (integer, fast, but rough), 'float' (floating point)
-jpeg_dct_method=ifast
-
-# log_2 of number of pixels to skip, 0 sends reconstructed double
-#   resolution (mainly useful for Y channel, others are just resampled)
-#   our eyes are more sensitive to intensity (y channel) so you might
-#   want to send the UV channels at a lower resolution (higher skip) as
-#   a form of compression
-# rawcam_y_skip is used when in sending single channel, regardless of
-#   which channel
-# valid values are 0-5
-rawcam_y_skip=2
-rawcam_uv_skip=3
-
-# you can send the original segmented image
-# or an RLE compressed version (which includes some noise removal)
-#segcam_compression   none | rle
-segcam_compression=rle
-
-# this is the channel of the seg cam which should be sent.
-# corresponds to the index of the .tm file you want in thresh
-segcam_channel=0
-
-# this is the log_2 of pixels to skip when sending
-# segmented camera images, same idea as rawcam_*_skip
-segcam_skip=1
-
-# this is the log_2 of pixels to skip when sending Region information,
-# same idea as rawcam_*_skip (added by nvh 21-04-05)
-regioncam_skip=1
-
-
-### Camera Calibration ###
-# see Config::vision_config::{computeRay,computePixel} to convert
-# between world coordinates and pixel coordinates using these values
-  
-# focal length (in pixels)
-focal_len_x = 198.807
-focal_len_y = 200.333
-  
-# center of optical projection (in pixels)
-principle_point_x = 102.689
-principle_point_y = 85.0399
-  
-# skew of CCD
-skew = 0
-  
-# Radial distortion terms
-kc1_r2 = -0.147005
-kc2_r4 = 0.38485
-kc5_r6 = 0
-  
-# Tangential distortion terms
-kc3_tan1 = -0.00347777
-kc4_tan2 = 0.00012873
-
-# resolution at which calibration images were taken
-calibration_res_x = 208
-calibration_res_y = 160
-
-
-##################################################################
-##################################################################
-[Main]
-##################################################################
-##################################################################
-
-# if non-zero, will call srand() with a high-precision timestamp, mangled by sensor data
-seed_rng=1
-
-# this mode parameter determines how input on console_port is handled
-# 'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
-# 'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
-# 'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise
-consoleMode=controller
-console_port=10001
-
-stderr_port=10002
-error_level=0
-debug_level=0
-verbose_level=0
-wsjoints_port=10031
-wspids_port=10032
-walkControl_port=10050
-aibo3d_port=10051
-headControl_port=10052
-estopControl_port=10053
-#stewart_port=10055
-wmmonitor_port=10061
-use_VT100=true
-# pause between writes: 0 for fast-as-possible, 100 for 10 FPS, etc.
-# in milliseconds
-#worldState_interval=0
-
-
-##################################################################
-##################################################################
-[Behaviors]
-##################################################################
-##################################################################
-
-### FlashIPAddrBehavior ###
-
-# You probably already know the first 3 bytes for your network
-# so you might only want the last byte for brevity
-# (valid values are 1 through 4)
-flash_bytes=4
-
-# Do you want to automatically trigger this on boot?
-# Will use a priority of kEmergencyPriority+1 in order to override
-# the emergency stop's status animation
-flash_on_start=0
-
-
-# your-stuff-here?
-
-##################################################################
-##################################################################
-[Controller]
-##################################################################
-##################################################################
-gui_port=10020
-select_snd=whiip.wav
-next_snd=toc.wav
-prev_snd=tick.wav
-read_snd=ping.wav
-cancel_snd=whoop.wav
-error_snd=fart.wav
-
-
-
-##################################################################
-##################################################################
-[Motion]
-##################################################################
-##################################################################
-
-# Any motion related paths which are not absolute (i.e. do not
-# start with '/') will be assumed to be relative to this directory
-root=data/motion
-
-# This is the default set of walk parameters
-walk=walk.prm
-
-# The file specified by "kinematics" should define the kinematic
-# chains which form your robot.
-# "kinematic_chains" lists the names of the chains which should be
-# loaded from that file
-<ERS-2*>
-<ERS-210>
-kinematics=/config/ers210.kin
-kinematic_chains=Body
-kinematic_chains=Mouth
-</ERS-210>
-<ERS-220>
-kinematics=/config/ers220.kin
-kinematic_chains=Body
-</ERS-220>
-kinematic_chains=IR
-</ERS-2*>
-<ERS-7>
-kinematics=/config/ers7.kin
-kinematic_chains=Body
-kinematic_chains=Mouth
-kinematic_chains=NearIR
-kinematic_chains=FarIR
-kinematic_chains=ChestIR
-</ERS-7>
-kinematic_chains=LFr
-kinematic_chains=RFr
-kinematic_chains=LBk
-kinematic_chains=RBk
-kinematic_chains=Camera
-
-# These values indicate the ratio of actual movement to commanded
-# So .9 means it moves 90% as far as it was supposed to.
-# This is then used both to calibrate joint values sent to the
-# system, as well as sensor values which are received back.
-# An unspecified joint is by default '1' which will then pass values
-# through unmodified.  Only PID joints are calibrated (i.e. LEDs and
-# ears are not)
-<ERS-7>
-calibrate:LFr:rotor=1.0
-calibrate:LFr:elvtr=1.0
-calibrate:LFr:knee~=1.0
-#...
-#The calibration I performed doesn't seem to hold up well, so
-#I'm leaving these all at 1.0.  Perhaps there is a constant
-#offset involved?  To be continued...
-</ERS-7>
-<ERS-2*>
-#ERS-2xx seems to be fairly well calibrated by system, but
-#you can always try to do better...
-</ERS-2*>
-
-# Sounds to play when turning estop on and off
-estop_on_snd=skid.wav
-estop_off_snd=yap.wav
-
-# These values are used by some behaviors to limit the
-# speed of the head to reduce wear on the joints
-# Units: radians per second
-<ERS-2*>
-max_head_tilt_speed=2.1
-max_head_pan_speed=3.0
-max_head_roll_speed=3.0
-</ERS-2*>
-<ERS-7>
-#the pan speed is revised down from Sony's maximum a bit
-max_head_tilt_speed=3.18522588
-max_head_pan_speed=5.78140315
-max_head_roll_speed=5.78140315
-</ERS-7>
-
-# If non-zero, robot should attempt to change directions instantaniously
-# If zero, robot should change directions more fluidly (following some internal acceleration calibration)
-inf_walk_accel=0
-
-console_port=10003
-stderr_port=10004
-
-
-
-##################################################################
-##################################################################
-[Sound]
-##################################################################
-##################################################################
-root=data/sound
-# volume = mute | level_1 | level_2 | level_3 | <direct dB setting: 0x8000 - 0xFFFF>
-# if you directly set the decibel level, be warned sony recommends against going above 0xF600
-# However, I believe the commercial software on the ERS-7 runs at 0xFF00
-# going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
-volume=level_3
-
-# Sound playback currently requires all sounds to be the same bit
-# rate.  Aperios further requires only either 8bit/8KHz or 16bit/16KHz
-# formats
-sample_rate=16000
-sample_bits=16
-
-# Preload is a list of sounds to cache at boot
-# can be either root relative or full path
-preload=skid.wav
-preload=yap.wav
-
-# Pitch detection confidence threshold [0-1]
-# Determines how liberal the pitch detector is at generating PitchEvents
-pitchConfidenceThreshold=0.6
-
-# Audio streaming settings
-# Audio from the AIBO's microphones
-streaming.mic_port=10070
-streaming.mic_sample_rate=16000
-streaming.mic_bits=16
-streaming.mic_stereo=true
-
-# Audio to the AIBO's speakers
-streaming.speaker_port=10071
-# Length of the speaker streaming buffer (ms)
-# Streamed samples are sent to the sound manager in packets of this length
-streaming.speaker_frame_len=64
-# Maximum delay (ms) during playback of received samples
-# If the playback queue gets longer it is emptied.
-streaming.speaker_max_delay=1000
-
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/config/tekkotsu.xml ./project/ms/config/tekkotsu.xml
--- ../Tekkotsu_3.0/project/ms/config/tekkotsu.xml	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/config/tekkotsu.xml	2007-11-22 00:31:00.000000000 -0500
@@ -0,0 +1,535 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict><!--
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+#########################   $Name: tekkotsu-4_0 $   ##########################
+#####################   $Revision: 1.11 $   ######################
+################   $Date: 2007/11/16 15:35:35 $   ################
+##################################################################
+
+This is an XML-based format using the Property List (plist) layout.
+
+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 in 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.
+
+You can change these settings at run time from the Controller
+by entering the command:
+   !set section_name.variable=value
+or by using the configuration editor found in the "File Access"
+menu.  Paths are assumed to be relative to the 'project/ms/'
+directory.  For example, this file would be referenced as
+'config/tekkotsu.xml'
+
+See also the 'simulator.xml' file, which provides you the ability
+to override settings when running in the simulator
+-->
+
+<!--======== behaviors ========-->
+<key>behaviors</key> <dict>
+	<!--flash_bytes: how many bytes of the address to flash
+	You probably already know the first 3 bytes for your network,
+	so you might only want the last byte for brevity.
+	(valid values are 1 through 4) -->
+	<key>flash_bytes</key> <integer>4</integer>
+	
+	<!--flash_on_start: whether or not to automatically trigger on boot
+	Will use a priority of kEmergencyPriority+1 in order to override
+	the emergency stop's status animation -->
+	<key>flash_on_start</key> <false/>
+</dict>
+
+<!--======== controller ========-->
+<key>controller</key> <dict>
+	<!--gui_port: port to listen for the GUI to connect to aibo on-->
+	<key>gui_port</key> <integer>10020</integer>
+	
+	<!--cancel_snd: sound file to use for "cancel" action-->
+	<key>cancel_snd</key> <string>whoop.wav</string>
+	
+	<!--error_snd: sound file to use to signal errors-->
+	<key>error_snd</key> <string>fart.wav</string>
+	
+	<!--next_snd: sound file to use for "next" action-->
+	<key>next_snd</key> <string>toc.wav</string>
+	
+	<!--prev_snd: sound file to use for "prev" action-->
+	<key>prev_snd</key> <string>tick.wav</string>
+	
+	<!--read_snd: sound file to use for "read from std-in" action-->
+	<key>read_snd</key> <string>ping.wav</string>
+	
+	<!--select_snd: sound file to use for "select" action-->
+	<key>select_snd</key> <string>whiip.wav</string>
+</dict>
+
+<!--======== main ========-->
+<key>main</key> <dict>
+	<!--aibo3d_port: port for send/receive of joint positions from Aibo 3D GUI-->
+	<key>aibo3d_port</key> <integer>10051</integer>
+	
+	<!--consoleMode: determines how input on console_port is interpreted
+	Value is one of: { controller | textmsg | auto } 
+	  'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
+	  'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
+	  'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise -->
+	<key>consoleMode</key> <string>controller</string>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10001</integer>
+	
+	<!--estopControl_port: port for receiving walk commands-->
+	<key>estopControl_port</key> <integer>10053</integer>
+	
+	<!--headControl_port: port for receiving head commands-->
+	<key>headControl_port</key> <integer>10052</integer>
+	
+	<!--seed_rng: if true, will call srand with timestamp data, mangled by current sensor data-->
+	<key>seed_rng</key> <true/>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10002</integer>
+	
+	<!--stewart_port: port for running a stewart platform style of control-->
+	<key>stewart_port</key> <integer>10055</integer>
+	
+	<!--use_VT100: if true, enables VT100 console codes (currently only in Controller menus - 1.3)-->
+	<key>use_VT100</key> <false/>
+	
+	<!--walkControl_port: port for receiving walk commands-->
+	<key>walkControl_port</key> <integer>10050</integer>
+	
+	<!--wmmonitor_port: port for monitoring Watchable Memory-->
+	<key>wmmonitor_port</key> <integer>10061</integer>
+	
+	<!--worldState_interval: time (in milliseconds) to wait between sending WorldState updates over wireless-->
+	<key>worldState_interval</key> <integer>0</integer>
+	
+	<!--wsjoints_port: port to send joint positions on-->
+	<key>wsjoints_port</key> <integer>10031</integer>
+	
+	<!--wspids_port: port to send pid info on-->
+	<key>wspids_port</key> <integer>10032</integer>
+</dict>
+
+<!--======== motion ========-->
+<key>motion</key> <dict>
+	<!--======== calibration_offset ========-->
+	<!--These values indicate the offset from user specified zero point to the
+	physical system's zero point.  Applied before calibration_scale when
+	converting from user's desired position to command to send to hardware. -->
+	<key>Model:ERS-7:calibration_offset</key> <dict>
+		<key>LFr:rotor</key> <real>0</real>
+		<key>LFr:elvtr</key> <real>0</real>
+		<key>LFr:knee</key> <real>0</real>
+		<!-- ... -->
+	</dict>
+	<!--======== calibration_scale ========-->
+	<!--Multiplier from desired position to command for each PID joint, applied after calibration_offset. -->
+	<key>Model:ERS-7:calibration_scale</key> <dict>
+		<key>LFr:rotor</key> <real>1</real>
+		<key>LFr:elvtr</key> <real>1</real>
+		<key>LFr:knee</key> <real>1</real>
+		<!-- ... -->
+	</dict>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10003</integer>
+	
+	<!--estop_off_snd: sound file to use when e-stop turned off-->
+	<key>estop_off_snd</key> <string>yap.wav</string>
+	
+	<!--estop_on_snd: sound file to use when e-stop turned on-->
+	<key>estop_on_snd</key> <string>skid.wav</string>
+	
+	<!--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-->
+	<key>inf_walk_accel</key> <false/>
+	
+    <key>Model:ERS-7</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers7.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Mouth</string>
+            <string>NearIR</string>
+            <string>FarIR</string>
+            <string>ChestIR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:ERS-210</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers210.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Mouth</string>
+            <string>IR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:ERS-220</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers220.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>IR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+	<key>Model:QBotPlus</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/QBotPlus.kin</string>
+
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:Regis1</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/Regis1.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Arm</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+	
+	<!--max_head_pan_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_pan_speed</key> <real>5.7814</real>
+	
+	<!--max_head_roll_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_roll_speed</key> <real>5.7814</real>
+	
+	<!--max_head_tilt_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_tilt_speed</key> <real>3.18523</real>
+	
+	<!--root: path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
+	Any motion related paths which are not absolute (i.e. do not start with '/')
+	will be assumed to be relative to this directory -->
+	<key>root</key> <string>data/motion</string>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10004</integer>
+	
+	<!--the walk parameter file to load by default for new WalkMC's-->
+	<key>walk</key> <string>walk.prm</string>
+</dict>
+
+<!--======== sound ========-->
+<key>sound</key> <dict>
+	<!--pitchConfidenceThreshold: confidence threshold required to generate a pitch event [0-1]-->
+	<key>pitchConfidenceThreshold</key> <real>0.6</real>
+	
+	<!--======== preload ========-->
+	<!--list of sounds to preload at boot-->
+	<key>preload</key> <array>
+		<string>skid.wav</string>
+		<string>yap.wav</string>
+	</array>
+	
+	<!--root: path to sound clips-->
+	<key>root</key> <string>data/sound</string>
+	
+	<!--sample_bits: sample bit depth, either 8 or 16-->
+	<key>sample_bits</key> <integer>16</integer>
+	
+	<!--sample_rate: sample rate to send to system, currently only 8000 or 16000 supported-->
+	<key>sample_rate</key> <integer>16000</integer>
+	
+	<!--======== streaming ========-->
+	<key>streaming</key> <dict>
+		<!--mic_port: port for streaming microphone samples-->
+		<key>mic_port</key> <integer>10070</integer>
+		
+		<!--mic_sample_bits: sample bit depth from the microphone (either 8 or 16)-->
+		<key>mic_sample_bits</key> <integer>16</integer>
+		
+		<!--mic_sample_rate: sample rate from the microphone-->
+		<key>mic_sample_rate</key> <integer>16000</integer>
+		
+		<!--mic_stereo: whether to stream stereo or mono from the microphone-->
+		<key>mic_stereo</key> <true/>
+		
+		<!--speaker_frame_length: length of frame sent to the speaker (ms)-->
+		<key>speaker_frame_length</key> <integer>64</integer>
+		
+		<!--speaker_max_delay: maximum delay (ms) during playback-->
+		<key>speaker_max_delay</key> <integer>1000</integer>
+		
+		<!--speaker_port: port for streaming speaker samples-->
+		<key>speaker_port</key> <integer>10071</integer>
+	</dict>
+	
+	<!--volume in decibels - the value is interpreted as a signed short, where
+	0x8000 is mute, 0xFFFF is full volume (low=0xE700, mid=0xEE00, high=0xF600)
+	If you directly set the decibel level, be warned sony recommends against going above 0xF600
+	However, I believe the commercial software on the ERS-7 runs at 0xFF00.
+	Going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
+	Value is one of: { mute | low | mid | high | <integer_value> } -->
+	<key>volume</key> <string>high</string>
+</dict>
+
+<!--======== vision ========-->
+<key>vision</key> <dict>
+	<key>Model:ERS-7</key> <dict>
+		<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+		Value is one of: { low | mid | high } -->
+		<key>gain</key> <string>mid</string>
+		
+		<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+		Value is one of: { slow | mid | fast } -->
+		<key>shutter_speed</key> <string>slow</string>
+		
+		<!--white_balance: white balance shifts color spectrum in the image
+		Value is one of: { indoor | outdoor | fluorescent } -->
+		<key>white_balance</key> <string>indoor</string>
+		
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	<key>Model:ERS-2*</key> <dict>
+		<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+		Value is one of: { low | mid | high } -->
+		<key>gain</key> <string>mid</string>
+		
+		<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+		Value is one of: { slow | mid | fast } -->
+		<key>shutter_speed</key> <string>mid</string>
+		
+		<!--white_balance: white balance shifts color spectrum in the image
+		Value is one of: { indoor | outdoor | fluorescent } -->
+		<key>white_balance</key> <string>fluorescent</string>
+		
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+		<!--<string>210pb.tm</string>  just pink and blue -->
+			<string>config/210phb.tm</string> <!-- pink, skin (hand), and blue -->
+			<!--   note: "skin" is just of people who work in our lab - not a general sampling... :( -->
+			<string>config/210genrl.tm</string> <!-- general colors for the ERS-210 -->
+			<string>config/ball.tm</string> <!-- standard Sony pink ball definition -->
+		</array>
+	</dict>
+	<key>Model:Regis1</key> <dict>
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	
+	<key>Model:QBotPlus</key> <dict>
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	
+	<!--The colors definition (.col) file gives names and a "typical" color for display.
+	The indexes numbers it contains correspond to indexes in the .tm file
+	This file is common to all .tm files; when doing new color segmentations,
+	make sure you define colors in the same order as listed here! -->
+	<key>colors</key> <string>config/default.col</string>
+	
+	<!--jpeg_dct_method: pick between dct methods for jpeg compression
+	Value is one of: { islow | ifast | float } -->
+	<key>jpeg_dct_method</key> <string>ifast</string>
+	
+	<!--region_calc_total: When true, this will fill in the CMVision::color_class_state::total_area
+	field for each color following region labeling.  If false, the total_area
+	will stay 0 (or whatever the last value was), but you save a little CPU. -->
+	<key>region_calc_total</key> <true/>
+	
+	<!--the resolution that object recognition system will run at.
+	This counts down from the maximum resolution layer, so higher numbers mean lower resolution. -->
+	<key>resolution</key> <integer>1</integer>
+	
+	<!--restore_image: Apparently someone at Sony thought it would be a good idea to replace some
+	pixels in each camera image with information like the frame number and CDT count.
+	If non-zero, will replace those pixels with the actual image pixel value in RawCamGenerator -->
+	<key>restore_image</key> <true/>
+	
+	<!--======== rawcam ========-->
+	<key>rawcam</key> <dict>
+		<!--channel: if encoding is single channel, this indicates the channel to send-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--compress_quality: 0-100, compression quality (currently only used by jpeg)-->
+		<key>compress_quality</key> <integer>85</integer>
+		
+		<!--compression: the type of compression to apply the image
+		Value is one of: { none | jpeg } -->
+		<key>compression</key> <string>jpeg</string>
+		
+		<!--encoding: holds whether to send color or single channel
+		Value is one of: { color | grayscale } -->
+		<key>encoding</key> <string>color</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10011</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+		
+		<!--uv_skip: resolution level to transmit uv channel at when using 'color' encoding mode
+		"skip" is the log_2 of number of pixels to increment, 0 sends reconstructed double
+		resolution (mainly useful for Y channel, others are just resampled).
+		Our eyes are more sensitive to intensity (y channel) so you might
+		want to send the UV channels at a lower resolution (higher skip) as
+		a form of compression.
+		Valid values on the Aibo are 0-5-->
+		<key>uv_skip</key> <integer>3</integer>
+		
+		<!--y_skip: resolution level to transmit y channel
+		Also used as the resolution level when in single-channel encoding mode -->
+		<key>y_skip</key> <integer>2</integer>
+	</dict>
+	
+	<!--======== regioncam ========-->
+	<key>regioncam</key> <dict>
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10013</integer>
+		
+		<!--skip: resolution level to extract regions from-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--======== segcam ========-->
+	<key>segcam</key> <dict>
+		<!--channel of RLEGenerator to send (i.e. which threshold map to use-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--what compression to use on the segmented imageValue is one of: { none | rle } -->
+		<key>compression</key> <string>rle</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10012</integer>
+		
+		<!--skip: resolution level to transmit segmented images at-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+	</dict>
+	
+	<!--======== calibration ========-->
+	<!--Lens distortion correction parameters
+	Computated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet-->
+	<key>Model:ERS-7:calibration</key> <dict>
+		<!--calibration_res_x: x resolution of images used during calibration-->
+		<key>calibration_res_x</key> <integer>208</integer>
+		
+		<!--calibration_res_y: y resolution of images used during calibration-->
+		<key>calibration_res_y</key> <integer>160</integer>
+		
+		<!--focal_len_x: focal length of camera, in pixels, K11-->
+		<key>focal_len_x</key> <real>198.807</real>
+		
+		<!--focal_len_y: focal length of camera, in pixels, K22-->
+		<key>focal_len_y</key> <real>200.333</real>
+		
+		<!--kc1_r2: r-squared radial distortion-->
+		<key>kc1_r2</key> <real>-0.147005</real>
+		
+		<!--kc2_r4: r to the 4 radial distortion-->
+		<key>kc2_r4</key> <real>0.38485</real>
+		
+		<!--kc3_tan1: first tangential correction term-->
+		<key>kc3_tan1</key> <real>-0.00347777</real>
+		
+		<!--kc4_tan2: second tangential correctiont term-->
+		<key>kc4_tan2</key> <real>0.00012873</real>
+		
+		<!--kc5_r6: r to the 6 radial distortion-->
+		<key>kc5_r6</key> <real>0</real>
+		
+		<!--principle_point_x: center of optical projection, K13-->
+		<key>principle_point_x</key> <real>102.689</real>
+		
+		<!--principle_point_y: center of optical projection, K23-->
+		<key>principle_point_y</key> <real>85.0399</real>
+		
+		<!--CCD skew, K12 = skew*focal_len_x-->
+		<key>skew</key> <real>0</real>
+	</dict>
+</dict>
+
+<!--======== wireless ========-->
+<key>wireless</key> <dict>
+	<!--id number (in case you have more than one AIBO)-->
+	<key>id</key> <integer>1</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/project/ms/data/motion/walk.pos ./project/ms/data/motion/walk.pos
--- ../Tekkotsu_3.0/project/ms/data/motion/walk.pos	1969-12-31 19:00:00.000000000 -0500
+++ ./project/ms/data/motion/walk.pos	2007-11-22 00:31:00.000000000 -0500
@@ -0,0 +1,14 @@
+#POS
+LFr:rotor	-0.1592	 1.0000
+LFr:elvtr	 0.2164	 1.0000
+LFr:knee~	 1.7743	 1.0000
+RFr:rotor	-0.2018	 1.0000
+RFr:elvtr	 0.2107	 1.0000
+RFr:knee~	 1.8018	 1.0000
+LBk:rotor	-0.7361	 1.0000
+LBk:elvtr	 0.0171	 1.0000
+LBk:knee~	 1.6175	 1.0000
+RBk:rotor	-0.7605	 1.0000
+RBk:elvtr	 0.0456	 1.0000
+RBk:knee~	 1.6580	 1.0000
+#END
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/Makefile ./tools/Makefile
--- ../Tekkotsu_3.0/tools/Makefile	2006-09-06 15:45:30.000000000 -0400
+++ ./tools/Makefile	2007-11-15 12:26:52.000000000 -0500
@@ -1,7 +1,8 @@
 
 COMPONENTS:=filtersyswarn binstrswap mon mipaltools easytrain
+SUBMAKE_TGTS:=$(shell find . test -mindepth 2 -maxdepth 2 -name Makefile)
 
-.PHONY: all clean releaseCheck $(COMPONENTS)
+.PHONY: all clean releaseCheck $(COMPONENTS) $(SUBMAKE_TGTS)
 
 TOOLS_BUILT_FLAG?=.toolsBuilt
 
@@ -17,19 +18,20 @@
 	@printf "Making tool $@: "
 	@$(MAKE) -C "$@" $(MAKECMDGOALS)
 
-releaseCheck:
-	@for dir in $(dir $(shell find * test/* -maxdepth 1 -name Makefile)) ; do \
-		printf "Checking tool $$dir:\n"; \
-		$(MAKE) -C "$$dir" clean; \
-		if [ $$? -ne 0 ] ; then \
-			exit 1; \
-		fi; \
-		$(MAKE) -C "$$dir"; \
-		if [ $$? -ne 0 ] ; then \
-			exit 1; \
-		fi; \
-		$(MAKE) -C "$$dir" test; \
-		if [ $$? -ne 0 ] ; then \
-			exit 1; \
-		fi; \
-	done
+releaseCheck: $(SUBMAKE_TGTS)
+
+$(SUBMAKE_TGTS):
+	@dir=$(dir $@); \
+	printf "Checking tool $$dir:\n"; \
+	$(MAKE) -C "$$dir" clean; \
+	if [ $$? -ne 0 ] ; then \
+		exit 1; \
+	fi; \
+	$(MAKE) -C "$$dir"; \
+	if [ $$? -ne 0 ] ; then \
+		exit 1; \
+	fi; \
+	$(MAKE) -C "$$dir" test; \
+	if [ $$? -ne 0 ] ; then \
+		exit 1; \
+	fi; \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/buildRelease ./tools/buildRelease
--- ../Tekkotsu_3.0/tools/buildRelease	2006-09-29 06:54:48.000000000 -0400
+++ ./tools/buildRelease	2007-11-15 12:32:11.000000000 -0500
@@ -4,7 +4,17 @@
 
 tmp="/tmp";
 if [ -z "$MEMSTICK_ROOT" ] ; then
-	MEMSTICK_ROOT=/mnt/memstick
+	if [ `uname` = "Darwin" ] ; then
+		if [ -z "$TEKKOTSU_ROOT" ] ; then
+			MEMSTICK_ROOT=`/usr/local/Tekkotsu/tools/osx_find_memstick`
+		else
+			MEMSTICK_ROOT=`$TEKKOTSU_ROOT/tools/osx_find_memstick`
+		fi;
+	else
+		MEMSTICK_ROOT=/mnt/memstick
+	fi
+else
+	ORIG_MEMSTICK_ROOT=$MEMSTICK_ROOT
 fi;
 
 if [ $# -lt 2 ] ; then
@@ -44,13 +54,13 @@
 
 if [ `grep PROJECT_NUMBER docs/doxygencfg | grep -c "$1"` -eq 0 ] ; then
 	echo "Version mismatch with docs/doxygencfg - you forgot to update PROJECT_NUMBER";
-	exit 1;
+	read -p "Press return to ignore... (^C to stop)"
 fi;
 
 for x in project/SampleMC.h project/SampleBehavior.h ; do
 	if [ -f "$x" ] ; then
 		echo "You forgot to untag the sample files"
-		exit 1;
+		read -p "Press return to ignore... (^C to stop)"
 	fi;
 done;
 for x in ERS210A ERS7 ; do
@@ -98,7 +108,7 @@
 
 export TEKKOTSU_ROOT=..
 
-for x in TGT_ERS210 TGT_ERS220 TGT_ERS2xx; do
+for x in TGT_QBOTPLUS TGT_QWERK TGT_LYNXARM6 TGT_REGIS1 TGT_CREATE TGT_ERS210 TGT_ERS220 TGT_ERS2xx; do
 	export TEKKOTSU_TARGET_MODEL=$x;
 	printf "\n\nTesting $x build\n\n\n";
 	cd ${tmp}/Tekkotsu_$1;
@@ -108,7 +118,7 @@
 		exit 1;
 	fi;
 	cd ${tmp}/Tekkotsu_$1/tools;
-	${MAKE} releaseCheck
+	${MAKE} -j2 releaseCheck
 	if [ $? -ne 0 ] ; then
 		echo "Framework tools failed for $x"
 		exit 1;
@@ -119,7 +129,7 @@
 		echo "Project Build failed for $x"
 		exit 1;
 	fi;
-	${MAKE} -j2 sim;
+	${MAKE} -j2 tekkotsu;
 	if [ $? -ne 0 ] ; then
 		echo "sim build failed for $x"
 		exit 1;
@@ -129,8 +139,19 @@
 echo "Enter memstick to be built onto for ERS-2xx - this memstick will be erased";
 read -p "Press return when ready... (^C to stop)"
 
+if [ -z "$MEMSTICK_ROOT" ] ; then
+	if [ `uname` = "Darwin" ] ; then
+		if [ -z "$TEKKOTSU_ROOT" ] ; then
+			MEMSTICK_ROOT=`/usr/local/Tekkotsu/tools/osx_find_memstick`
+		else
+			MEMSTICK_ROOT=`$TEKKOTSU_ROOT/osx_find_memstick`
+		fi;
+	else
+		MEMSTICK_ROOT=/mnt/memstick
+	fi
+fi;
 $TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
-rm -rf /mnt/memstick/*;
+rm -rf $MEMSTICK_ROOT*;
 ${MAKE} update;
 if [ $? -ne 0 ] ; then
 	echo "Project build failed"
@@ -166,7 +187,7 @@
 		exit 1;
 	fi;
 	cd ${tmp}/Tekkotsu_$1/tools;
-	${MAKE} releaseCheck
+	${MAKE} -j2 releaseCheck
 	if [ $? -ne 0 ] ; then
 		echo "Framework tools failed for $x"
 		exit 1;
@@ -177,7 +198,7 @@
 		echo "Project Build failed for $x"
 		exit 1;
 	fi;
-	${MAKE} -j2 sim;
+	${MAKE} -j2 tekkotsu;
 	if [ $? -ne 0 ] ; then
 		echo "sim build failed for $x"
 		exit 1;
@@ -187,8 +208,16 @@
 echo "Enter memstick to be built onto for ERS-7 - this memstick will be erased";
 read -p "Press return when ready... (^C to stop)"
 
+#reset memstick root if using darwin; (memstick name might change if using different stick)
+if [ `uname` = "Darwin" -a -z "$ORIG_MEMSTICK_ROOT" ] ; then
+	if [ -z "$TEKKOTSU_ROOT" ] ; then
+		MEMSTICK_ROOT=`/usr/local/Tekkotsu/tools/osx_find_memstick`
+	else
+		MEMSTICK_ROOT=`$TEKKOTSU_ROOT/osx_find_memstick`
+	fi;
+fi
 $TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
-rm -rf /mnt/memstick/*;
+rm -rf $MEMSTICK_ROOT/*;
 ${MAKE} update;
 if [ $? -ne 0 ] ; then
 	echo "Project build failed"
@@ -197,7 +226,7 @@
 
 $TEKKOTSU_ROOT/tools/mntmem $MEMSTICK_ROOT;
 rm -rf ${tmp}/Tekkotsu_memstick_ERS7_$1;
-cp -arp /mnt/memstick ${tmp}/Tekkotsu_memstick_ERS7_$1;
+cp -rp $MEMSTICK_ROOT ${tmp}/Tekkotsu_memstick_ERS7_$1;
 $TEKKOTSU_ROOT/tools/umntmem $MEMSTICK_ROOT;
 chmod a+rx ${tmp}/Tekkotsu_memstick_ERS7_$1
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/convertmot/Makefile ./tools/convertmot/Makefile
--- ../Tekkotsu_3.0/tools/convertmot/Makefile	2006-03-28 12:08:23.000000000 -0500
+++ ./tools/convertmot/Makefile	2007-11-15 20:03:34.000000000 -0500
@@ -15,14 +15,17 @@
 SRCSUFFIX:=.cc
 PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
 
-# Use the containing framework, regardless of TEKKOTSU_ROOT setting (no '?=')
-TEKKOTSU_ROOT=../..
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo failure),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -32,7 +35,8 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
@@ -41,12 +45,16 @@
          -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -76,7 +84,7 @@
 clean:
 	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
 
-test: $(BIN)
+test: ./$(BIN)
 	@for x in * ; do \
 		if [ -r "ideal-$$x" ] ; then \
 			if diff -u "ideal-$$x" "$$x" ; then \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/convertmot/convertmot.cc ./tools/convertmot/convertmot.cc
--- ../Tekkotsu_3.0/tools/convertmot/convertmot.cc	2006-09-09 00:33:07.000000000 -0400
+++ ./tools/convertmot/convertmot.cc	2007-01-30 17:56:24.000000000 -0500
@@ -116,7 +116,14 @@
 int main(unsigned int argc, const char** argv) {
 	if(argc<3)
 		return usage(argc,argv);
-	config=new Config("tekkotsu.cfg");
+	::config = new Config();
+	::config->setFileSystemRoot("");
+	if(::config->loadFile("tekkotsu.xml")==0) {
+		if(::config->loadFile("tekkotsu.cfg")==0)
+			std::cerr << std::endl << " *** ERROR: Could not load configuration file tekkotsu.xml *** " << std::endl << std::endl;
+		else
+			std::cerr << "Successfully imported settings from old-format tekkotsu.cfg" << std::endl;
+	}
 	unsigned int used=1;
 	bool isRad=true;
 	while(used<argc) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/filtersyswarn/filtersyswarn.cc ./tools/filtersyswarn/filtersyswarn.cc
--- ../Tekkotsu_3.0/tools/filtersyswarn/filtersyswarn.cc	2006-02-05 19:11:04.000000000 -0500
+++ ./tools/filtersyswarn/filtersyswarn.cc	2007-10-26 14:07:37.000000000 -0400
@@ -33,8 +33,8 @@
 	regcomp(&instbegin,instbeginstr.c_str(),REG_EXTENDED|REG_NOSUB);
 	regcomp(&inststat,inststatstr.c_str(),REG_EXTENDED|REG_NOSUB);
 	string pliststr_no_vdtor=".*/plist[a-zA-Z]*\\.h:[0-9]*: warning: base ";
-	string dualcoding_no_vdtor=".*DualCoding/ShapeFuns\\.h:[0-9]*: warning: base ";
-	regcomp(&ignorebegin,(OPENR+".*: warning: |"+pliststr_no_vdtor+"|"+dualcoding_no_vdtor).c_str(),REG_EXTENDED|REG_NOSUB);
+	string dualcoding_no_vdtor=".*DualCoding/(PolygonData\\.cc|ShapeFuns\\.h):[0-9]*: warning: base ";
+	regcomp(&ignorebegin,(OPENR+".*: warning: |"+pliststr_no_vdtor+"|"+dualcoding_no_vdtor+"|.*local/terk/(TeRKPeerCommon|peer/MRPLPeer|SerialIO).h:.*: warning:").c_str(),REG_EXTENDED|REG_NOSUB);
 	regcomp(&warnstat,"^   ",REG_EXTENDED|REG_NOSUB);
 
 	string file, instant;
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/installXCodeTemplates ./tools/installXCodeTemplates
--- ../Tekkotsu_3.0/tools/installXCodeTemplates	2005-10-25 23:56:09.000000000 -0400
+++ ./tools/installXCodeTemplates	2007-11-07 00:27:21.000000000 -0500
@@ -3,7 +3,12 @@
 # installXCodeTemplates
 # Created by Ethan Tira-Thompson on 3/8/05.
 
-DEFAULT="/Library/Application Support/Apple/Developer Tools/File Templates/Tekkotsu"
+VER=`uname -r | cut -f 1 -d .`;
+if [ $VER -lt 9 ] ; then
+	DEFAULT="/Library/Application Support/Apple/Developer Tools/File Templates/Tekkotsu"
+else
+	DEFAULT="/Library/Application Support/Developer/Shared/Xcode/File Templates/Tekkotsu"
+fi
 ORIGDIR="`pwd`";
 cd "`dirname \"$0\"`/../project/templates";
 SOURCE="`pwd`"
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/ControllerGUI ./tools/mon/ControllerGUI
--- ../Tekkotsu_3.0/tools/mon/ControllerGUI	2005-06-29 17:59:24.000000000 -0400
+++ ./tools/mon/ControllerGUI	2007-08-27 18:17:54.000000000 -0400
@@ -15,4 +15,9 @@
 	exit 1;
 fi;
 
-java -Xmx256M org.tekkotsu.mon.ControllerGUI $* &
+if [ "`uname`" = "Darwin" ] ; then
+	JAVAFLAGS="${JAVAFLAGS} -Xdock:name=ControllerGUI -Xdock:icon=images/ControllerIcon.png"
+fi
+
+java ${JAVAFLAGS} -Xmx256M org.tekkotsu.mon.ControllerGUI $* &
+
Binary files ../Tekkotsu_3.0/tools/mon/images/ControllerIcon.png and ./tools/mon/images/ControllerIcon.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/ControllerGUI.java ./tools/mon/org/tekkotsu/mon/ControllerGUI.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/ControllerGUI.java	2006-09-20 16:22:17.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/ControllerGUI.java	2007-08-29 14:10:54.000000000 -0400
@@ -1,6 +1,7 @@
 package org.tekkotsu.mon;
 
 import java.awt.*;
+import java.awt.font.*;
 import java.awt.event.*;
 import javax.swing.*;
 import javax.swing.event.*;
@@ -9,15 +10,30 @@
 import java.util.prefs.Preferences;
 import java.io.PrintWriter;
 import java.io.FileWriter;
+import javax.swing.*;
+import javax.swing.plaf.*;
+import javax.swing.plaf.basic.BasicToolTipUI;
+import javax.swing.text.*;
 
 //Admittedly a little sloppy, but I don't want to spend forever on this...
 
 public class ControllerGUI extends JFrame implements ActionListener, KeyListener, EStopListener.UpdatedListener {
+	public class MyMenu extends JList {
+		public MyMenu() { super(); }
+		// use custom tooltip to support multiple lines
+		public JToolTip createToolTip() { return new JMultiLineToolTip(); }
+	}
+	
 	org.tekkotsu.sketch.SketchGUI cameraSkGUI=null, localSkGUI=null, worldSkGUI=null;
-	JList menu;
+	MyMenu menu;
 	JScrollPane menuScroll;
 	JComboBox title;
-	JLabel status;
+	public class MyLabel extends JLabel {
+		public MyLabel(String s) { super(s); }
+		// use custom tooltip to support multiple lines
+		public JToolTip createToolTip() { return new JMultiLineToolTip(); }
+	}
+	MyLabel status;
 	JList scripts;
 	ControllerListener comm;
 	EStopListener estopComm;
@@ -68,7 +84,7 @@
 	final static ImageIcon rarrow = new ImageIcon("images/rarrow.gif");
 	final static ImageIcon larrow = new ImageIcon("images/larrow.gif");
 	final static ImageIcon carrows = new ImageIcon("images/chasingarrows.gif");
-
+		
 	public class MyCellRenderer implements ListCellRenderer {
 		public Component getListCellRendererComponent(JList list,Object value,int index,boolean isSelected,boolean cellHasFocus) {
 			ControllerListener.MenuEntry me=(ControllerListener.MenuEntry)value;
@@ -102,8 +118,8 @@
 				title.setBorder(BorderFactory.createLineBorder(Color.GRAY,1));
 			else
 				title.setBorder(BorderFactory.createEmptyBorder(1,1,1,1));
+			JComponent tmp=Box.createHorizontalBox();
 			if(me.hasSubmenu) {
-				Box tmp=Box.createHorizontalBox();
 				tmp.add(title);
 				//				tmp.add(Box.createHorizontalGlue());
 				JLabel arr=new JLabel(rarrow);
@@ -113,7 +129,6 @@
 					tmp.setToolTipText(me.description);
 				return tmp;
 			} else {
-				Box tmp=Box.createHorizontalBox();
 				tmp.add(title);
 				tmp.add(Box.createHorizontalStrut(rarrow.getIconWidth()));
 				if(me.description.length()!=0)
@@ -214,7 +229,7 @@
 						}
 					}
 					//Set focus to the main menu
-					menu.requestFocus();
+					//menu.requestFocus();
 				}
 				for(int i=0; i<scriptsModel.getSize(); i++)
 					if(scriptsModel.get(i).toString().equals("CONNECT"))
@@ -470,7 +485,7 @@
 		getContentPane().add(Box.createVerticalStrut(spacer_size),BorderLayout.NORTH);
 		getContentPane().add(Box.createVerticalStrut(spacer_size),BorderLayout.SOUTH);
 		
-		menu=new JList();
+		menu=new MyMenu();
 		menu.setCellRenderer(new MyCellRenderer());
 		menu.setFixedCellWidth(165);
 		menu.addMouseListener(new JListDoubleClick(this)); 
@@ -529,7 +544,7 @@
 				tmp2.add(Box.createHorizontalStrut(spacer_size));
 				tmp.add(tmp2,BorderLayout.WEST);
 			}
-			status=new JLabel("Connecting...");
+			status=new MyLabel("Connecting...");
 			tmp.add(status,BorderLayout.CENTER);
 			{
 				Box tmp2=Box.createHorizontalBox();
@@ -679,8 +694,8 @@
 				scriptsModel.addElement(new ScriptEntry(prefs.get("ControllerGUI.script"+i+".title","unknown"),prefs.get("ControllerGUI.script"+i+".cmd","")));
 		} else {
 			//uninitialized, supply some default scripts
-			scriptsModel.addElement(new ScriptEntry("Quality Video","!set vision.rawcam_transport=tcp\n!set vision.rawcam_compression=none\n!set vision.rawcam_y_skip=1\n!set vision.rawcam_uv_skip=1\n!set vision.rawcam_interval=1500"));
-			scriptsModel.addElement(new ScriptEntry("Smooth Video","!set vision.rawcam_y_skip=2\n!set vision.rawcam_uv_skip=3\n!set vision.rawcam_interval=0\n!set vision.rawcam_compression=jpeg\n!set vision.rawcam_transport=udp"));
+			scriptsModel.addElement(new ScriptEntry("Quality Video","!set vision.rawcam.transport=tcp\n!set vision.rawcam.compression=none\n!set vision.rawcam.y_skip=1\n!set vision.rawcam.uv_skip=1\n!set vision.rawcam.interval=1500"));
+			scriptsModel.addElement(new ScriptEntry("Smooth Video","!set vision.rawcam.y_skip=2\n!set vision.rawcam.uv_skip=3\n!set vision.rawcam.interval=0\n!set vision.rawcam.compression=jpeg\n!set vision.rawcam.transport=udp"));
 			scriptsModel.addElement(new ScriptEntry("Head Remote Control","!root \"TekkotsuMon\" \"Head Remote Control\""));
 			scriptsModel.addElement(new ScriptEntry("Walk Remote Control","!root \"TekkotsuMon\" \"Walk Remote Control\""));
 		}
@@ -782,3 +797,116 @@
   public void keyTyped(KeyEvent e) { }
 }
 
+//multi line tooltips from Zafir Anjum http://www.codeguru.com/java/articles/122.shtml
+class JMultiLineToolTip extends JToolTip {
+	private static final String uiClassID = "ToolTipUI";
+	
+	String tipText;
+	JComponent component;
+	
+	public JMultiLineToolTip() { updateUI(); }
+	public void updateUI() { setUI(MultiLineToolTipUI.createUI(this)); }
+	
+	public int getColumns() { return columns; }
+	public void setColumns(int columns) {
+		this.columns = columns;
+		this.fixedwidth = 0;
+	}
+	
+	public int getFixedWidth() { return fixedwidth; }
+	public void setFixedWidth(int width) {
+		this.fixedwidth = width;
+		this.columns = 0;
+	}
+	
+	protected int columns = 0;
+	protected int fixedwidth = 0;
+}
+
+class MultiLineToolTipUI extends BasicToolTipUI {
+	static MultiLineToolTipUI sharedInstance = new MultiLineToolTipUI();
+	Font smallFont; 			     
+	JToolTip tip;
+	protected CellRendererPane rendererPane;
+	private JTextArea textArea ;
+	
+	public static ComponentUI createUI(JComponent c) {
+		return sharedInstance;
+	}
+	
+	public MultiLineToolTipUI() {
+		super();
+		textArea = new JTextArea();
+		smallFont = new Font("sanserif",0,11);
+	}
+	
+	public void installUI(JComponent c) {
+		super.installUI(c);
+		tip = (JToolTip)c;
+		rendererPane = new CellRendererPane();
+		c.add(rendererPane);
+	}
+	
+	public void uninstallUI(JComponent c) {
+		super.uninstallUI(c);
+		c.remove(rendererPane);
+		rendererPane = null;
+	}
+	
+	public void paint(Graphics g, JComponent c) {
+		String tipText = ((JToolTip)c).getTipText();
+		textArea.setText(tipText );
+		textArea.setFont(smallFont);
+		textArea.setMargin(new Insets(4,6,4,6));
+		Dimension size = c.getSize();
+		textArea.setBackground(c.getBackground());
+		rendererPane.paintComponent(g, textArea, c, 1, 1, size.width - 1, size.height - 1, true);
+	}
+	
+	public Dimension getPreferredSize(JComponent c) {
+		String tipText = ((JToolTip)c).getTipText();
+		if (tipText == null)
+			return new Dimension(0,0);
+		textArea.setText(tipText );
+		textArea.setFont(smallFont);
+		textArea.setMargin(new Insets(4,6,4,6));
+		rendererPane.removeAll();
+		rendererPane.add(textArea );
+		textArea.setWrapStyleWord(true);
+		int width = ((JMultiLineToolTip)c).getFixedWidth();
+		int columns = ((JMultiLineToolTip)c).getColumns();
+		
+		if( columns > 0 )
+		{
+			textArea.setColumns(columns);
+			textArea.setSize(0,0);
+			textArea.setLineWrap(true);
+			textArea.setSize( textArea.getPreferredSize() );
+		}
+		else if( width > 0 )
+		{
+			textArea.setLineWrap(true);
+			Dimension d = textArea.getPreferredSize();
+			d.width = width;
+			d.height++;
+			textArea.setSize(d);
+		}
+		else
+			textArea.setLineWrap(false);
+		
+		Dimension dim = textArea.getPreferredSize();
+		
+		dim.height += 1;
+		dim.width += 1;
+		return dim;
+	}
+	
+	public Dimension getMinimumSize(JComponent c) {
+		return getPreferredSize(c);
+	}
+	
+	public Dimension getMaximumSize(JComponent c) {
+		return getPreferredSize(c);
+	}
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/ControllerListener.java ./tools/mon/org/tekkotsu/mon/ControllerListener.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/ControllerListener.java	2006-08-08 16:12:54.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/ControllerListener.java	2007-11-21 16:58:12.000000000 -0500
@@ -170,14 +170,22 @@
 								break;
 							}
 							int sel=Integer.parseInt(readLine(sin));
-							if(x==-1) {
+							if(sel==-1) {
 								_isConnected=false;
 								break;
 							}
 							last=readLine(sin);
 							if(!_isConnected) break;
+							int descript_nlines = Integer.parseInt(readLine(sin));
+							if(descript_nlines==-1)
+								_isConnected=false;
+							if(!_isConnected) break;
 							String descript=readLine(sin);
 							if(!_isConnected) break;
+							for(; descript_nlines>0; descript_nlines--) {
+								descript+="\n"+readLine(sin);
+								if(!_isConnected) break;
+							}
 							menu.add(new MenuEntry((x>0),(sel>0),last,descript));
 						}
 						_status="";
@@ -212,8 +220,16 @@
 						_menus.add(new Vector());
 						_titles.clear();
 					} else if(msgtype.equals("status")) {
+						int nlines = Integer.parseInt(readLine(sin));
+						if(nlines==-1)
+							_isConnected=false;
+						if(!_isConnected) break;
 						_status=readLine(sin);
 						if(!_isConnected) break;
+						for(; nlines>0; nlines--) {
+							_status+="\n"+readLine(sin);
+							if(!_isConnected) break;
+						}
 					} else if(msgtype.equals("load")) {
 						String type=readLine(sin);
 						if(!_isConnected) break;
@@ -243,26 +259,28 @@
 							consArgClasses[1]=Integer.TYPE;
 							Constructor objCons=objClass.getConstructor(consArgClasses);
 							Object obj=objCons.newInstance(consArgs);
-							dynObjs.put(name,obj);
-							dynObjPorts.put(name, new Integer(port));
-							if(dynObjSrcs.get(name)==null) { //check the GUI didn't already assign a src (for VisionGUI)
-								//find out who launched this (not infallable - dynamic controls launching windows may not have stable launch points...)
-								int minsel=-1;
-								if(_menus.size()>1) {
-									Vector menuitems=(Vector)_menus.get(_menus.size()-2);
-									for(int i=0; i<menuitems.size(); i++)
-										if(((ControllerListener.MenuEntry)menuitems.get(i)).selected) {
-											minsel=i;
-											break;
-										}
-											String title=((ControllerListener.MenuEntry)((Vector)_menus.get(_menus.size()-2)).get(minsel)).title;
-									Vector path=buildSelectionPath();
-									String cmd=new String();
-									for(int i=1; i<path.size()-1; i++)
-										cmd=cmd+"\""+path.get(i)+"\" ";
-									cmd=cmd+"\""+title+"\"";
-									System.out.println("Launched by: "+cmd);
-									dynObjSrcs.put(name,cmd);
+							if(port!=0 && name.length()>0) {
+								dynObjs.put(name,obj);
+								dynObjPorts.put(name, new Integer(port));
+								if(dynObjSrcs.get(name)==null) { //check the GUI didn't already assign a src (for VisionGUI)
+									//find out who launched this (not infallable - dynamic controls launching windows may not have stable launch points...)
+									int minsel=-1;
+									if(_menus.size()>1) {
+										Vector menuitems=(Vector)_menus.get(_menus.size()-2);
+										for(int i=0; i<menuitems.size(); i++)
+											if(((ControllerListener.MenuEntry)menuitems.get(i)).selected) {
+												minsel=i;
+												break;
+											}
+												String title=((ControllerListener.MenuEntry)((Vector)_menus.get(_menus.size()-2)).get(minsel)).title;
+										Vector path=buildSelectionPath();
+										String cmd=new String();
+										for(int i=1; i<path.size()-1; i++)
+											cmd=cmd+"\""+path.get(i)+"\" ";
+										cmd=cmd+"\""+title+"\"";
+										System.out.println("Launched by: "+cmd);
+										dynObjSrcs.put(name,cmd);
+									}
 								}
 							}
 						}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/RoverGUI.java ./tools/mon/org/tekkotsu/mon/RoverGUI.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/RoverGUI.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/RoverGUI.java	2007-07-21 20:24:35.000000000 -0400
@@ -0,0 +1,392 @@
+package org.tekkotsu.mon;
+
+import javax.swing.*;
+import java.awt.*;
+import java.awt.geom.*;
+import java.awt.event.*;
+import javax.swing.event.*;
+import java.util.prefs.Preferences;
+
+public class RoverGUI extends JFrame implements PointPick.PointPickedListener, ChangeListener, ActionListener, MouseListener, RoverListener.RoverUpdatedListener {
+	static int defPort=10056;
+	
+	PointPick gripper;
+	PointPick camera;
+	
+	JSlider gripperSlider;
+	JSlider gripperAngleSlider;
+	JSlider perspectiveSlider;
+	JSlider gripperHeightSlider;
+	JSlider cameraDistanceSlider;
+	
+	JButton flattenButton;
+	JCheckBox autoPerspectiveCheckBox;
+	JCheckBox autoAngleCheckBox;
+	JCheckBox autoTrackCheckBox;
+	JCheckBox maxDistCheckBox;
+	
+	
+
+	JLabel status;
+	JButton reconnectBut;
+	
+	RoverListener comm;
+	static int slidermax=1000;
+	final static ImageIcon carrows = new ImageIcon("images/chasingarrows.png");
+	static Preferences prefs = Preferences.userNodeForPackage(RoverGUI.class);
+
+	static public void main(String s[]) {
+		int port=defPort;
+		if(s.length<1)
+			usage();
+		if(s.length>1)
+			port=Integer.parseInt(s[1]);
+		String[] args=new String[s.length-1];
+		for(int i=0; i<s.length-1; i++)
+			args[i-1]=s[i];
+		JFrame frame=new RoverGUI(s[0],port,args);
+		/*		frame.addWindowListener(new WindowAdapter() {
+			public void windowClosing(WindowEvent e) { System.exit(0); }
+			});*/
+	}
+	
+	public static void usage() {
+		System.out.println("Usage: java RoverGUI host [port]");
+		System.out.println("       if port is not specified, it defaults to: "+defPort);
+		System.exit(2);
+	}
+		
+	public RoverGUI(String host, int port, String args[]) {
+		super("TekkotsuMon: Rover Manipulator Control");
+		pack();
+		comm=new RoverListener(host,port);
+		RoverUpdated(comm);
+		comm.addRoverUpdatedListener(this);
+		int offx=getGraphicsConfiguration().getBounds().x;
+		int offy=getGraphicsConfiguration().getBounds().y;
+		setLocation(prefs.getInt("RoverGUI.location.x",50),prefs.getInt("RoverGUI.location.y",50));
+		setVisible(true);
+	}
+
+	public void close() {
+		prefs.putInt("RoverGUI.location.x",getLocation().x);
+		prefs.putInt("RoverGUI.location.y",getLocation().y);
+		//I think I had needed to add getInsets() to keep the window from moving when reopening it, but now it *causes* it to move... weird.  what changed?
+		//prefs.putInt("RoverGUI.location.x",getLocation().x+getInsets().left);
+		//prefs.putInt("RoverGUI.location.y",getLocation().y+getInsets().top);
+		comm.kill();
+		dispose();
+	}
+	
+	class CloseRoverAdapter extends WindowAdapter {
+		RoverGUI gui;
+		CloseRoverAdapter(RoverGUI gui) {this.gui=gui;}
+		public void windowClosing(WindowEvent e) {
+			gui.close();
+		}
+	}
+
+	public void RoverUpdated(RoverListener comm) {
+		if(status!=null) {
+			gripper.setEnabled(comm._isConnected);
+			camera.setEnabled(comm._isConnected && !autoTrackCheckBox.isSelected());
+			
+			gripperSlider.setEnabled(comm._isConnected);
+			gripperAngleSlider.setEnabled(comm._isConnected && !autoAngleCheckBox.isSelected());
+			perspectiveSlider.setEnabled(comm._isConnected && !autoPerspectiveCheckBox.isSelected());
+			gripperHeightSlider.setEnabled(comm._isConnected);
+			cameraDistanceSlider.setEnabled(comm._isConnected && !maxDistCheckBox.isSelected());
+			
+			flattenButton.setEnabled(comm._isConnected);
+			autoPerspectiveCheckBox.setEnabled(comm._isConnected);
+			autoAngleCheckBox.setEnabled(comm._isConnected);
+			autoTrackCheckBox.setEnabled(comm._isConnected);
+			maxDistCheckBox.setEnabled(comm._isConnected);
+			
+			if(comm._isConnected) {
+				comm.sendCommand("autoPerspective "+(autoPerspectiveCheckBox.isSelected()?1:0));
+				comm.sendCommand("autoAngle "+(autoAngleCheckBox.isSelected()?1:0));
+				comm.sendCommand("autoTrack "+(autoTrackCheckBox.isSelected()?1:0));
+				comm.sendCommand("maxDist "+(maxDistCheckBox.isSelected()?1:0));
+
+				comm.sendCommand("gripper "+gripperSlider.getValue()/(float)slidermax);
+				comm.sendCommand("gripperAngle "+gripperAngleSlider.getValue()/(float)slidermax*Math.PI);
+				comm.sendCommand("perspective "+perspectiveSlider.getValue()/(float)slidermax*Math.PI/2);
+				comm.sendCommand("gripperHeight "+gripperHeightSlider.getValue()/(float)slidermax);
+				comm.sendCommand("cameraDistance "+cameraDistanceSlider.getValue()/(float)slidermax);
+
+				Point2D.Float p=gripper.getPoint();
+				comm.sendCommand("tgt "+p.x+" "+p.y);
+				p=camera.getPoint();
+				comm.sendCommand("look "+p.x+" "+p.y);
+				
+				status.setText("Connected.");
+			} else
+				status.setText("Reconnecting...");
+		}
+	}
+
+	public void mouseClicked(MouseEvent e) {}
+	public void mouseEntered(MouseEvent e) {}
+	public void mouseExited(MouseEvent e) {}
+	public void mousePressed(MouseEvent e) {}
+	public void mouseReleased(MouseEvent e) {}
+
+	public void pointPicked(Point2D.Float p, MouseEvent e, PointPick pp) {
+		if(pp==gripper) {
+			comm.sendCommand("tgt "+p.x+" "+p.y);
+			if(autoTrackCheckBox.isSelected())
+				camera.setPoint(p.x,p.y);
+		} else if(pp==camera) {
+			comm.sendCommand("look "+p.x+" "+p.y);
+		}
+	}
+
+	public void stateChanged(ChangeEvent e) {
+		if(e.getSource()==gripperSlider) {
+			comm.sendCommand("gripper "+gripperSlider.getValue()/(float)slidermax);
+		} else if(e.getSource()==gripperAngleSlider) {
+			comm.sendCommand("gripperAngle "+gripperAngleSlider.getValue()/(float)slidermax*Math.PI);
+		} else if(e.getSource()==perspectiveSlider) {
+			comm.sendCommand("perspective "+perspectiveSlider.getValue()/(float)slidermax*Math.PI/2);
+		} else if(e.getSource()==gripperHeightSlider) {
+			comm.sendCommand("gripperHeight "+gripperHeightSlider.getValue()/(float)slidermax);
+		} else if(e.getSource()==cameraDistanceSlider) {
+			comm.sendCommand("cameraDistance "+cameraDistanceSlider.getValue()/(float)slidermax);
+		}
+	}
+
+	public void actionPerformed(ActionEvent e) {
+		if(e.getSource()==flattenButton) {
+			gripperHeightSlider.setValue(0);
+		} else if(e.getSource()==autoPerspectiveCheckBox) {
+			perspectiveSlider.setEnabled(!autoPerspectiveCheckBox.isSelected());
+			comm.sendCommand("autoPerspective "+(autoPerspectiveCheckBox.isSelected()?1:0));
+		} else if(e.getSource()==autoAngleCheckBox) {
+			gripperAngleSlider.setEnabled(!autoAngleCheckBox.isSelected());
+			comm.sendCommand("autoAngle "+(autoAngleCheckBox.isSelected()?1:0));
+		} else if(e.getSource()==autoTrackCheckBox) {
+			camera.setEnabled(!autoTrackCheckBox.isSelected());
+			comm.sendCommand("autoTrack "+(autoTrackCheckBox.isSelected()?1:0));
+			Point2D.Float p=gripper.getPoint();
+			camera.setPoint(p.x,p.y);
+		} else if(e.getSource()==maxDistCheckBox) {
+			cameraDistanceSlider.setEnabled(!maxDistCheckBox.isSelected());
+			comm.sendCommand("maxDist "+(maxDistCheckBox.isSelected()?1:0));
+		} else if(e.getSource()==reconnectBut) {
+			int port=comm._port;
+			String addr=comm._host;
+			comm.kill();
+			comm.removeRoverUpdatedListener(this);
+			comm = new RoverListener(comm._host,comm._port);
+			comm.addRoverUpdatedListener(this);
+		}
+	}
+	
+	public void frameInit() {
+		super.frameInit();
+		
+		int strutsize=10;
+		int topstrut=30;
+		int sepsize=5;
+		getContentPane().setLayout(new BorderLayout());
+		getContentPane().add(Box.createHorizontalStrut(strutsize),BorderLayout.EAST);
+		getContentPane().add(Box.createHorizontalStrut(strutsize),BorderLayout.WEST);
+		getContentPane().add(Box.createVerticalStrut(strutsize),BorderLayout.NORTH);
+		
+		JPanel p=new JPanel();
+		p.setLayout(new GridLayout(1,2,50,strutsize));
+		
+		// GRIPPER
+		{
+			JPanel tmp=new JPanel();
+			tmp.setLayout(new BorderLayout());
+			{
+				Box tmp2=Box.createVerticalBox();
+				tmp2.add(Box.createVerticalStrut(topstrut));
+				tmp2.add(new JLabel("Height:"));
+				gripperHeightSlider = new JSlider(SwingConstants.VERTICAL,-slidermax/4,slidermax,0);
+				gripperHeightSlider.setPreferredSize(new Dimension(0,0));
+				gripperHeightSlider.addChangeListener(this);
+				tmp2.add(gripperHeightSlider);
+				flattenButton=new JButton("Flatten");
+				flattenButton.addActionListener(this);
+				tmp2.add(flattenButton);
+				tmp.add(tmp2,BorderLayout.WEST);
+			}
+			{
+				Box tmp2=Box.createVerticalBox();
+				{
+					Box tmp3=Box.createHorizontalBox();
+					tmp3.add(new JLabel("Gripper Position:"));
+					tmp3.add(Box.createVerticalStrut(topstrut));
+					tmp2.add(tmp3);
+				}
+				gripper=new PointPick(false);
+				gripper.addPointPickedListener(this);
+				Dimension d=new Dimension(225,225);
+				gripper.setPreferredSize(d);
+				tmp2.add(gripper);
+				tmp.add(tmp2,BorderLayout.CENTER);
+			}
+			p.add(tmp);
+		}
+		
+		// CAMERA
+		{
+			JPanel tmp=new JPanel();
+			tmp.setLayout(new BorderLayout());
+			{
+				Box tmp2=Box.createVerticalBox();
+				tmp2.add(Box.createVerticalStrut(topstrut));
+				tmp2.add(new JLabel("Distance:"));
+				maxDistCheckBox = new JCheckBox("Max Dist");
+				maxDistCheckBox.setSelected(true);
+				maxDistCheckBox.addActionListener(this);
+				tmp2.add(maxDistCheckBox);
+				cameraDistanceSlider = new JSlider(SwingConstants.VERTICAL,0,slidermax,0);
+				cameraDistanceSlider.addChangeListener(this);
+				cameraDistanceSlider.setEnabled(false);
+				tmp2.add(cameraDistanceSlider);
+				tmp.add(tmp2,BorderLayout.EAST);
+			}
+			{
+				Box tmp2=Box.createVerticalBox();
+				{
+					Box tmp3=Box.createHorizontalBox();
+					tmp3.add(new JLabel("Camera Position:"));
+					tmp3.add(Box.createHorizontalGlue());
+					tmp3.add(Box.createVerticalStrut(topstrut));
+					autoTrackCheckBox=new JCheckBox("Track Gripper");
+					autoTrackCheckBox.addActionListener(this);
+					autoTrackCheckBox.setSelected(true);
+					tmp3.add(autoTrackCheckBox);
+					tmp2.add(tmp3);
+				}
+				camera=new PointPick(false);
+				camera.addPointPickedListener(this);
+				Dimension d=new Dimension(225,225);
+				camera.setPreferredSize(d);
+				tmp2.add(camera);
+				tmp.add(tmp2,BorderLayout.CENTER);
+			}
+			p.add(tmp);
+		}
+		getContentPane().add(p,BorderLayout.CENTER);
+		{
+			Box tmp2=Box.createHorizontalBox();
+			tmp2.add(Box.createHorizontalStrut(strutsize));
+			{
+				Box tmp3=Box.createVerticalBox();
+				{
+					JPanel tmp3b = new JPanel(new GridLayout(1,2,50,strutsize));
+					
+					// GRIPPER
+					Box tmpL=Box.createHorizontalBox();
+					{
+						Box tmp4=Box.createVerticalBox();
+						gripperAngleSlider=new JSlider(-slidermax,slidermax,0);
+						gripperAngleSlider.addChangeListener(this);
+						tmp4.add(gripperAngleSlider);
+						{
+							Box tmp5=Box.createHorizontalBox();
+							JLabel tl;
+							tmp5.add(tl=new JLabel("Face Left"));
+							tl.setFont(tl.getFont().deriveFont(tl.getFont().getSize2D()*.8f));
+							tmp5.add(Box.createHorizontalGlue());
+							tmp5.add(new JLabel("Angle"));
+							tmp5.add(Box.createHorizontalGlue());
+							tmp5.add(tl=new JLabel("Face Right"));
+							tl.setFont(tl.getFont().deriveFont(tl.getFont().getSize2D()*.8f));
+							tmp4.add(tmp5);
+						}
+						gripperSlider=new JSlider(0,slidermax,slidermax);
+						gripperSlider.addChangeListener(this);
+						tmp4.add(gripperSlider);
+						{
+							Box tmp5=Box.createHorizontalBox();
+							JLabel tl;
+							tmp5.add(tl=new JLabel("Close"));
+							tl.setFont(tl.getFont().deriveFont(tl.getFont().getSize2D()*.8f));
+							tmp5.add(Box.createHorizontalGlue());
+							tmp5.add(new JLabel("Gripper"));
+							tmp5.add(Box.createHorizontalGlue());
+							tmp5.add(tl=new JLabel("Open"));
+							tl.setFont(tl.getFont().deriveFont(tl.getFont().getSize2D()*.8f));
+							tmp4.add(tmp5);
+						}
+						tmpL.add(tmp4);
+					}
+					{
+						Box tmp4=Box.createVerticalBox();
+						autoAngleCheckBox=new JCheckBox("Auto");
+						autoAngleCheckBox.addActionListener(this);
+						autoAngleCheckBox.setSelected(true);
+						tmp4.add(autoAngleCheckBox);
+						tmp4.add(Box.createVerticalGlue());
+						tmpL.add(tmp4);
+					}
+					tmp3b.add(tmpL);
+					
+					// CAMERA
+					Box tmpR=Box.createHorizontalBox();
+					{
+						Box tmp4=Box.createVerticalBox();
+						perspectiveSlider=new JSlider(-slidermax,0,-slidermax);
+						perspectiveSlider.addChangeListener(this);
+						tmp4.add(perspectiveSlider);
+						{
+							Box tmp5=Box.createHorizontalBox();
+							JLabel tl;
+							tmp5.add(tl=new JLabel("Overhead"));
+							tl.setFont(tl.getFont().deriveFont(tl.getFont().getSize2D()*.8f));
+							tmp5.add(Box.createHorizontalGlue());
+							tmp5.add(new JLabel("Angle"));
+							tmp5.add(Box.createHorizontalGlue());
+							tmp5.add(tl=new JLabel("Parallel"));
+							tl.setFont(tl.getFont().deriveFont(tl.getFont().getSize2D()*.8f));
+							tmp4.add(tmp5);
+						}
+						tmp4.add(Box.createVerticalGlue());
+						tmpR.add(tmp4);
+					}
+					{
+						Box tmp4=Box.createVerticalBox();
+						autoPerspectiveCheckBox=new JCheckBox("Auto");
+						autoPerspectiveCheckBox.addActionListener(this);
+						autoPerspectiveCheckBox.setSelected(true);
+						tmp4.add(autoPerspectiveCheckBox);
+						tmp4.add(Box.createVerticalGlue());
+						tmpR.add(tmp4);
+					}
+					tmp3b.add(tmpR);
+					
+					tmp3.add(tmp3b);
+				}
+				
+				tmp3.add(Box.createVerticalStrut(strutsize));
+				tmp3.add(new JSeparator());
+				tmp3.add(Box.createVerticalStrut(strutsize-sepsize));
+				{
+					Box tmp4=Box.createHorizontalBox();
+					tmp4.add(status=new JLabel("Connecting..."));
+					tmp4.add(Box.createHorizontalGlue());
+					reconnectBut=new JButton(carrows);
+					reconnectBut.setPreferredSize(new Dimension(carrows.getIconWidth(),carrows.getIconHeight()));
+					reconnectBut.addActionListener(this);
+					reconnectBut.setToolTipText("Drop current connection and try again.");
+					tmp4.add(reconnectBut);
+					tmp3.add(tmp4);
+				}
+				tmp3.add(Box.createVerticalStrut(strutsize));
+				tmp2.add(tmp3);
+			}
+			tmp2.add(Box.createHorizontalStrut(strutsize));
+			getContentPane().add(tmp2,BorderLayout.SOUTH);
+		}
+
+		gripper.setEnabled(false);
+		camera.setEnabled(false);
+		addWindowListener(new CloseRoverAdapter(this));
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/RoverListener.java ./tools/mon/org/tekkotsu/mon/RoverListener.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/RoverListener.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/mon/RoverListener.java	2007-07-20 14:18:52.000000000 -0400
@@ -0,0 +1,94 @@
+package org.tekkotsu.mon;
+
+// Sends "Rover" command data from TekkotsuMon to the AIBO.
+import java.lang.Integer;
+import java.lang.String;
+import java.lang.System;
+import java.io.OutputStream;
+import java.io.InputStream;
+import java.net.Socket;
+import javax.swing.Timer;
+import java.awt.event.ActionEvent;
+import java.awt.event.ActionListener;
+import java.util.Vector;
+import java.net.SocketException;
+
+// The class itself. Brilliant that even though it does the talking,
+// it extends TCP*Listener*.
+public class RoverListener extends TCPListener {
+  // The command output stream
+  OutputStream out;
+  Socket mysock;
+	Vector listeners=new Vector();
+	
+	public interface RoverUpdatedListener {
+		public void RoverUpdated(RoverListener mc);
+	}
+
+	void addRoverUpdatedListener(RoverUpdatedListener mcl) { listeners.add(mcl); needConnection(); }
+	void removeRoverUpdatedListener(RoverUpdatedListener mcl) { listeners.remove(mcl); }
+	void fireRoverUpdated() {
+		for(int i=0;i<listeners.size();i++)
+			((RoverUpdatedListener)listeners.get(i)).RoverUpdated(this);
+	}
+
+  // Connect to control socket
+  public void connected(Socket socket) {
+    mysock = socket;
+    try {
+			mysock.setTcpNoDelay(true);
+		 try {
+			mysock.setTrafficClass(0x10);
+		 } catch(SocketException e) {}
+			out = mysock.getOutputStream();
+			InputStream sin=socket.getInputStream();
+			fireRoverUpdated();
+			fireConnected();
+			while (true) { //not that we expect input, but will block until the socket is closed
+				String msgtype=readLine(sin);
+				if(!_isConnected) break;
+			}
+    } catch(SocketException e) {
+    } catch(Exception e) {
+      e.printStackTrace();
+    } finally {
+      fireDisconnected();
+    }
+
+		try { socket.close(); } catch (Exception ex) { }
+
+		_isConnected=false;
+		fireRoverUpdated();
+		//The sleep is to get around the socket still listening after being closed thing
+		if(!destroy)
+			System.out.println("Rover - connection closed... reconnect after 5 seconds");
+		try { Thread.sleep(5000); } catch (Exception ex) {}
+  }
+
+  // Disconnect from control socket
+  public void close() {
+		//    try { mysock.close(); } catch(Exception e) {}
+    //_isConnected = false;
+    super.close();
+		//we'll fire an event to the listeners when the readLine in connected finally fails
+  }
+
+  // Send a Rover command
+  public void sendCommand(String command) {
+    if (out == null)
+      return;
+    command=command+"\n";
+    try {
+      out.write(command.getBytes());
+    } catch(Exception e) { close(); return; }
+  }
+
+  // Some state inquiry functions
+  public boolean hasData() { return false; }
+  public boolean isConnected() { return _isConnected; }
+
+  // Constructors
+  public RoverListener() { super(); }
+  public RoverListener(int port) { super(port); }
+  public RoverListener(String host, int port) { super(host, port); }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/TCPVisionListener.java ./tools/mon/org/tekkotsu/mon/TCPVisionListener.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/TCPVisionListener.java	2006-10-02 16:38:23.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/TCPVisionListener.java	2006-11-29 20:18:56.000000000 -0500
@@ -1,6 +1,5 @@
 package org.tekkotsu.mon;
 
-import java.awt.image.BufferedImage;
 import java.util.Vector;
 import java.util.Date;
 
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/VisionListener.java ./tools/mon/org/tekkotsu/mon/VisionListener.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/mon/VisionListener.java	2005-08-31 17:59:27.000000000 -0400
+++ ./tools/mon/org/tekkotsu/mon/VisionListener.java	2007-01-30 17:56:25.000000000 -0500
@@ -33,7 +33,6 @@
 	final static int DEFAULT_HEIGHT=144;
 	static int defRawPort=10011;
 	static int defRLEPort=10012;
-    //added this hardcoded region port, why is it variable in tekkotsu.cfg?
     static int defRegionPort=10013;
 
 	public void addListener(VisionUpdatedListener l);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java ./tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java	2006-03-02 13:28:03.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/AgentShapeInfo.java	2007-02-20 01:58:14.000000000 -0500
@@ -2,6 +2,7 @@
 
 import java.awt.Color;
 import java.awt.Graphics2D;
+import java.awt.Rectangle;
 import javax.swing.Icon;
 import javax.swing.ImageIcon;
 
@@ -26,7 +27,7 @@
 	public float getBottom() { return centroidy+2; }
 
 	public String toString() {
-		return (super.toString() + "(orientation " + orientation + ")");
+		return (super.toString() + " (x=" + centroidx + ", y=" + centroidy + ", theta=" + orientation + ")");
 	}	
 	
 	public Icon getIcon() { return icon; }
@@ -52,6 +53,14 @@
 		coordsY[2] = (int) (centroidy + 120 * Math.sin(2.618+orientation));
 		graphics.drawPolygon(coordsX,coordsY, 3);
 
+		//draw a point at the exact agent location
+		Rectangle bounds = graphics.getClipBounds();
+		int radius;
+		if (bounds != null)
+		    radius= java.lang.Math.max(4,java.lang.Math.max(bounds.width,bounds.height)/100);
+		else
+		    radius = 4;
+		graphics.fillOval((int)centroidx-radius/2, (int)centroidy-radius/2, radius, radius);
 	}
 
 	public float getOrientation() { return orientation; }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java ./tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java	2006-03-23 14:38:32.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/BlobShapeInfo.java	2007-02-15 00:07:32.000000000 -0500
@@ -47,7 +47,7 @@
 	bottomRight_z = _bottomRight_z;
     }
 
-	// should adjust these to take into account the crossbar height for pillar/pinata blobs in worldspace
+	// should adjust these to take into account the crossbar height for pillar/poster blobs in worldspace
 	public float getLeft() { return java.lang.Math.min(topLeft_x,bottomLeft_x); }
 	public float getRight() { return java.lang.Math.max(topRight_x,bottomRight_x); }
 	public float getTop() { return  java.lang.Math.min(topLeft_y,topRight_y); }
@@ -55,7 +55,7 @@
 
 
 	public String toString() {
-	    String _orient = (orient==0) ? "ground" : (orient==1) ? "pillar" : "pinata";
+	    String _orient = (orient==0) ? "ground" : (orient==1) ? "pillar" : "poster";
 	    String _center = "center=(" + centroidx + " " + centroidy + " " + centroidz + ")";
 	    return super.toString() + " " + _orient + " area=" + area + " " + _center;
 	}
@@ -68,7 +68,7 @@
 	}
 
     public void renderTo(Graphics2D graphics, float scaling) {
-	if (orient == 0 || SketchGUI.gui.space == SketchGUI.Space.cam) { // always render camspace blobs in the camera plane
+	if ( orient == 0 ) {
 	    graphics.setStroke(new BasicStroke(0.5f));
 	    graphics.drawLine((int)topLeft_x,(int)topLeft_y,(int)topRight_x,(int)topRight_y);
 	    graphics.drawLine((int)bottomLeft_x,(int)bottomLeft_y,(int)bottomRight_x,(int)bottomRight_y);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/LineShapeInfo.java ./tools/mon/org/tekkotsu/sketch/LineShapeInfo.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/LineShapeInfo.java	2006-04-14 19:54:13.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/LineShapeInfo.java	2007-02-15 04:07:16.000000000 -0500
@@ -98,17 +98,22 @@
 	    } else {
 		e2xi = 10000; e2yi = (int)(e2xi*m+b);
 	    };
+	    graphics.setStroke(new BasicStroke(1.0f));
 	    graphics.drawLine(e1xi,e1yi,e2xi,e2yi);
-	final float dl = 5/scaling;
-	if (end1_valid)
-	    graphics.drawLine((int) (e1xi+dl*Math.cos(theta)+.5),(int) (e1yi+dl*Math.sin(theta)+.5),
-			      (int) (e1xi-dl*Math.cos(theta)+.5),(int) (e1yi-dl*Math.sin(theta)+.5));
-	    //	    graphics.fillOval((int)e1x-radius/2, (int)e1y-radius/2, radius, radius);
-	if (end2_valid)
-	    graphics.drawLine((int) (e2xi+dl*Math.cos(theta)+.5),(int) (e2yi+dl*Math.sin(theta)+.5),
-			      (int) (e2xi-dl*Math.cos(theta)+.5),(int) (e2yi-dl*Math.sin(theta)+.5));
-	//	    graphics.fillOval((int)e2x-radius/2, (int)e2y-radius/2, radius, radius);
-
+	    final float dl = 5/scaling;
+	    if (end1_valid) {
+		int v1xi = (int)e1x, v1yi = (int)e1y;
+		graphics.drawLine((int)(v1xi+dl*Math.cos(theta)+.5), (int)(v1yi+dl*Math.sin(theta)+.5),
+				  (int)(v1xi-dl*Math.cos(theta)+.5), (int)(v1yi-dl*Math.sin(theta)+.5));
+		//	    graphics.fillOval((int)v1x-radius/2, (int)v1y-radius/2, radius, radius);
+	    }
+	    if (end2_valid) {
+		int v2xi = (int)e2x, v2yi = (int)e2y;
+		graphics.drawLine((int)(v2xi+dl*Math.cos(theta)+.5), (int)(v2yi+dl*Math.sin(theta)+.5),
+				  (int)(v2xi-dl*Math.cos(theta)+.5), (int)(v2yi-dl*Math.sin(theta)+.5));
+		//	    graphics.fillOval((int)e2x-radius/2, (int)e2y-radius/2, radius, radius);
+	    }
+	    
 	// draw circles for variance
 	// graphics.drawOval((int)e1x,(int)e1y,(int)(e1v/2),(int)(e1v/2));
 	// graphics.drawOval((int)e2x,(int)e2y,(int)(e2v/2),(int)(e2v/2));
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/LocalizationParticleShapeInfo.java ./tools/mon/org/tekkotsu/sketch/LocalizationParticleShapeInfo.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/LocalizationParticleShapeInfo.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/LocalizationParticleShapeInfo.java	2007-02-21 04:29:44.000000000 -0500
@@ -0,0 +1,63 @@
+package org.tekkotsu.sketch;
+
+import java.awt.Graphics2D;
+import java.awt.Graphics;
+import java.awt.Color;
+import java.awt.Font;
+import javax.swing.Icon;
+import javax.swing.ImageIcon;
+import java.awt.Rectangle;
+import java.awt.geom.*;
+import java.awt.BasicStroke;
+
+// stores info for a LocalizationParticleShape
+public class LocalizationParticleShapeInfo extends ShapeInfo {
+    static Icon icon = new ImageIcon(icon_path+"locpart.png");
+    static Icon inv_icon = new ImageIcon(icon_path+"locpartinv.png");
+    
+    public LocalizationParticleShapeInfo(int _id, int _parentId, String _name, Color _color,
+					 float _centroidx, float _centroidy, float _centroidz, float _orient, float _weight) {
+	super(_id, _parentId, _name, _color, _centroidx, _centroidy, _centroidz);
+	orientation = _orient;
+	weight = _weight;
+    }
+	
+    float orientation;
+    float weight;
+
+    // returns left-most coordinate of object
+    public float getLeft() { return centroidx; }
+    // returns right-most coordinate of object
+    public float getRight() { return centroidx; }
+    // returns top-most coordinate of object
+    public float getTop() { return centroidy; }
+    // returns bottom-most coordinate of object
+    public float getBottom() { return centroidy; }
+    
+    public String toString() {
+	String _particle = "wt=" + weight + " (" + centroidx + ", " + centroidy + ") th=" + orientation;
+	return super.toString() + " " + _particle; }
+
+    public Icon getIcon() { 
+	if (inverted)
+	    return inv_icon;
+	else
+	    return icon; 
+    }
+
+    public void renderTo(Graphics2D graphics, float scaling) {
+	Rectangle bounds = graphics.getClipBounds();
+	int radius;
+	if (bounds != null)
+	    radius= java.lang.Math.max(4,java.lang.Math.max(bounds.width,bounds.height)/100);
+	else
+	    radius = 4;
+	graphics.setStroke(new BasicStroke(1.0f));
+	graphics.fillOval((int)centroidx-radius/2, (int)centroidy-radius/2, radius, radius);
+	float dx = (float)java.lang.Math.cos(orientation)*radius*3;
+	float dy = (float)java.lang.Math.sin(orientation)*radius*3;
+	graphics.drawLine((int)centroidx,(int)centroidy,(int)(centroidx+dx),(int)(centroidy+dy));
+    }
+
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/SketchGUI.java ./tools/mon/org/tekkotsu/sketch/SketchGUI.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/SketchGUI.java	2006-10-02 16:38:24.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/SketchGUI.java	2007-02-20 01:58:15.000000000 -0500
@@ -83,7 +83,6 @@
     SketchOrShapeInfo curObject;
     String panelTitle;
     int panelCount = 1;
-    static SketchGUI gui;
 
     public static void main(String args[]) {
 	if(args.length<2)
@@ -109,7 +108,7 @@
 	}
 	else usage();
 
-        gui = new SketchGUI(args[0], _listingPort, _sketchPort, _space);
+	SketchGUI gui = new SketchGUI(args[0], _listingPort, _sketchPort, _space);
 	gui.addWindowListener(new WindowAdapter() {
 		 public void windowClosing(WindowEvent e) {System.exit(0);}});
 	gui.setVisible(true);
@@ -250,7 +249,7 @@
 	String inputLine;
 	
 	if (!panelBoundsSet){
-	    // Get image bounds from the dog
+	    // Get image bounds from the robot
 	    netout.println("size");
 	    System.out.println(inputLine = readLine());
 	    while((inputLine=readLine()).compareTo("size end") != 0) {
@@ -637,6 +636,15 @@
 	    return new PyramidShapeInfo(id, parentId, name, color, cx, cy, cz,
 				      FLx, FLy, FRx, FRy, BLx, BLy, BRx, BRy,
 				      Topx, Topy);
+	} else if(shapetype == 10) { // localzationparticleshape
+	    inputLine = readLine();
+	    st = new StringTokenizer(inputLine, ": ");
+	    st.nextToken();
+	    float orient = Float.parseFloat(st.nextToken());
+	    float weight = Float.parseFloat(st.nextToken());
+	    System.out.println("  orient: " + orient + "   weight: " + weight);
+	    return new LocalizationParticleShapeInfo(id, parentId, name, color, cx, cy, cz,
+						orient, weight);
 	} else {
 	    System.out.println("Invalid shape!");
 	    return new ShapeInfo(id, parentId, name, color, cx, cy, cz);
@@ -654,13 +662,15 @@
 	st = new StringTokenizer(inputLine,": ");
 	st.nextToken();
 	float area = Float.parseFloat(st.nextToken());
-	System.out.println("area: "+area);
+	System.out.println(" area: "+area);
 
 	inputLine = readLine();
 	st = new StringTokenizer(inputLine,": ");
 	st.nextToken();
 	int orient = Integer.parseInt(st.nextToken());
-	System.out.println("orient: "+orient);
+	System.out.println(" orient: "+orient);
+	if ( space == Space.cam )
+	    orient = 0; // always display cam-space blobs as lieing in the camera plane
 
 	inputLine = readLine();
 	st = new StringTokenizer(inputLine,": ");
@@ -668,7 +678,7 @@
 	float topLeft_x = Float.parseFloat(st.nextToken());
 	float topLeft_y = Float.parseFloat(st.nextToken());
 	float topLeft_z = Float.parseFloat(st.nextToken());
-	System.out.println("topLeft: " + topLeft_x + " " + 
+	System.out.println(" topLeft: " + topLeft_x + " " + 
 			   topLeft_y + " " + topLeft_z);
 
 	inputLine = readLine();
@@ -677,7 +687,7 @@
 	float topRight_x = Float.parseFloat(st.nextToken());
 	float topRight_y = Float.parseFloat(st.nextToken());
 	float topRight_z = Float.parseFloat(st.nextToken());
-	System.out.println("topRight: " + topRight_x + " " + 
+	System.out.println(" topRight: " + topRight_x + " " + 
 			   topRight_y + " " + topRight_z);
 
 	inputLine = readLine();
@@ -686,7 +696,7 @@
 	float bottomLeft_x = Float.parseFloat(st.nextToken());
 	float bottomLeft_y = Float.parseFloat(st.nextToken());
 	float bottomLeft_z = Float.parseFloat(st.nextToken());
-	System.out.println("bottomLeft: " + bottomLeft_x + " " + 
+	System.out.println(" bottomLeft: " + bottomLeft_x + " " + 
 			   bottomLeft_y + " " + bottomLeft_z);
 
 	inputLine = readLine();
@@ -695,7 +705,7 @@
 	float bottomRight_x = Float.parseFloat(st.nextToken());
 	float bottomRight_y = Float.parseFloat(st.nextToken());
 	float bottomRight_z = Float.parseFloat(st.nextToken());
-	System.out.println("bottomRight: " + bottomRight_x + " " + 
+	System.out.println(" bottomRight: " + bottomRight_x + " " + 
 			   bottomRight_y + " " + bottomRight_z);
 
 	return new BlobShapeInfo(id,parentId,name,color,cx,cy,cz,area,orient,
@@ -780,18 +790,15 @@
 	getContentPane().add(Box.createVerticalStrut(strutsize),BorderLayout.NORTH);
 	getContentPane().add(Box.createHorizontalStrut(strutsize),BorderLayout.WEST);
 	getContentPane().add(Box.createHorizontalStrut(strutsize),BorderLayout.EAST);
-		
-	//	setTitle(((space==1) ? "Cam" : ((space==2) ? "Local" : "World"))+"Space "+host);
-	setTitle(space.name()+": "+host);
+	setTitle(space.name()+" GUI: "+host);
 
 	sketchPanel.setMinimumSize(new Dimension(imageWidth/2, imageHeight/2));
 	sketchPanel.setPreferredSize(new Dimension(imageWidth*2, imageHeight*2));
 	sketchPanel.setLockAspectRatio(true);
 
 	curSketchPanel = sketchPanel;
-	//	panelTitle = ((space==1) ? "Cam" : ((space==2) ? "Local" : "World")) + "Img";
-	panelTitle = space.name() + " view: ";
-	sketchPanel.makeSketchFrame(sketchPanel, panelTitle+" "+host);
+	panelTitle = space.name() + " view"; // don't append host here because of clones
+	sketchPanel.makeSketchFrame(sketchPanel, panelTitle+": "+host);
 	{
 
 	    Box tmp1 = Box.createHorizontalBox();
@@ -907,7 +914,7 @@
 
     class CloseSketchGUIAdapter extends WindowAdapter {
 	SketchGUI gui;
-	CloseSketchGUIAdapter(SketchGUI gui) {this.gui=gui;}
+	CloseSketchGUIAdapter(SketchGUI _gui) { gui = _gui; }
 	public void windowClosing(WindowEvent e) {
 	    gui.close();
 	}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/SketchInfo.java ./tools/mon/org/tekkotsu/sketch/SketchInfo.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/SketchInfo.java	2006-02-20 18:43:32.000000000 -0500
+++ ./tools/mon/org/tekkotsu/sketch/SketchInfo.java	2007-02-19 20:08:27.000000000 -0500
@@ -12,8 +12,12 @@
 
 // stores info for a Sketch, to use as UserObject for DefaultMutableTreeNode
 public class SketchInfo extends SketchOrShapeInfo {
-    static Icon icon = new ImageIcon(icon_path+"sketch.png");
-    static Icon inverted_icon = new ImageIcon(icon_path+"sketchinv.png");;
+    static Icon bool_icon = new ImageIcon(icon_path+"sketchbool.png");
+    static Icon inverted_bool_icon = new ImageIcon(icon_path+"sketchboolinv.png");;
+
+    static Icon uchar_icon = new ImageIcon(icon_path+"sketchuchar.png");
+    static Icon inverted_uchar_icon = new ImageIcon(icon_path+"sketchucharinv.png");
+
 
     static Icon int_icon = new ImageIcon(icon_path+"sketchint.png");
     static Icon inverted_int_icon = new ImageIcon(icon_path+"sketchintinv.png");
@@ -39,9 +43,9 @@
     int height;
 
 
-    int jetred[]; 
-    int jetgreen[];
-    int jetblue[];
+    byte jetred[]; 
+    byte jetgreen[];
+    byte jetblue[];
 
     float grayMax, grayMin;
 
@@ -63,12 +67,14 @@
     
     public Icon getIcon() { 
 	if (inverted) {
-	    if (sketchType == SKETCH_BOOL_TYPE) return inverted_icon;
-		else return inverted_int_icon;
+	    if (sketchType == SKETCH_BOOL_TYPE) return inverted_bool_icon;
+	    else if (sketchType == SKETCH_UCHAR_TYPE)  return inverted_uchar_icon;
+	    else return inverted_int_icon;
 	}
 	else {
-	    if (sketchType == SKETCH_BOOL_TYPE) return icon;
-		else return int_icon;
+	    if (sketchType == SKETCH_BOOL_TYPE) return bool_icon;
+	    else if (sketchType == SKETCH_UCHAR_TYPE)  return uchar_icon;
+	    else return int_icon;
 	}
     }
 
@@ -86,10 +92,6 @@
     // Deep image copying. Called when the image is first loaded to cache it
     public void copyImage(BufferedImage _img)
     {
-	Hashtable colortable = new Hashtable();
-	int colorCount = 0;
-	boolean lookingForGray = true;
-
 	if (_img == null) {
 	    System.err.println("Tried to copy a null image");
 	    return;
@@ -97,9 +99,23 @@
 
 	if (colormap == COLORMAP_SEG_TYPE || sketchType == SKETCH_BOOL_TYPE )
 	    {
-		System.out.println("Type = "+_img.getType()+" RGB="+BufferedImage.TYPE_INT_ARGB);
-		img = new BufferedImage(_img.getWidth(), _img.getHeight(), 
-					_img.getType(),((IndexColorModel) _img.getColorModel()));
+		System.out.println("Type = "+_img.getType()+" RGB_Type="+BufferedImage.TYPE_INT_RGB);
+		if ( _img.getColorModel() instanceof IndexColorModel )
+		    img = new BufferedImage(_img.getWidth(), _img.getHeight(),
+					    _img.getType(),
+					    ((IndexColorModel) _img.getColorModel()));
+		else {
+		    // If the sketch is a usint but it has COLORMAP_SEG_TYPE, it has the wrong ColorModel.
+		    // The user probably converted a bool or uchar sketch to usint.
+		    // So use the jet colormap.
+		    // *** THIS IS SORT OF A KLUDGE ***
+		    // Note that usint can have values > 256 so we might still get an array bounds error
+		    // if the sketch contains large values.
+		    IndexColorModel cmodel = new IndexColorModel(8,256,jetred,jetgreen,jetblue);
+		    img = new BufferedImage(_img.getWidth(), _img.getHeight(),
+					    BufferedImage.TYPE_BYTE_INDEXED,
+					    cmodel);
+		}
 		img.getRaster().setRect(_img.getRaster());
 
 	    }
@@ -113,31 +129,20 @@
 		    {
 			int x = i % _img.getWidth();
 			int y = i / _img.getWidth();
-			img.getRaster().setSample(x,y,0,_img.getRaster().getSample(x,y,0));
 			int cur = _img.getRaster().getSample(x,y,0);
+			img.getRaster().setSample(x,y,0,cur);
 			if (cur > grayMax) 
 			    grayMax = cur;
-			if (cur < grayMin)
+			else if (cur < grayMin)
 			    grayMin = cur;
 		    }
 		System.out.println("Grayscale image: "+img.getType()+" "+colormap+" ("+
 				   grayMin+","+grayMax+")");
-		if (grayMax == grayMin) {
-		    grayMax++;
-		}
-
-
-		//img.getRaster().setRect(_img.getRaster());
+		if (grayMax == grayMin) ++grayMax;
 	    }
 	imageLoaded = true;
     }
 
-    // The RenderTo function is an artifact of the old way sketches 
-    // were rendered and is no longer called. 
-    /*public void renderTo(Graphics2D g)
-    {
-    }*/
-
 
     public void renderToArrays(int r[], int g[], int b[], int counts[])
     {
@@ -192,9 +197,9 @@
 			}
 			if (inverted)
 			    cur = 255 - cur;
-			r[pos]+=jetred[cur];
-			g[pos]+=jetgreen[cur];
-			b[pos]+=jetblue[cur];
+			r[pos] += 0x00FF & (int)jetred[cur];
+			g[pos] += 0x00FF & (int)jetgreen[cur];
+			b[pos] += 0x00FF & (int)jetblue[cur];
 			counts[pos]++;
 		    }
 		}
@@ -205,19 +210,19 @@
     public void makeJetMap()
     {
 
-	jetred = new int[256];
-	jetgreen = new int[256];
-	jetblue = new int[256];
+	jetred = new byte[256];
+	jetgreen = new byte[256];
+	jetblue = new byte[256];
 
 	for (int i=0;i<256; i++) {
 	    if (i < 32)
 		jetgreen[i] = 0;
 	    else if (i < 96)
-		jetgreen[i] = (i-32)*4;
+		jetgreen[i] = (byte) ((i-32)*4);
 	    else if (i <= 160)
-		jetgreen[i] = 255;
+		jetgreen[i] = (byte)255;
 	    else if (i < 224)
-		jetgreen[i] = (224-i)*4;
+		jetgreen[i] = (byte) ((224-i)*4);
 	    else
 		jetgreen[i] = 0;
 	}
@@ -235,9 +240,9 @@
 	}
 
 	// manually set color 0 to background gray
-	jetred[0] = 128;
-	jetgreen[0] = 128;
-	jetblue[0] = 128;
+	jetred[0] = (byte)128;
+	jetgreen[0] = (byte)128;
+	jetblue[0] = (byte)128;
     }
     
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/SketchPanel.java ./tools/mon/org/tekkotsu/sketch/SketchPanel.java
--- ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/SketchPanel.java	2006-04-27 20:15:03.000000000 -0400
+++ ./tools/mon/org/tekkotsu/sketch/SketchPanel.java	2006-11-29 20:20:12.000000000 -0500
@@ -317,7 +317,7 @@
 	     sketchPanel.setLockAspectRatio(true);
 	     ++gui.panelCount;
 	     sketchPanel.makeSketchFrame(sketchPanel, 
-					 gui.panelTitle+gui.panelCount+" "+gui.host);
+					 gui.panelTitle+" "+gui.panelCount+": "+gui.host);
 	     sketchPanel.setBounds(leftBound, rightBound, topBound, bottomBound);
 	     sketchPanel.imageUpdated(_image,paths);		
 	 } 
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketch.png and ./tools/mon/org/tekkotsu/sketch/icons/sketch.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchbool.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchbool.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchboolinv.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchboolinv.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchint.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchint.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchintinv.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchintinv.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchinv.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchinv.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchuchar.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchuchar.png differ
Binary files ../Tekkotsu_3.0/tools/mon/org/tekkotsu/sketch/icons/sketchucharinv.png and ./tools/mon/org/tekkotsu/sketch/icons/sketchucharinv.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/safemot/Makefile ./tools/safemot/Makefile
--- ../Tekkotsu_3.0/tools/safemot/Makefile	2006-03-28 12:08:23.000000000 -0500
+++ ./tools/safemot/Makefile	2007-11-15 20:03:34.000000000 -0500
@@ -15,14 +15,17 @@
 SRCSUFFIX:=.cc
 PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
 
-# Use the containing framework, regardless of TEKKOTSU_ROOT setting (no '?=')
-TEKKOTSU_ROOT=../..
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo failure),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -32,7 +35,8 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
@@ -41,12 +45,16 @@
          -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -76,7 +84,7 @@
 clean:
 	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
 
-test: $(BIN)
+test: ./$(BIN)
 	@for x in * ; do \
 		if [ -r "ideal-$$x" ] ; then \
 			if diff -u "ideal-$$x" "$$x" ; then \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/safemot/safemot.cc ./tools/safemot/safemot.cc
--- ../Tekkotsu_3.0/tools/safemot/safemot.cc	2006-09-09 00:33:07.000000000 -0400
+++ ./tools/safemot/safemot.cc	2007-01-30 17:56:25.000000000 -0500
@@ -42,7 +42,14 @@
 int main(unsigned int argc, const char** argv) {
 	if(argc<3)
 		return usage(argc,argv);
-	config=new Config("tekkotsu.cfg");
+	::config = new Config();
+	::config->setFileSystemRoot("");
+	if(::config->loadFile("tekkotsu.xml")==0) {
+		if(::config->loadFile("tekkotsu.cfg")==0)
+			std::cerr << std::endl << " *** ERROR: Could not load configuration file tekkotsu.xml *** " << std::endl << std::endl;
+		else
+			std::cerr << "Successfully imported settings from old-format tekkotsu.cfg" << std::endl;
+	}
 	unsigned int used=1;
 	bool isRad=true;
 	while(used<argc) {
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/graphics/StoryboardIcon.ai ./tools/storyboard/graphics/StoryboardIcon.ai
--- ../Tekkotsu_3.0/tools/storyboard/graphics/StoryboardIcon.ai	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/graphics/StoryboardIcon.ai	2005-10-18 12:15:54.000000000 -0400
@@ -0,0 +1,782 @@
+%PDF-1.4%âãÏÓ
+1 0 obj<< /Type /Catalog /Pages 2 0 R /Metadata 228 0 R >> endobj2 0 obj<< /Type /Pages /Kids [ 5 0 R ] /Count 1 >> endobj3 0 obj<< /ModDate (D:20051017164320-04'00')/CreationDate (D:20051017204030Z)/Producer (Adobe PDF library 5.00)/Creator (Adobe Illustrator 10)>> endobj5 0 obj<< /Type /Page /MediaBox [ 0 0 128 128 ] /Parent 2 0 R /PieceInfo << /Illustrator 122 1 R >> /LastModified (D:20051017164319-04'00')/ArtBox [ 3 1.37012 123.43164 126.57617 ] /Group 223 0 R /TrimBox [ 0 0 128 128 ] /Thumb 224 0 R /Contents 226 0 R /Resources << /ColorSpace << /CS0 138 0 R >> /XObject << /Im0 144 0 R /Fm0 150 0 R /Fm1 162 0 R /Im1 171 0 R /Fm2 176 0 R /Fm3 188 0 R /Im2 196 0 R /Im3 202 0 R /Fm4 207 0 R /Fm5 219 0 R >> /ExtGState << /GS0 139 0 R /GS1 153 0 R >> /ProcSet [ /PDF /ImageC ] >> >> endobj6 1 obj<< /Length 1108 >> stream
+%!PS-Adobe-3.0 %%Creator: Adobe Illustrator(R) 10.0%%AI8_CreatorVersion: 10.0%%For: (A Student) ()%%Title: (StoryboardIcon.ai)%%CreationDate: 10/17/05 4:43 PM%%BoundingBox: 3 1 124 127%%HiResBoundingBox: 3 1.3701 123.4316 126.5762%%DocumentProcessColors: Cyan Magenta Yellow Black%AI5_FileFormat 6.0%AI3_ColorUsage: Color%AI7_ImageSettings: 0%%RGBProcessColor: 0 0 0 ([Registration])%%AI6_ColorSeparationSet: 1 1 (AI6 Default Color Separation Set) %%+ Options: 1 16 0 1 0 1 0 0 0 0 1 1 1 18 0 0 0 0 0 0 0 0 -1 -1 0 0 0 0 1 0 0 0 0 1 0 0 0 0 0 1 2 3 4%%+ PPD: 1 21 0 0 60 45 2 2 1 0 0 1 0 0 0 0 0 0 0 0 0 0 () %AI3_TemplateBox: 64.5 63.5 64.5 63.5%AI3_TileBox: 30 31 582 761%AI3_DocumentPreview: None%AI5_ArtSize: 128 128%AI5_RulerUnits: 2%AI9_ColorModel: 1%AI5_ArtFlags: 0 0 0 1 0 0 1 0 0%AI5_TargetResolution: 800%AI5_NumLayers: 3%AI9_OpenToView: -375 359 1 1006 719 90 0 0 11 42 0 0 1 1 1 0%AI5_OpenViewLayers: 737%%PageOrigin:30 31%%AI3_PaperRect:-30 761 582 -31%%AI3_Margin:30 -31 -30 31%AI7_GridSettings: 72 8 72 8 1 0 0.8 0.8 0.8 0.9 0.9 0.9%AI9_Flatten: 1%%EndCommentsendstreamendobj38 1 obj<< /Length 15551 >> stream
+%%BoundingBox: 3 1 124 127%%HiResBoundingBox: 3 1.3701 123.4316 126.5762%AI7_Thumbnail: 124 128 8%%BeginData: 14914 Hex Bytes%0000330000660000990000CC0033000033330033660033990033CC0033FF%0066000066330066660066990066CC0066FF009900009933009966009999%0099CC0099FF00CC0000CC3300CC6600CC9900CCCC00CCFF00FF3300FF66%00FF9900FFCC3300003300333300663300993300CC3300FF333300333333%3333663333993333CC3333FF3366003366333366663366993366CC3366FF%3399003399333399663399993399CC3399FF33CC0033CC3333CC6633CC99%33CCCC33CCFF33FF0033FF3333FF6633FF9933FFCC33FFFF660000660033%6600666600996600CC6600FF6633006633336633666633996633CC6633FF%6666006666336666666666996666CC6666FF669900669933669966669999%6699CC6699FF66CC0066CC3366CC6666CC9966CCCC66CCFF66FF0066FF33%66FF6666FF9966FFCC66FFFF9900009900339900669900999900CC9900FF%9933009933339933669933999933CC9933FF996600996633996666996699%9966CC9966FF9999009999339999669999999999CC9999FF99CC0099CC33%99CC6699CC9999CCCC99CCFF99FF0099FF3399FF6699FF9999FFCC99FFFF%CC0000CC0033CC0066CC0099CC00CCCC00FFCC3300CC3333CC3366CC3399%CC33CCCC33FFCC6600CC6633CC6666CC6699CC66CCCC66FFCC9900CC9933%CC9966CC9999CC99CCCC99FFCCCC00CCCC33CCCC66CCCC99CCCCCCCCCCFF%CCFF00CCFF33CCFF66CCFF99CCFFCCCCFFFFFF0033FF0066FF0099FF00CC%FF3300FF3333FF3366FF3399FF33CCFF33FFFF6600FF6633FF6666FF6699%FF66CCFF66FFFF9900FF9933FF9966FF9999FF99CCFF99FFFFCC00FFCC33%FFCC66FFCC99FFCCCCFFCCFFFFFF33FFFF66FFFF99FFFFCC110000001100%000011111111220000002200000022222222440000004400000044444444%550000005500000055555555770000007700000077777777880000008800%000088888888AA000000AA000000AAAAAAAABB000000BB000000BBBBBBBB%DD000000DD000000DDDDDDDDEE000000EE000000EEEEEEEE0000000000FF%00FF0000FFFFFF0000FF00FFFFFF00FFFFFF%524C45FDFCFFFD54FFA8FD78FFA1688C68FD76FFA193FD048CFD73FFA88C%688C688C688C68FD6EFFA89A8C8C688C8C8C688C8C8C688CFD6BFFA89A68%8C688C688C688C688C688C688C68FD69FFA86FFD118CFD67FFA18C688C68%8C688C688C688C688C688C688C688C68FD62FFA193688C8C8C688C8C8C68%8C8C8C688C8C8C688C8C8C688C8C8CFD5FFFA88C688C688C688C688C688C%688C688C688C688C688C688C688C688C68FD5DFFA1FD1E8CFD59FFCAA86F%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C68FD55FFA86F8C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C%688C8C8C688C8C8C688C8C8C688CFD53FF7D93688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C68FD50%FFCA93FD2A8CFD4DFFA8A1688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C68FD49FF9A%8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8CFD45FFA8A86F8C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C68FD44FFA1FD378CFD41FFA193%688C688C688C688C688C688C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C688C688C68FD3CFF%A893688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C%8C8C688CFD39FFA89A688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C68FD37FFCA9AFD438CFD35FF6F8C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C68FD30FFA18C8C8C688C8C8C688C8C8C688C8C8C688C8C8C68%8C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C%8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8CA8FD2CFF76%93688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C68CAFD2AFFA168FD4F8CA8FD2A%FF688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C68A8FD29FFA18C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C%8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C688CA8FD29FFA1688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C68A8FD29FF9AFD518CA8FD29FF93688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C76A8A8FD2AFF8C8C688C8C8C688C8C%8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C68%8C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C%8C688C8C8CA1FD30FFA88C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C6FA8FD32FFCAFD458C%93FD35FF768C688C688C688C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C688C6FCAFD36FF93688C8C8C688C8C8C688C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C%8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8CA1FD3AFF688C688C%688C688C688C688C688C688C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C688C688C688C689A%A8FD3BFFFD3E8C9AFD3DFF688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C68A8FD3EFF8C8C8C688C8C8C688C8C8C688C8C%8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C68%8C8C8C688C8C8C688C8C8C688C8C8CFFFF845A2F0D070D2F5A7EFD36FF68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C6893A87E07%0D070D060D070D060D075AA8FD33FFFD388C9A842F070D070D070D070D07%0D070D070D5AFD32FF688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C689A7E0D070D060D355F5F8A655F352F070D060D2FFD30FFA88C68%8C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C%8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C68A17E0D070D0D6065%8A8A8A658A8A8A65660D0D070D2FFD2FFFA8688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C68937E0D070D0D8A658A658A658A658A658A658A%2F0D060D2FFD2EFFA1FD348C93AF2F070D0D8A8A8A898A8A8A898A8A8A89%8A8A8A350D070D84FD2DFF9A688C688C688C688C688C688C688C688C688C%688C688C688C688C68936F8C688C688C688C688C688C688C688C688C688C%688C688CA87E060D0766658A658A658A658A658A658A658A658A0D0D072F%FD2DFF688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8CA1A8FFFF%FF9A8C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C6FFF0D0D07%608A8A658A8A8A898A8A8A898A8A8A898A8A8A070D0784FD2CFF8C688C68%8C688C688C688C688C688C688C688C6893A8FD05FFA18C688C688C688C68%8C688C688C688C688C688C688C688C68CA7E0D070D658A658A658A658A65%8A658A658A658A658A6535060D2FFD2CFFFD118CA1A8FD07FFA8FD188C9A%FF5A070D358A8A8A898A8A8A89FD078A898A8A8A5F2F070DFD2BFFA88C68%8C688C688C688C688C688C689AA1FD09FFA88C688C688C688C688C688C68%8C688C688C688C688C688C688CA8FF2F0D075F658A658A658A898A658A89%8A898A898A658A898A070D07A9FD2AFFA18C8C688C8C8C688C8CA8A8FD0E%FF8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8CA1FFFF0D%070D658A658A8A8A898A8A8A89FD078A898A8A35072FA8FD2AFF6F8C688C%688C68A1A8FD11FF688C688C688C688C688C688C688C688C688C688C688C%688C68CAFFFF070D068A658A658A658A658A898A898A898A898A898A658A%2F0D07A9FD2AFF938C8C8C9AA1FD13FF93FD198CFFFFFF0D072F8A8A89FD%088AAE8AAE8AAEFD058A5A0D2FA8FD2AFF6893A8FD15FFA88C688C688C68%8C688C688C688C688C688C688C688C688C688C6FFFFFFF0D0D078A898A65%8A898A898A8A8A2758838A8AAE8A8A898A2F2F0DA9FD41FFA88C688C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C68FD048CA8FFFFFF5A0D0D358A8A%8A89FD048AAE8A59F82758AE8AAE8AAE8A5A2F2FAFFD41FF9A688C688C68%8C688C688C688C688C688C688C688C688C688C688CA1FFFFFF5A0D073565%8A898A658A898A898A5FFD04F8598AAE8A842F362FFD42FFFD1B8CCAFD04%FF0D2F0DFD088AAE8AAEFD05F82783AF5A5A5A85FD41FF688C688C688C68%8C688C688C688C688C688C688C688C688C688C688CA1FD04FF5A0D2F2F8A%898A89FD048AAE8A2EFD06F82753595AA9FD41FF8C688C8C8C688C8C8C68%8C8C8C688C8C8C688C8C8C68FD048C938CA1FD04FFA8302F2F59FD068AAE%8AAF59FD08F8277EFD42FF688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C6FFD05FF5A2F282F598A898A89FD048AAEFD0AF827%FD41FFFD168C938C8C8C938C93FD06FFF8002836598A8AAE8AAE8AAFAE52%FD0BF852A8FD3EFF688C688C688C688C688C688C688C688C688C688C688C%688C688C68938C93FD04FF27F8F8F8052F2F605FFD048AAE52FD0DF852FF%FFFFA1CAFD37FFA18C8C8C688C8C8C688C8C8C688C8C8C688C8C8C68FD04%8C938C938C9393CAFFFF52FD04F8282F302F2F2F5A60845A7EFD0EF84B93%8C8CA8FD37FF9A688C688C688C688C688C688C688C688C688C688C688C68%8C68938CFD0493CA7DFD04F8277E2F0D2F0D2F2F5A2F5A5927FD0BF84B68%8C688C68A8FD37FF6FFD148C938C938CFD0493BC93BC6FFD04F827A8FFFF%A935302F5A2F5A5A842EFD08F84B68FD078CA1FD36FFA88C688C688C688C%688C688C688C688C688C688C688C688C8C8C68FD04939A93FD05F87DFD06%FFA9A88484AFA8A8F8274B6F688C688C688C688C688C688C68A1FD37FF8C%8C688C8C8C688C8C8C688C8C8C68FD088C938C93939A939A9A27FD04F84B%A8A8FD09FFA1A16F8C8C8C688C8C8C688C8C8C688C8C8C688C9AFD36FFA1%8C688C688C688C688C688C688C688C688C688C688C688C68FD04939A934B%FD04F8209A93936893688C688C688C688C688C688C688C688C688C688C68%8C688C688C689AFD36FFA8FD138C938C938CFD0493BC9A6FFD04F8209AFD%04938C938C93FD188C93FD36FF768C688C688C688C688C688C688C688C68%8C688C68938C938C93939A939AFD05F89AFD049368938C8C688C688C688C%688C688C688C688C688C688C688C688C688C688CFD36FF9A688C8C8C688C%8C8C688C8C8C68FD088CFD04939A939AFD05F89A9A9AFD04938C93FD068C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C68FD36FF6F8C688C688C%688C688C688C688C688C688C688C688C68FD04939AFD05F84B939A939368%93688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8CA8FD35FF9AFD118C938C938CFD0493BC4BFD04F84B9ABCFD04938C938C%93FD1B8CFD36FF6F8C688C688C688C688C688C688C688C688C68938C938C%93939A4BFD04F827939AFD049368938C8C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688CA8FD35FF9A8C8C688C8C8C688C8C8C%68FD048C938C938CFD0493BC6FFD04F8206FBCFD04938C938C93FD068C68%8C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8CFD36FF6F8C688C68%8C688C688C688C688C688C688C6893689393936FFD05F86F9AFD04936893%688C688C688C688C688C688C688C688C688C688C688C688C688C688C688C%688CA8FD35FFA1FD0B8C938C8C8C938CFD04939A9327FD04F84BBC93BC93%938C938C938C93FD1D8CA8FD35FFA88C688C688C688C688C688C688C688C%68938C93939A934BFD04F8209AFD04938C93688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C4BFD36FF688C8C8C%68FD088C938C938C93939A936FFD04F8209A939A93938C938C938C938C8C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C6852%27FD35FF8C688C688C688C688C688C688C68938CFD04936FFD05F89AFD04%938C93688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C4BF852FD34FF9AFD088C938C938CFD0493BC939AFD%05F8769A9AFD04938C938C8C8C93FD1F8C6FF8F87DFD34FF688C688C688C%688C688C8C9368FD04939A20FD04F84B939A93938C938C8C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C688C688C688C688C%68F8F8F8A8FD33FFFD068C938C8C8C938C93939A939A4BFD04F84B9A9A93%9A93938C93FD068C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C%8C8C688C8C8C688C8C6FF8F8F827A8FD32FF688C688C688C688C688C68FD%04939A4BFD04F8206F9A939368938C8C688C688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C688C68FD04F827FD%32FFCA8C938C938C938C938CFD0493BC6F20F8F8F8206FBC939AFD04938C%93FD268C52FD04F852FD33FF68938C9368938CFD04939A9320FD04F86F9A%939A939368938C8C688C688C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C688C688C688C68FF27FD04F87DFD33FF8CFD0893%BC9A27FD04F84BBC939AFD04938C93FD068C688C8C8C688C8C8C688C8C8C%688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C688CFFFFFD05F8A8FD05%FFAF84FD2BFFA868FD06939A934BFD04F8209A939A93936893688C688C68%8C688C688C688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C68FFFFA8FD05F8FF845A070D070D060D2F5AA8FD27FF93%939A93BC93BC9A76FD04F8209A9ABCFD04938C938C93FD288CCAFFFF7DF8%F8F8270D0D070D070D070D070D070D2FA9FD24FFA852FF9A9A939A9A9AFD%05F89A939AFD049368938C8C688C688C688C688C688C688C688C688C688C%688C688C688C688C688C688C688C688C688C688C688C68CAFFFFFF52F806%070D070D060D072F060D070D060D075AFD23FF7D27A8FFCABC9A9AFD05F8%769ABCFD04938C938C938C8C688C8C8C688C8C8C688C8C8C688C8C8C688C%8C8C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8CA8FFFFFFAF2F0D2F%072F3560898A8A8A65602F0D070D0736AFFD21FF52F852FFFFA8A120FD04%F84B9A9AFD04936893688C688C688C688C688C688C688C688C688C688C68%8C688C688C688C688C688C688C688C688C688C688C6FFD05FFA935072F07%355F8A658A658A658A658A5F2F060D072FFD21FFF8F8F8FFFFFF52FD04F8%4B9ABC93BC93938C938C938C93FD238C9AA8FD08FF5A2F362F60FD048A89%8A8A8A898A8A8A8936070D077EFD1FFF7DF8F8F827FF7DFD04F827A8CA93%9A93938C93688C688C688C688C688C688C688C688C688C688C688C688C68%8C688C688C689A7DCAFD0FFFA92F2F2F608A8A898A898A658A898A658A65%8A6535070D06A9FD1EFF52FD04F87D27F8F8F827A8FFFFFFCAA89A938C93%FD048C688C8C8C688C8C8C688C8C8C688C8C8C688C8C8C6FA1A1CAFD0AFF%7D277DFD07FF5A5A35608AAEFD068A898A8A8A898A8A8A6535070D2FFD1E%FF27FD09F87DFD07FFA8FFA8A16F93688C688C688C688C688C688C689A6F%A1A1A8A8FD11FFF8F8F82752A8FFFFA85A595AFD068A898A898A658A658A%658A658A5F0D070DA8FD16FFA8AFA9AFA9FFA8FD09F852FD32FF7DFD05F8%2752847E8484AF8AAF8AAE8AAEFD068A898A8A8A898A2F0D0784FD13FF5A%30072F0D362F5A5959FD09F8A8FD33FF27FD07F805277DAEAE8AAE8A8A89%8A898A658A898A658A658A6560070D2FFD11FF840D0D072F2F302F5A5A7E%27FD0AF827277DA8FD2FFF7DFD0AF8272E838AAE8AAEFD048A898A8A8A65%8A8A8A5F0D070DFD0FFFA82F060D070D0735355A59845AFD0FF827A8FD2E%FF27FD0DF82759838A898A898A658A658A658A658A060D07FD0EFFA92F07%2F0D2F598A8AAE8AAFAE84FD0EF852FD29FFA8A87D7D52522727FD10F82D%AEFD068A898A8A8A890D070DFD0DFFA82F070D0659658A89FD048AAE52FD%0CF827A8FD1FFFA8A87D7D52522727FD19F8042E8A898A898A658A658A65%8A658A060D07FD0DFF36070D076089FD048AAE8AAEAE27FD0AF827A8FD16%FFA8A8A87D527D2727FD23F85283AE8A8A898A8A8A898A8A8A658A5F0D07%0DFD0CFF84070D065F658A658A898A89AE8AAEFD09F8277DFD0DFFA8A87D%7D527D2727FD2CF8278A8A8A898A898A658A658A658A658A655F070D2FFD%0CFF2F0D07368A8A89FD048AAE8AAE59FD08F8597EFD04FFA8A8A87D7D52%522727FD22F82752277D527DA8A8FD09F82D83AF8AAE8AAEFD068A898A8A%8A898A2F0D077EFD0BFF7E0D070D5F8A658A658A898A8AAE8A2EFD05F804%525A595A5352FD0427F827FD1DF8272752527D7DA8A8FD09FF52FD08F859%8AAE8AAE8A8A898A898A658A898A658A658A5F0D070DA8FD0BFF5A070D35%8A898A8A8A89FD048AAE04FD04F85284AF845A2F59FD0427F827F827FD11%F8272752527D7DA8A8FD14FF27FD05F827527E5A848AAE8AAE8A8A898A8A%8A898A8A8A658A8A2F070D2FFD0CFF070D0660658A658A658A898A8A8A5F%F8F8F8278A8AAE8A8A2F2F2F27F827F827FD09F8272727527D7DA87DFD1F%FFFD05F87DFFA9535A2F848A8A898A898A658A658A658A658A6535070D06%A9FD0CFF0D070D8A8A89FD088A59F82D5FAF8AAE8AAE8A362F362727F827%2752527D52A8A8FD29FF7DF8F82752FD04FF842F5A2F84FD088A898A8A8A%8936070D077EFD0CFFA9070D0D8A658A658A898A898A8A8A275F8A8A8AAE%8A8A898A2F2F0784FD33FF52F852A8FD05FFAF5A0D2F0D355F8A898A658A%658A658A5F2F060D072FFD0DFF840D0735658A8A8A898A8A8A89FD048AAE%8A8A8AAE8A8A8A5A0D2FA8FD33FF52FD09FFA95A0D2F0D2F358A8A8A898A%8A60350D070D0736FD0EFFAF060D078A658A658A658A898A658A898A898A%898A898A898A070D07A9FD3EFFA95A070D070D060D0D2F060D070D060D07%5AFD10FF0D070D658A8A8A89FD0F8A892F0D2FFD41FFA92F0D072F070D07%0D070D070D2FA9FD11FF2F0D075F658A658A658A898A658A898A898A898A%658A895F070D2FFD43FF845A070D070D060D0D5A84FD13FF5A070D2F8A65%8A8A8A898A8A8A898A8A8A898A8A8A898A2F0D077EFD47FFAFA8A9FD17FF%A80D060D5F8A658A658A658A658A658A658A658A658A5F0D070DA8FD62FF%2F0D072F658A8A8A898A8A8A898A8A8A898A8A8A6535070D2FFD63FFA906%0D0735658A658A658A658A658A658A658A6535060D07A9FD64FF7E070D07%35658A8A8A658A8A8A898A8A8A6535070D0784FD66FF5A060D070D358A65%8A658A658A658A5F0D060D075AFD68FF5A070D070D0D605F8A8A8A5F600D%0D070D075AFD6AFF84070D060D070D060D070D060D070D0684FD6DFF5A0D%070D070D070D070D070D5AFD70FFA97E2F2F070D062F2F7EA8FD5EFFFF%%EndDataendstreamendobj59 1 obj<< /Filter [ /FlateDecode ] /Length 63 1 R >> stream
+H‰ìWínÛÈ}‚yöG€­½ä|Ó
+p8œl€f×°³[‹ÂÐÆl*T‘Yî6}úž{g(Q–ÒÝýžP¡‡ŸsÎ¹wî}ñ‡ëÛ‹î~óóx¡.ëJ¼xÑoÇÅn³½ªx´z»Z==î¶4ôòæUÕÔ—5.êÞú»ráãöq¹Y_M§Ýû²«nwO÷ãz÷ªzù
+£ï—»Õˆñ[ÜñùçÍb{ÿöÃf}¹X¾š^‰gÄÅn¤ç|Ó¸ojSé+­ªëw¸ lžÖ÷ËõÇ°ùÏU¥ª¦j¤ÆîpêÛåÍøøüü¥r5]¤.µj,ì¥qVâò¸ùðô	Ÿu½Ý|ûÍj³}¼ªúÏ‹uõnñgÕßÆÕjóKV‹ÿ˜ª¹KËÕˆy}Zì*K“ìÞª;¾õ‡GÜƒÛé˜†ÝÝÛO¹w;|LŒÜ¼	ó×añò§›ñã’¹ÅÜÿþŠiµù¹·ãÃ"ãQW4aPúÖVqüÇâiµË/¬WáLã	¬¾ G¾Éâ5MÙ3š¿˜pÑÐ¿Ãe§Gt,Á®æ×\_Gz…Ìçm]iƒ³²\ßœ<ŸgLŸHÜ½?=¬ 6ëeõ¥©¬¢Ÿé¨\Ö³¢u¥šÊxY9ÛäsÇ/Ç_®ªï6ë1‹Õmw·Ëÿ’‘¤§=Þ<­ÆíëåÌHj3Óï6÷ã
+×îïM«7›ÿæÞ/¶Ç,·Y=íØö¾.§¾{úô—Åç‘ì¤ò¾×ï7?ò÷](g*eZb¿®måš¶jËKšJË™:åyt7Ý;=Ô)òû5ìõývùq¹¾bZØ5êîzñ0noÆ»«ƒ&¦ëbþ¾;ß‚±ê¢ÜJ†}³]ÞüêdåóOúÒÏövÚóì@Ôn7®³Ç‡õ}¿ùDŠ<R¼ÂØkx~µù˜Ïíù^÷ô'ÉßA¼ëírMß ¾{ªÂzvþÍvq¿Ä£‘?8(ÿTýõŸËÝXÝ`x±z%ÎŽ²[Ã½øIÔŒ×¢þ}[óEÈ1¨ôÌ¶ÀxFKøé
+£"c ?!oP€n`ø¦: ˆ&4}¡Iü‘”RZi¥¼le'ƒìe”ƒLøø(¥•QV9åU«:T¯¢„J˜O£¥VZk£­vÚëVwº×Q:a†Ò(£5ÎxÓš`zMÂŒ¥UÖXk½mm°½0ûFÀÕHÍÎ»Îõ.ºä¯¼ñÎ·>øèæ¢ZÓº¶kûv 3ª3ëº®ïRh‚.´¡©—½é]ß	ec ]zðCÂdÒÉ&—ÚRLIüVH)ø£ÇP‡§m2¸Páò&ÕC†!ý†nhñ 7ØÁà‘jC3Ô1Å!ÆØÇ»ØF/¢Ã[MÔQE	¾ë>õCû¾}×·½Ç§Y| î>´éëÂ"><„ð˜†ÓQAbZµèR7t³˜kÛyÌÙbæó—Ð¶nS;´œ0Ó¶Yð¤Á–gµO~ =XìÀ¥ Ô‚Xz%H®]rï] õ-pÁ8A$lTÛd¡S°óÖA;c5T”°Z-L2¤í!q¡=·Æ@z4¦Ö	†ˆ0F€=ZØÄÁ.¶Q°O£k•Ô OõðVy³Y˜NÃ|&¬e‚!#Œ`ÐFu°¬uLÜÈºI°u„Á¼ÞÂ÷`
+qÑ4z‰ÐÛ(P‚h³ˆ@¼¡€,üÕ
+_­ðÕ
+_­pb]½¸[*ŽÊfYúçnÅ‹»³çÂ£8®›yO=¾ëä,î1—<(—¦‚ç|ÔoPì¡ì)xŽË•ÎkÁ¤føÇ°†1mŠi—L}F©XX†D>©‘¡tÉèmg¸[`¸ŠÐ,^Þ¤ êƒŠ.4jÖ3±¦¤jä2„´%uIßÏ¥Š-0EoÚ•’…'Ô,? ›€lŠ2<Û"[ÃrñdØ"0	'‚£`™…Ë>ZŽãe@¼ôˆ—Ó˜Q9nzœCèÂÇ!|r åB•Šˆ¡ÀqÔ!Žæ‘¤ÄN³€êgAu+}­Yp¬eÙ¬Øk¥&yJ ÍƒmÂ…ÜtCáL3‹%9qjâÄtHK9)ÍY>føl6_LGçÒ>%ÍÄlN9iŸ•D&ó„É0KN®ÄŒzÆâ!IuÅþÌâ”ªæ,N	k²õÜÐ“•Uqñä_æ’Y<ºµ+QáO"BÏS•1{ „ØGC7‹Ï­ÃI40$'Î&÷>¹	áš÷'}Aî[¦.¦ÝÃÏàf°3”I”ýêò,Î´k9¢<g±:¸Ï·´upc€'{,˜îÚÄMÌÍ$­¦Øƒ‹-¼ì°Üz,º´k8Öb”X•Ï›ˆ•œÉC¼°%q¸›Þ…E½´õXäÑ£ (5˜·FÈ”_9áUT”V|èé]¨hC}*­MŸ@<‰J‰vD¡ásŠ Ì…™áéetW¤m@•’X:rå]…
+F£Ž1” (›¡²!>hjô‘ô¶È,r×”O#M]^Wú¼ˆ§P¯×p·§¹ß£G=_Ç]_Ä;Kß8IÝŸæþÏ!¶[â¡N}à€N°†-%/,)Á"5xh×ÌžÓò€î°†%²˜f`}³¶=«:i*‹š–u,*K7	gŠd$W{­H§†%Ò,ŽeqÚ"IBrÔ,‡*B8V eˆýYDŠ°Èy£Ã+{^`Þ ˆòµAÎqÈ>-²P€"ô™3ÿŒwñÚOIå'ŒŸò­ÅºÏ}†és<ƒeñŒæg$3Ç§Ÿã—Ù=Th¯…­œÿÿ?†ÄüF<Bÿan¶€m/xµ9€—{“·\©²I^ˆš¼ñrDÒÀ‹R,Ë;@5^Y`ëÖ~SRËp‚ò aš˜f˜’uWjÀ²,ñŠ’£-G]›/û°¤ßÿ.BIÁ´;îX<›+ï¹P0\Ñ¢‡üCsG/öû1ORâ0ˆÃaùÿœr9rÆçI‰’&ÙDq()­R‚E¨sÌwÜ	"ÀàÊ
+’×ÊÄŽp·ãÚ¿šÛ¿ˆh Æ¢ÃpÛWcu‰Ôï	–ˆæ~bÂS„3èŽÐl*²S{dÏ/4Û9‰y°fWº/ö¥“-íÆÔh</ æ%”+­ÞÔ1ÈCý$¨„â¹Û_ßÜø#´{tboóPÐðBÊE;’'¡¬Z§QYª{ÍéÔð[hó‚óê´–åì¹IH\ýPŽå,[Vµ)Ñž_ÙnÀT
+þ6_@úéU²#7rD¿ þ¡/ØKr3|ájøâ‹>Ð`0°¿_¼ˆŒLVWI-™uI­"™/ã-uõT~ª­ªóÊWòòƒàáÎ`ÁÏBà*´¢¦²vPÚ4H^´p1;Êœ	ÝÀ32Qîfž•Gi7Ù=eÜ{ó­ë‰ó»9Ã²W.EøáŽÓ•Â©yTs­Jcæhu>uvÕ9Áþòùz©9Ö¦%!u«ƒžè§òáÆDtÐ€_X†~¿ct˜¢&†ì©ö~'rÁ@óE;^KÝ­5…á¢/h8•ÝAï3;¸K˜8×6è+ýÂæq˜oÐºÔ=˜On™ÊLå³ÒgµÏŠŸUß”ßÕ?€þé©Ð
+qó<SoL¶°Ñ}í¦ÂNÛÔÑ2M´KJœ°©èYãöt¤9hJ•wçi^FÝÁìyTN;äÖLžÞÑOì3ßõÔuÏ%lg±\ž)(JUŠÝrlº%YÏ±¯b¬ÜS¬;n7 u*#•¦B«:d$Õã)©:¥J¤Ò3(µÊu=-&Î‡ûO}+30»õžÇšúsNó4¦½)F.Ü³q{7ryèòà$çÙkñ´1ÌƒhÅqÔäPæ±Ä%œÎží°²9µš8¯:±úg¡ïÙ¼vÎïñÈµâìÚ<aÖšWQÇŠS3«.ÙfµJ°ëîüjë<k•¯Ì·™swír¦Rp¦ášŠŽ×ð›Á²†`
+3qÖø9v7ÌÒ#qš,$y·*9MÖT¹YžA˜œsñAO±foàæ_ô¨V¢Á•H7¿léœ¾œiJ
+3†-Üº{JÈq¬ŽdI½‰¸Yh9ö:á‹Te4½ÔMluR«²Z/ø¡?Ý[d635z5vYôêÙ+“w—9Ÿ¸‚ŸÄ„m>Yw‘{”¹<2yT
+?;CËI/j—uÎa¬èzÍ~!@ªHÛ4°à“±i‰‹"3”…0à 5u«ˆ@ï®4^Ûž½[Âir™’ÂHM„§ßÖqâAuØí :# lÛŽ¨qa,ú=}Ìÿ|ûºy#yj˜î–©{a ÂDU5H˜©b¨j[U›«Úbå“·Vf‹§Pâ(f!p1°ºIB-å Ý $Äa©Ž®‘Ï;i¨¨¨­tš€’QXn¢à‚@ô.½Ôœh6Dü»õ.»¾éÒ)Õ¡ÖŒ¡VL¹F¼Î‡.Cu6'V¢òD1êš0VÔÑ©iÈ‰´¥j,•¢ô‚í‚ËÚ<ž.Ç,ˆT4ó‡©ÇÔÑÓ=hc,·^»¾^ï×§tÇù…‘[hè,ÍŽê.Õå%Õ)m;lWK¯¯×ûõÂàÌkì511†©QUVÐv¶¨ÔghÛtßºv}¹Þm—:L¡/ºNùD#Ú+&têS.šÕStãºr}µÞ»è5ÓçNL‡ƒç.bgÈmÙD´«.P:‚³(CÀÑ*B$ŽÀ`aó­õ)ZÞD³w¶Ùš<Y{Ù[ïëv	jí\£‘c´°‹Þìšõl‰^Ñ¥–ýAoNö&÷eŽŽ˜ã­=oq½Å÷VÎ×¼¯àpí•®-p1Á´ÁTÅâƒá„)ž=-$#‚†jxÙqHå/œÀôz%ê³~ãÉÑÑËØä·@­`–s¼¬ÕFeªÊ8”2F¡†'þ¨ÀÉÐ80Rá’QÉ˜"Gã+áCž¦ã[ùã?¢éh¹°ç¹á¥Ý¹ÙcŠ…‹(P,žX89#˜ –H¤d’$¨BÝÚk8¾:8ˆ›È&öó$aïþs'™¯þs%ÅÙÏÌ/¹T†#MÏXceWÃ€s¹ì˜ív,î,Œ<zF
+_¢:–èógÁ~§ˆaªmú–Ä(›oÉ- Î$êN—Ã™D:Û=¡-.k¾·ØRç)­Îiyé¾l]µåµ’ØÚ²ôÚö<M¢náª¶°VË/àò% <+˜æ[¼LŽD[-þÙòçÒõûâmé772ø—êºÛ™×¶§ûº_*õ×SGÇ¥S‘UßT¨µÔlÕnªO¤öÐ
+‹êýÀR ¢3³TçV¯Qs©L|½h1{)5;êÆ-<jÖA‘éL˜#X*¿›€Jél9úœË¸ô¶RÒw¬ýT±l-- Œ,HQÝÁŠ\è6¦îïÄ“ºŒ¤šè?FÐ,mÉÂNXÎØ}Þ÷û]|›{Þ7fÛJ¾I|'+·`Ë·¥ƒpGšò$¬®ü /oÜ™'zó‰î|-ôíåÍå­acRíËöÄÅvòfl+y#y¶‰¼n@Æ\-Þ–Éø:FU%Rq©.ª­ªÌÏŽ.ZÁ~ÚªZI¹fÖTÕÈ÷		p¨bWWI±šË+êt¢Ì…¶‹sææÌ¹{Í¤¡É©hBÊþý½~	I¶5­á± ¨)›ØJÈ·JÈ{Jyþj£’%7guÑwf)¿‹ù]ÎCÐ¡æ#£¦+úÄ©4Mõå…§:hïâ®ò®ß?¸*Uø]ÔzSäUæïBßÞÄ¾ÈýÌóv“|?G8:‚sb–¬õHS‡ší‰Sû¥æK­×L×¥ž«¡ßR·¥^NK3Y³,Ú+ÇD•á‘]•yªâ¨ÜOiû%ìÔüÒK½vRÚnmvå¥¤˜)ôúdÄº»©›ŸzpTÙSM>Ì˜©ŒÕÉ¦Vç|ˆªÏx9ç~ÀCà®›¡ò’ðT¹ÖðUK¸«Gg5ºn‹%>ëî·Üs¹æçªÝWq`^â–`scPjy¨ù¡¦‡­ÄÿBÇÀ¦2RUJ]í%ÚãžlFMÆ†Ï‘Ñjb eˆ²Œ*Ì^?&ØƒYö¤¬Ú>¬×E§'·$ŠÊÏH	š(C3¥h‘OÜ6—]Õ¥ƒÚtš S£3‹¤±ŽÎñe’Ì¢<Q½f¡„-¡ÐUz¥Ö2í7HLµ;*wO¥3ýh¡yBÙ›)}6þØÜŽ”Î/|‹ƒÙSÒõXØÑë<p¼/P‰žŸ_I¤„3±¢5{:ï<¡Ž[G‰I¦c5c¼@²a›ÆNm@ƒÚafN¯	3º °MÛ@²¼g¢¥pôxÕ€Ÿ˜Y º¡O‡:hqƒóß#ïˆ¯Ì ë•àìØñ	µntRÄÒƒ`ÐŒrõÒYÞî'ëâyêüÕNäîEÂˆŸ3¼f§ƒd&ÞgzÆ¹_qË”NøˆÖaüfrÄ´j2Ò´¤ù	‰Š	«E$ÐÆØMí\pº3V5R5Nw”jŒ*„	|jt*l©q!*J@"ˆÜñ¨Ñ¨±¨¨a ( ƒâ¬þ!Í§ÔûÖ|B‡ùs™ñÑ4ý‚<1ác‹èG7oÝÛÐ¼Éôþ¿ËO?ÿðýÛ¿ñîná]ÃÔé#Æ!é]í4ê¿ L=>z{b×L³Ý<åÝ?x?ßÝÛ×]*P×o~;ÅcpÏÔZÚ~|›ªÿÈÍ·ãàc²§+n±.xìßoøûn×7¿Yµ,þGŸâ¹Oÿ“ëm»AŸéáGê[…·]è ÿ˜ì¿µ-ÏýÁÛ­SÓ¬œlsKâ·1e
+ñØ¶Ü#÷o·uU“¾÷N¼o;ä§õ¯ÃÏç—Ïù×/ŸÿõËìÛ¯¿ýþ%ÿêOoøÛ?ÿûËÅ>Ð,4÷3Æ$5ß—F§éo•H`C–äwR}“m©cª}Mïq¦~Üë†È{¬ÁëC++–bøFXÛ;ò­‡>{ø‹ÇËã’käõ¬¯Ú3ÈÓwÿ%_ùÏ6â¶VùÐ†žWÿ¬äÝ/(É¹åØÙ$ÙE9dù½0?‘f¡6O!Ì”å¯Z¨Wò¬y–ZŸÃ@™<ï$ú.Òw™6¡>ÄuºVêlŸ–ö©v‘ì,Ú‡åÊýh¢m”Ix
+5¹7#µ‹[îÚMõa°ÍZã‰î¨w÷Òæ¢ÍA›{Î¾~Ù¼²údsÈÙ›/6?L'L#¬KUã¯OÖë<®ãbÌÑ DåÔH—Xè¸ÆIm×‰Nh9=1˜Á§?¼ôºr•%WÕEõï*} ÔAb¥pÚUpp‰´8ø×…èÃ†\³\ó5]#¾—ð’‹h°¾ëÝ±þ;š±»;MØ·¦‚‰ïÂ†ôsC«Aß&tp@/{ô´EÔr¢ß;ú¾ñe(	ðhÈi‘/tè 0ÿc¿lvå6® üýwc Ùìf“ì6¼aóÇÈÖYfaØh#I€¼~êÔén6É¹÷J–¬Ü ™Xòh†äu¾ªJxœVïˆøÜãÉ[”Æ7s…4$!‘Ìñx¬ƒ˜¤Nî¸ñ+žs¢à"¤7A„åØC˜ø]Øå	A´Ä;CÆbž jé"w»àŽ§¹²o%œ+²YÀ†±(Rlz, €
+2îxô¢œ«%•2bEð9,Ý€åóXA‡e´€à.BÁ‚."c,l”sbõd‰,4°`°Ù H(rƒ,¥&Yü
+\ N.G¼¼z Â¼]ôˆˆò¡‚ßÜÎLà€\ÈÓƒA$²0aQ˜<Ê•…SÚìfEYviUè#H&ç/É4âÙ©,‚ÔJÙ7<#²P €ÛgåÖð7ËO‘R(ç#?õ…DÍs¡êÂ‘u' a™À¹†‘á†ù’%äÈÖè]}‰ðKMøÞÔô2ÖvT°RÂJ+¼/Ä/eL™Oê›ÚÉ´•±—eþ«h9k}@@KšxºAà#›!ñI®j4±Ë'ÞÓ ŠEH‹“·€DârGH ’ø@o EÁ?ÐOæñ…öBzáüNÂÝ…ì3™.8wÄ¸ \ñ­èFó2ä¶2;ßŠé!÷]A3¡L“Íò¤KOÂ¸;UB!by­Í,÷1õ¯T·¨JÑÂK95ö€ÃoÅ€@^yg2¤ß˜¯²\as·+<_ãíJõ
+Óeæ‡on3úK¾u›±oz=ZkFÇ%¦|fùšØ.. ‹ëE°\\Ña7Å1“˜¨x©,Ú+°xð_öxôø%äÈå+,4NP0¸Ç2v&ÂhÈ*¸[á¶|ƒL>1œp‰£’^Èˆ‡¹’‰I˜ŽÜJBÓ`0ƒü+ì³„…PO6òàÝÁ:RŽ]Ð6ì»ðL8&Sr­DÕL4…&£3N–—½»ôžsº%tE”© ätkBM5¥*¹JVU~•ÄÚ“À•bæ]sx=âk¦ØHŠi†ùßö.©t¼O›©.p¦ÿé_È_˜¿fÔÏâC[ Ì…ô}ÓowUñò9QædÖ`™çcÌãÃSŒa„9˜S|9…—6º0¸äÜr¤–`rh©‘¥–WJXÑ¨RrŠ¦Í(šP4Ÿt†ñDÃ‰F“©Æ—É–wo>+ýu­_õ~W}î{÷Jx/“ÓmÂm¸%&/Ë±2×I·Yn³cšM;Ï~û±÷—3\vúÛø2å¦ëí=RÌ”SÌüJŠ)½5äÃæjJŒáé·ÿ¼ÿša³m²®É/%½Ì’^Ò‘[rj)‰¥¤•@zk«Õ^»å^+Í¶¤³ÝJ/†åöZoµàº\pKÅ¹â&è|¥îL<ÚsµéŽæVuµìî·²‹º‹›ž“ãßÐžðËýþ°q|Ò.õÔ=YL÷äžúð-n£Ãßñù¿šo~úèÏ§Ê±­ò¡±íg;~vèž¦á[‡ÇÜü#¿À£#"Ê‡:'—ã¦AþèzyÏå7§ —Šû?è×Áëã\¿ïë8sZÍ7ó_†Ÿ¶ï~øÇÏïÞÿúá_úFúõïï?”·¾{úÓ?¤§~ÿá—ßþýgsú?üžñ)½Ã è}“!ïãš±uºSÆl³[“ÒJ+Áj¬ÑzDuˆjÅÔ‘ÔèÙÔÔz&%1µ1µ[Ó\3n®ù…ûB}E>Ÿq_`_P¯ /˜WÈgÄ“ï »Á.	ÜT »b]
+æÄ@%aÊ2I­ÌP17HéŽ–é©d'Iƒal²M+\ØcÍ¥jÿ;rÀÚT>ÍL ‡ÿ?nyNÓí=~Ö¼~À×^ûyLÓGc8M+ØCÆþñ˜\e®3žfªêÄ‡ŒvŸ\}ÆzÀó’]ª»,TSŠÌ«÷è£ïžžÂÜîÚåŽA
+&£Ú¢š¢Z¢¢Ú¡š¡¯Fs^«ºš~'“Ão*Æ—mOMO-OOÝN½NN}N]N=Nn748µ75·@gS_SW³ÕÑÔÏÔÍÔËÔÉ\q±i2ô0u0úWv/õ®´`ÆŒÄ¸€ TÐ!I:`Å.#ì/ iÎ Îìlq7ØC‹8ÚƒGâé:E0*U+ˆµcW-øÕ#× Ù„œÁ¶„Ü»‚t;â’÷z¸ú 
+NA9‚Š	t\ÁÈ+o¨{s A'p4‚§	\]±a;¢”m{pw ¥æFöÖ…ë·JÁqEj]´Cô_E4×`úE^Ÿ~ÀéïÔY^ûÀ§Î<à%þ›à³æÕB
+¶d·ï$Ç“â¨·:Jø•p¡ËëÌÍ$êT•º™“XG
+U¥:çŠÙÆ	µl2JÔaÀqþy â¿Sæ>wX ®<ô¹¹¶£;#ßŸ™g’©±¦D›XN¨×7ñ+åêóWë·ŽáóâÚúfýdùd"}ÄÓ)º±JºJÜá¥Úèa-í+àÏû­ÛÍý®¯ï!^a÷ãabæ‹ôëãá¾fJí½ö\PÞÜêmq²ÖÃ¿&xW‚oíð¬~%MM¬
+FõÀ¦ÐÉÄ£Ä¡Ýi¢3-l]†$v$f$V¤F¤6$&$$$ö#æ“­Gç°ÃtÄrJÌ¦‡ÑˆÍÌ´˜þ¢î¢Þ¢ÎB_1°1•‰†"v²ÓJÄH&¸ˆzˆ8ˆúGÙåÖ;l³£ÉÊ>ëzÉ#q¯‡7‡Î¯À?tþ'H2€+[&‹re"N<C°eàÝµ”ßÂ¸TÄõ(‰-=ÑÕ¦¸æ®¡k-‹^ë"ÊÆ%WÆK£gm´X6Ç5wÇÈö8æþèØ wvÈ…-2bó&6IÏ.iÑ°vÀ^êdb¡&wJ¯­L{åR›åT»¥Ëír«ý2æ†9”Ž9v†5s•¢‰lÙ4GvÍ>·Í=÷ÍÄÆrçôÚ:Qö´w.¹y“Ë§×ú‰¨tÉ4h	Elï›zî Ú@µB
+Z>O-#»¦4LK)4Á¡2£t›³[¾à¶&‡‚±FƒÚéoãžóü?‡=‘è‰Å'=<¿q)¶Üv®{[-PV ,A‰9åÊeš cj¸ºÆ«c–­VWM2²ùWøzõÁ47ø<¡¹½gå:Ú|W’]äYÔ€UÕëÇÐ-ˆ/úzþ€%•˜¨+åÌ#tŠmòÉ±ÇÂJqeå	^ž˜Þ¡çEh™e­‚,–àÊâBV`*Qpê †L
+à‘‹:<
+à{:næqÐFX³3B™	„¾txtB–Hªx!
+q²%Áˆ@D" >ø!ôv9„Ðd Ä…ÀBP¡ PL($
+"N€xD÷&jæÿ€o?ÚüÑ¤[P–ÙÞ3Ë·¡}…žv|ÒB^=d6À&ˆ.B|	\!ÅÅÀB˜=ä9@¦“Z#3ý"©•èžë#”ží7†{íðG¸j`ÈOpÚU‚¾AÉ°°à;$ybâŸ™ù×œúmÎý“`öOLÿó¿eð¥„Ü–¦¸¦	v„½_±ý;CñH$#{A!»Áwƒz`sArEˆ¹$¬Z²4…à	l‰}aCcèØz¶†q™xsuXYº\|-ñT!ºì6ê5SöÈâ»¡#^ëéœ*Üb¨Á
+P¨
+Tª„C‡.zxcŠxY/*â‘>B"óÉjÈZ8)a:d`ê UBÑÂVó‡«ùÃ7ù)'(SæQ2OU“½HhÇß¦oÆ5S(óõÁþÿ~ñR
+ÏäÖù2”Déè‹ùÐhf¯QÝqú<ž3ä9Sž'æ™uL™e–Ë¬æú™Ó˜—ÿùÕ¹Îä¿lç‹¦ðßùzõ€GØxû}`’á]S·Úè>>Þ£Ô˜Svgtßjx9¾ð„ìð€70o7gÐ3€¢#hêAUºv‚Ø€ÛØß À±–Ìºƒp6ðz·gð;€ã#xîÁu¾wØ÷_@}dÿ$ý°[pì ;XºÂ0›@@á&ž}À"zï îÊV0Ã›Á Gê¥ŒaAXaY‰%!°&,
+ŽUagYXXþÃ~ùôÆäPüð;ô%ÀÌÅP•TRièï`ÎÙ=Í!ÖF``Æ»H²ßÉGVIên©Ûžìž,vÒ®.IE>ò÷Z1<ƒ‡g˜áø†¶ŒÄƒ´†y(Å>p?1ÂBt0ÙˆÒŒÄlV¢Ïf¢ÞÚ‰ùØP€ ‹8¤Ip9'R„‹¨÷ƒŽþx8–¶7ÛlØ\‰k›^‹e}“Þ°ÑÙÛ Õ&{/ws“õ”õ2œSŠ–®os¶•îC›™¹IÄ´@Û®rhS÷hNš>ZÞ„™ MbÛ&ÎEOÚ'r›X7‰Ô"~PƒxS{ˆ½©=ì4étÑ´=\oû­ÍAz¡9œ·‡¥9ÜÛÐdp“µmÚ"b®)>ž­+¹¬ß½æ»×\¼f¿sEO\'Á·§‚Ãì3wò§Àÿ/
+Yü‘>|ºoqÿMÊ.Ô­,ôm……ºkâj¿ãeØ)r-¥¿ñ½Ê–Ø’zµÓñ2}&‚>³ýÄ_«õãì­À÷¹º+ÙÜµõI……Uy_Ôíµº§s8ÐºˆëuEZ·ÞòæRÞ±éC÷[ø4½<þúõóãóÓËwý úòü’>úåôÓß¿þëßÏÿüüÇéã^¾=}ÿ™.>áÃ©ä"y#[ÐÅ1[\›âû7ÆÍiçžû£µ9¸YXoxß‹Ýh+·^óA»Ïr÷3]yÂ×óÃAC@DfˆKŠXsÄ–$–Xh‚y‚(¤`¨ S$ªH\‘ÈBÙ"Ñ…ò…ƒ3456789:;<"Œ‰°‡Ð‡ð‡ˆ#ã "("0"8"@"H"P"X"`RNOPJ@Š`ŠDXá p¨e¹ô —£©›ËVQ¥ ütsêÞÝ^ÐþŸnÆÕ[½õ	wƒŽ_`'úý üb<ˆ+ÙïùÞ]áÇß”ÿêåÖAÛÿnâM×xÂ¶áÕ7ú?>áþÙ’Âé~5ø¡¿Á?	ýgø¿ÄÿµØZ€Å,6€ ™X¼ »˜d’!H–@MÙ3j`Èü:õêààÔ+xôÛ
+ýW¾Ð /·°úµX‡‘ÐÆg8ñâ"<º}/Ð|8ŠW!¾¢Ã¬è15F„L™&3±Õ(`7,‡‡í(a=4"ww'¸Š|~¬àžó7¤£Un"‘Ûmd0jK,&_ö9Êoµ†žŠv(òÖÓì’Ó5¼7 ëx£kwHÈtƒÙî'â°w†),ÇÚóÓ]È_€¶ k¹¤F°ß¸	«°•µ’¿ˆ‘’¾ªš§,yob¯³Øû$tÈÜ«Ä¡ïhÚ†ªMÑªæš å"	OÐ®ƒj+èµN;èS”9CŽœÈ«c@'jg>2ÇYqÿ©¹=D&ÌŽIs`æœº¹/˜B=óhÅ\Zsëˆ—CëÀð:õ3µc¨-nCn$æÝŽ¹wd<˜Ç‚iØ3îQ·Š–y¹gnžÆy*¤=wOiŒ!°á6Ò’FŒ ñ`tau¥ö…â¹OJ{€sä.!ƒažù[ã<ÌýÜ1Gîo5È¿ëFùJøk¾WºÛó#	î)³}¹¢ûq2Ý7ºOlŸÈ>Ö'¨/L¯D¯<¯4_qU%–ŸŒã;CøÚðÝº+¶+²G¯ºpz@æ ¼ŒW€pøæ@Û-øºE—\ˆ®.ˆuâê¸J;®ÖÈU[sýV<¶<WsÁG?ñH¸Ì;.÷È_sñW,Ïb(8I‹c`‘t,—H¬›šõS±’<+ªà\N¬°uÖ±Þ"ë®fõU,CÏr,8ßËs`™v,×È²­Y¾ËØ³ -8‘¬q>mV|‹¡PÛ(ð4gCC;º2ho_‹ãXÖ¦ÉépK4þbíµÅ«=þò®ç#dÃ‹ «wºœJ—îÌ'º1Ê+q8þÈšöyÏÅƒÛÑÕC_6Š–ˆKåµ¬šTÀ¯BƒÔTl#˜§ŸÈÕ€XÙ•@'‡çŸ!¿òS¶à¯,&LV‚ÑœIQÄ¨rAöM¶æ{“Ó­@^ô)lÈòTŠDU¤"SªHUÄê!VGÐë ƒ)wÑ®¨wÑ¯*xÛŠŠEÇªäV^UÕ,zVEë%ºvP‰h[Ô­ú…‹Æh\U^»´Ä=™ v‘»
+¾@ŠèEö*|‘¾Š_¯pBŒèÒzôƒŽÐÚ³ŠZÕÑòŒ»~Çå6“ ²É%¹”äS§RPZÀ	£	ñ‰9gÒÂ“’8àˆ HQ QüøA‰;„9@ÄƒVqC`CP£ƒ…ÐPÌ°B‰/”.”-”,”+@dP‘b2ž(3O,4±°„„pDo!q?,1Œ£R„†Vo¦ªP®`² ÀEÀÐˆ9Z	L
+‡l®À¶öjÊöÊe{Ue{ÕlìÕ°Ø«Å\-Öj1V‹©Z•™)sQÞÐÎ‰Ì0Ec89rå¸o"G/‡/8W"šIƒ‚$CÓ!	IyÑÌHn”ô$CJ{’'%>a>¥>Î™‘ŸdNéOòˆS(¯/ï"y”LöLJ#ò©•œJV¹³ In—ìJ~5ÃÈ1i’-½KjƒeµÉylp Ž@Ç7&Zä~‹¬ÈÏx{y-#ù:Ã;C¾3$2$'/X©¦bV¬ƒ5$T92Þ¡#ÖÕ9ñ–zM>aµæ_+@k@ª @N˜»—‡ÐtÂÍ¨ŒiUV„±òàêÐÚÐÊºðwÔ„ˆé¢"^W;Õ ¥@7jáZ%œ×A\¡
+¶5°­€%ÿK¤°* Hhd•j¡6àÌäÿ?Ç†·]n”mÎžÕIDA#RX“àÀªt8¤‰ŒÌgØËÔ|Ð-ø "Q&q€À .‰¬×õ+Íº0:>‘©«–8ÑRä	STJ.aW•T;°â¦0ƒXW’0‹\|Ü¹L‚Ð„±ìm(ë@ŽÆ½ˆ #SXæpe38ÍßÎf/&¯$_¦.å±[ç‰+3wHóØPh9¨õ«ò¡¶ñðÞà]\V ÏÕÙÉ!=²ÃÜq¸®ô­WÐoü¥® €8`@ /ó>à¸;;`Ÿ¸1 RøQðQèQài´£¤³­7¸Q°IÇ:Ú¡:™tž	…\f¶ø5Æ7N+r¬@&¨¤‘(A ‘Ò(²!ãe…$ËÌ’k’œ pQ,@E œ˜	,¡€ŠŠl˜À¸¢3|ˆ`Aˆ )%ÎPb°Œ€—ÞB "¸¢íT ¯|ÂPÆ§Î2w0yÜ1åÙ³>Ífúä¹“gÎ ìIdêD˜Ô Æ
+ôèua)£ŒÀÍèÙÚDj€¥ˆZ³8éE„!5Acø¶³aÁ¾2°”YŽÁÌùŽro#¬}ë«¡ø
+îu a¤éPì=ð½µáÖ í:JiCÎ‰ Lº	$0 u6ó"üCÍ¥à8üNÅCá›p*øy=ÿj+'¿Š¢lOŽÿQŸŠ“?…âÄƒH¾ó‘>|zÕwúorç¢,¬üreÃKx)–á;Ky
+Í÷’ju—×|KïÃmLžÄµõú.=P5ï¹Üá¾õºwÑÈcÔX«òPñO,¬*>…r½ó=«±oä¶‰%…Ý[®}Î¼lx¼ŒwêGúÐý>M/¿~ýüøüôò]?èŸ¾<¿¤~9ýô——Ï>=ž¾ØG'÷3]û‡Ð?r‘¼;ŽwÇaŽ£ÈƒËã¬-,Ÿp9:ý_þkþÿ_+Õúj­ÖR¬!+§æhô…Ú“Q‘,Y8½<X[ñ'€¿ƒ Ö@¨'°Ð¨<dDä2U £ îÈ‹ $E¤Þ0iT•Ò%ÜÒƒš„›„œ‚ÑScÕ‚¢:TXÁS3¨J¸Ê­<Á
+d	f Vm¸\-°K£G(â
+„Mæ~ yË9Q¯˜•€3Á3½j#á°¦Á:€†=Öùè3ìÃÝœmVä·f?£?Zà&\@ÐP$¸°à(#Uh€ƒ%žüG×ÿ%½\v#9Ž(úñÜ°7D=²^†7õ4¼6¼òB0AsaûÿáÈ{#¢²ª»©1Ýh$ŠVeDÜ<ç÷ðN„rEÂ ¼â a(<90S`fÀAôA€ÿ2üý®à§èÇiýeþkIzª/êd»‚îráå g­÷’Ç/Yñö‡giEFGgB§Ø%Bîôçã¦ËsòIËgõº|¤ø÷øþP<UqJw{:§eò²¡±ñ”å¶ç“Åóà0Ð€»óZ5O«}QÉJXª.ª/j°Qeê-¨µH>¦ßÎ<G`1Ø2S.a˜ãp´8D ÂWKD:b%&Š9[ÅÞBq´PœÃˆnµ%akI‹”É%Âï°#AèYÚ]óE†à†ã~ãÝóÎU-[á5c Ë©4)|fqŠÍdŒé
+“©fN‰q…qÑrMÍV¸Ë|sj‹K‹+Ë c¨#F;Æ;A<§¨¸¦¸¤´Î>A?[¡'J@£1Ð©&.&®%KÐóð
+Ô¾Êiò
+Ô¾Êiò
+Ô¾Êiò
+Ô¾Êiò
+Ô~„Ó\ñþ,x‹	oÂâÅÍKÜ?	ï×â¼'‰c™¼ã½7Á%N„p  ^5CbHÀ¶8›ç“«Â)äÁv¯8°Å ‡ 4õH	‡ØrlT8Ìº#Vò¡.b';!wœo÷âCðœk;kžöfdÌ#ŸìØ„`'vú­u ¶.Ö‰Íbv	ädÌ¢ÛkwW©K”%ÍÄ5)‡K•ÂŽ4JÄ’jt£û¶ýÐ®É'RtD,”ÛÖy€K|+6NwNbébíbñ\‘ÊÝ;·Ï÷¯Ü@\±%ìlDkJ.â¹ŠwiªÑ€ §‚º ”’œÆ‚œ	f»Lô;äO§ÜXåÕ'¾C‚UNJ99%Å:ÒA-“Õíª“Ë]WNÝþŠñ>G<9)ïò¬<uEÎŽB°ZZœ=JÖ£†i©¹Eäõcù“_,DË­Ÿ-LGÔÞB5HFk.,ünÏ•WÅ›mïGÛ{Û|,~Šåo–,,HUÎXˆA,‘–(‡¶äN¼ïY4(4|’O¡€¹¦D.E;¤HµÈ¬(^äfän´Ã*1=¢ ¹"¹$Q“\”\•(KÐ%P}‰Æ´‰&Õ£8Q(Où×S ¨P”¨|Ê©V ÊB5¯‹˜UÑ«rc²[åK ¶^ß<¿ÑÍÊ¢•?Y¶r3³på«){eÂQÂ½[ŠÓx^ûŽ>(… þ·hobŸ@é+¨ü Œ7ÀïØ=·`6»[“«1 &N;H7†Ð h£ç5È¹6fîŒ™IÌ«FèžÑÙ«5Y[½´;ÍÚAg`Òv-z²›Â¡SZëNµÕ†ö á=iˆ/ç›û¡]kÔ·54‰9[cÆ8a)¦‹³µÆ\q¨RÇiå(ILRŠ)âå	âøpxRÆæŠC7OšÃ’èGìè©F.E¥F3£c5|Øˆ•¡Ec” ¡ÁDˆ[.2Ä(Õ	3¢ÆŒ(üôC£ÁA‰zä‚”ë0Mbpéïô½5_"–ÑC6â›ÃÑnÅdl >Æ;JÏA€†E>\ÂÔðC°$d:r@g^õÃ$ž³hÓˆßVÛ_ßYŽ¤¥sYN¦Ï¦Oç9Ÿ)¢p*FtÃªC*–ƒÝ“9Ý°Ú¿3©÷A•ë¤>Ì)Ãmµ`c¨yœM–c9År‚åôDdFhåÀÊa•SžP«ÝÖÇýž&vO¯ê;ÍœSrÃrÏÑÁ¹¡x–WiI–™ÄA0(QÀ?gSRWA\7æ’gÐu¢ZÀÛ#Í8g‘±H‚úœ¸5ÆS–gØžOÏCŽÂeðô¢~q©·/ÊAiA
+|(¡ÂAƒØQ¦Ñd-’é·3äØD¶Ce@&ÆáLšW1yuUb÷WKv‹1GÅ9®³ÍÐŽ—ZmIØZâr“¸ß–¿ÃŽ¡giwÍMn€µ±Dæ1;/ofiîi£’@&H[5¶|dmËŸ01+VŒ¸°‘ *ràCÊunQV™@-tºN#P_H²ÚÁ(©w<*^Æ!jEÏTOIó€îQø\ùLúÄ¼ÏÌ/ÜOíÀFýs¤šB÷Ð@A)\06ÜÃi„9)„ª„h@¼ÊÝW3Ö»°Ja¬û_M…­î…«Ž!ª¦©&©«ÀQOCu?¥žn:š˜¦BK)¥®;&¤bFêž³†ãÐp’¹ÅÆ•f2™é 1Pè‹ª‹èžÍ–¢’ '5”d‡†,ðŽ¦ÑÁ&²"TWÂ[Lx/n^âþIx¿ïØà=YfòŽ÷Þ—øb¾Ç"^Œá~=Ž$-°5lŒYhƒyFL
+]gÛdG7„ vø{¨ˆDxo‰Ò±“LSÅÎpç\ÛY¦Š›©âlì7žŽ(vú­u ¶.Ö	SÂpÁ°AfÑíÎµ»‹¹ÃÔé‘7š5ˆ™“Ã%‹†ŠJŽ±$is„X|¬¶o÷mû¡]“û²»vD,”ÛÖy€K|+6NwNbébíbñtõ°yåîÛçûWn N®Øv6¢µ%ñ\ÅXFÛÅJq*¨J)YÀi`,ˆÀ™`¶ËD¿C^ðTpÊU^}â;$Xå¤”“SR<¡#ÝÔ2QÝ®:¹ÜuåÔí¯ïsÄ““ò.ÏúÈSWäì(«¥ÅÙ£d=j˜‘š[Ä@^ÿ1–?!`ñÅB´ÜúÙÂt´@í-T€¤a´æÂÂï¶ð\yU¼Ùö~´½·ÍÇâ§XþÖ`É"ÀB€TåŒ…(¤Á‰`y€rh+AîÄ;ðžUAƒrAÃç ù:Ñ ‘+ÑhJäR´CŠT‹ÌŠRáEnFîF;Ü¨Ó#
+’+’K5ÉEÉU‰²]µÐ—hL›hR80ŠÕ‰ò”=Š
+E‰Ê§L‘j5ºÐ©,TóºˆY½*7&»U°`ëõÍóMÐ¬,Zù“e+73W¾šH°W&%Ük±¥8çµïèƒR*à‹öö ö	”¾‚ÊÀxüî€Ý#p{f±k°5¹zjâ´ƒtc€6z^ƒœkcæÎ˜™Ä¼j„îé½Z“µÕK»Ó¬t&m×¢'»é!:¥µîT«QÝihÞ“†ø¢q¾i°:ÑµF}‹QÓA“˜³5fŒ–bº8[kÌ‡*Å@qœVŽ’Ä$¥˜"ÎPž Ž‡'Åà`lJú‡TïzLoÕûd4SÒ?šiÔêÙè×´š·®zÓõÎ?õ7ùéçÿñ§–ëïÑŽà{ðß§¾Êß[U-þkýcÐ†ùÏã{¥¯|þÆ/þ<~÷?m×¾OmÓá=ý'¿ò®Íÿù®Í—Þõ+ÝD/—M~šÿÚý¼|ûË¿~ùöÛ÷ÿðË÷_ûð/ýéíÿøøåŸß¿½ýj_z«§?ÊÓ¯¾ÕoíÛòY©Ët5Nrjt^óCÕýí`ú'AqŠKXàNœpC–yQ™!¸ccDG„Ò­ÂEØ€åb„AÂ(™Ìð˜JB¶bAeÑÂj-b:362"nrà°OŽÖ.9ƒ¯~gâ‚Æ=ßEùàß\~«Ñj¯²æ¨åE­Oj;KÊÿÀüààÀ]\[È³{ìß`=,»¸¡“ì¥w“ýLbçØÃk4v²« 7wµç:¬ÍD—­níŠ`¿µãÃò¶Oæ_‹Õ
+$Û0,ŽËØ×Z%Iþé¬Ø”!j,j*fÇ'èZ+…ó¬-jQÇç%_@§f\È nó¾;{çÝ»÷o.{(háJ.ÛØ H–³3PbI§XÔ‡~J4ô±¥­¿·­¾²³ÞÝè­í=|mqÙfoõÙì6Ò ý–hyÙø{/FáIÉÃ¦* ÕëzÈÍ¢[?‰WínuúPÔh55µˆ±?gi5ØLNK<â‘ËOcåÒ‘ÄF®‹Áë‹ñãŽ6†^sQË­VûxÖ”µuœõê@½äá¹SÊÊ³Ró¨ Ý+H'®Fÿâj; ·LçŠÞ³Bø¨8ÞkÐ'Ä¬tµzÔ¡è¾­ù³(ÑOJöƒ u;M«Q«eeÊÞáWÂ¬Ì—…a@fw yÖ¼v5+“+)êoTfÌî1‹"äù/ûÕ’9ŽO€;x;;IEi©u ¾ÿbþ¤”ílW/zÞ8ãUu—Ê$@ "Pü=5HÇD§°gtƒ•‡ÿŒŒ48Ž>¦/=°¹\!ºÀFœÙ¬é(k#,ùi&ˆcÇÌ¤Â`µÍüþ™Ÿ5çWH˜$m,ŸPgÁ5ôè*¤ýðÛ©ßNývêŸîT“8ÕàÐà˜Á×|AKûÏ=¦üÝ-‹½ÿë>Æ}ä·CÐ‡\Çð„Zi’ê¯?ôÝpùÛ²›Ç»º&ûýøþ(™OÁløss|ÆÜ¬öû6Øzûêï³G´œ6Ë³QÄ¢=ŠOì›øf.q,Ž*®ß|ÿ,É,æd§Vñx±ÿ]ñŠCñ‰cñ‰!Q.q/þðîï^°õû£'Ç[.1qKQq¿¹ùš»äwÚäèÄæ³Ë6-3ëXõñ¹G¹;9w™]ZS¢¤¸U£VNYæËs¾²âž¥¨®)fHV›”T¾˜Š–SÒ˜JRMÖTÞ?ÝZïªµôH±µøU<¤×CÏ}ô'nÜ“–v'&[ULªÇ§“fUÉ¢ðA_3tu[ØÃ¢„3œT2=÷ˆ¯™ Ž3s…€îÔ8Ÿ(gbhë&hò}^¡Õ;tûÄXô žƒÂOÐúÂÏÞ¤ÃéÇãùtÄ|H]zL=(š«NVìÒ‘=ÁK(Ûzr=»^qüŽBÜ£IŽò¯Q¯²¦ëØ…¢ná­.½›ç®±ÛÕûéŸÈ[æ{*uí®¸-ÖÕÊ…·¯‡¬§nBŒô€ÁQn{4B;ãöèŽmÁHuÝ˜á¹uŽ¥kxÃB>°œO(K1áŽ‹îUìóãˆºá±çÒ›†ÀŽŽG<•à€Î§PLbNà²•sm³ÓÏ_·¤%_Ä®— uÉX5Uµij•¢¶¯ù©IO—ÔtÍK¦N%(ÉCBª¹¨Æ yÒñû¢®¨0õW’$,YÈÊ{6âPåÁ?I%ÝÙ›ó<# #&¨[Ù;ía8uH<ÅQû<°ã¾=êëˆ0vt†êÍ¡AôÔUÇÐkýôóiZÅ[h¡Ô0ªe4Óèh{­<c”âÍ=Ò?Ù@VÙšÈƒôWYd ‘ôR¼¤ºÉŽn2^ÝäfR[ØZIœG.>Ò\$=$-¤ÙÇjÍ4f»¸$“˜!Ý ÌCíõeeOBê‡õ¢cŽÔƒ¯Üyòær1ç­5/Æ¼qåVÎìÈ­Œ¡xqÖN’ßSÑ¬`žÅR¡¬Hë3§ÚX]zÖ$¦z°ÂRXÔ wÐ”ÕÝÑ½•¡Ì$z„\° Ïi_¡§3ä~‚ðà½.ƒN NÜÚÑøM™!ðvÜˆá0®È±wèçŠ†ÍXÖàˆ0ÒˆÁÊŒY1C³¸ÀÞäæ—›ÍMß]Ž—Ž¯)änÉïóšbsÓ|×zÛzßzãzç|ërïöæõîùöõþµµ¹
+µ¬„°µ,mÜ¡¾HP§r„Á?0•:d«ºF @É<UÍAáà9eè (jDux7LÖB¹TïªG!hµ¶ƒúFªñ®ójI"®÷Ä öªžØ·ä†E}ý	Õ1wú/¢žÎÞ¬ïý7<>¾§&„<kIË@£Lßë[\˜)>ú}lê—‡¸õÞûÿ(w„ÇàŸâkÆœ<\÷JØHÞÞöM~UŸÈƒÝ¯Xˆ«ïß¯¾ßP¼ÿ Éøgë?ëŠ³Í^¿:Üãæð«»‡¯¯–×PŒ/¡Ûb§ûUÿk¸£Ñ4›éŠÕœÌjJòš½f¶ÅÅoÒqV¿é’ßTÇ9Ñ(_-'L§dÏIoÕÑNÅ:ûä;Íuš…6}˜‘NVzH–¦Sè;Cö”²¡ÁW¯Úùñ¬«äð”âc!E›ìd–’%·‚½ ¤J1‹S¢ew!aK¾Öô´œË\K|“·‚¦{Œ™¡¤ËÌ6ìCi‚e‰”/ÒØ6R€3ßŒqÊ¹¥p¬¤£½îJøÊ´+í.	'gœX2'MÄÁl|±¤kcN?Ç^p¼€FV’Ÿ¥£­h¼í+»®lòWêHáÎ|ãMË™Ê—˜P©r#Š‘òuºjRU¤Ažè!Üh˜AbU‡RÆÖ‹!#Z6ìI222*–&â–æõ¦´ÞÙ;Z?¾yù‘ÿÓB†”ÿ,7¬l®!NÚ÷’åú—,çk–+A®Æ8Lƒ¤0òg–»3Ÿ}CßLÙýØjX›„4\šŒf”ËTÉ±@v­Ih”MYX¦D#ˆ"d‰2DÙ±±ñûëk{ÁZ°Ì!<æŸ‚˜…1—ÙÔ¢K±L³DlÂ™¦
+hš-RHFŒÉ’Ç§FµÖ^ãÚk`Ë‘mçÌV"[6îÓc`»Æ5†5yöï%¨Ô¨RÃÊøhßW³ïÒd–äÞ›ÐòUlù$¸È5¹ü6þ·ñ¿ÿ?kü¨ó/ô^µÖ(Àh9NîËžÆ[k¦µ›4t°ž««U61š“MôÊ)—”L20“ŒL$9“Ì÷h)ÒäGs˜™fV†;=M¤‘ut¯3>F?âÄ7;<²à­²N^zsÅe#®èVÏ ?7ìÕû5 âëÔaõö®Ã"Žàí†R,8HÀÂöXÜK¼:¬õø¯ø€ÒMòßØ?³cSå=Ð‘ôFùƒ”ßåC¡ü…ôBÎŸ7Þó²ßRé”ÒæÈpƒ>ÁFÁÆ!Z`ÍSaX–4%sš–
+ß`L3ä$¸9Eö(–‘#÷)„ÉèÇO!?”+?ÈúwT&×0\”Æ•¢$½‘$9{#;Š9Õz¢þxfˆ1EJ‹\}öâ–7A¡8¶„µ`I˜ÚfNÊKø÷xƒKÑù>r<ÂúùìïÁúº×5’†hlz{ïlîkÞ—žjCåÒÏÚÍÚÉ¦‹¥ƒQ[×´Lš^]{to‰{iÁk± „[*ã¸ao°}‚õ
+¹ÿ aùó3ä³_¼ötPÙê ¥=ô@—úëæž]]ÑMPÇF6nf«lØ´=¶ð17ÂòiÛ·»~MW	l°n{ì{¬{.ü´òué\1ºdtÍ,ÂM8ÙžûF7ŽãÖs;îž“û'"”*ÌÅÑ|1®êNZ¸—fÑ¿†pC¢ÛeLÇ÷dx~õß¢{†|ö‹÷À¾ö±?ñ8âZW^P‹µ‰Ã‰ª¨àˆzN¨íŒB¯(ùŽœhF(ôˆ6MhØ<.JÞl?ÐÏ£¢ƒ3 ##‡lBßUÎäÆ=¨¸'U¸FÛ·¤#¯«B%@¥Àì³J½.Ýe\t\†¶­[¶Bm³ÚÈãƒ„’_y5/	kƒ­`¿à¸BÔ<àüð‚Ï~ñ~ûúÛ×ÿõ¾þw Ïf)ºendstreamendobj63 1 obj17781 endobj64 1 obj<< /Filter [ /FlateDecode ] /Length 65 1 R >> stream
+H‰ìWËn9üþC]Ì\|90àÓðy0'FÏü?62Éª®–ºeËØ½©Ý-Õ‹dfdDÐ®ŽÃ¯^Ð×ºaFœ‘‘÷(Q/C¬íjôE×CÜºðs!þ#ìrwŸ¿‹ÏBžTzÁŽ–~$ý#•
+ø9ôâýÉ¯‹¤çþw÷o~.ÿƒ±<NZ¯×ÃŠtRgžýèÅÉÅü•‡Ç¨«u¸àŒ¡ëÎF|{»*š¶Zý³½hzôä#ÿâxt«WzØÈH)ÑAsº´ã7rÖÎß<m%‹þ¥§1n®â.}r÷íéáã÷/ßŸþ'òã×oOÛ©?–ßþzzúò÷ãÃòužZ‚ú]\=»¨Å.ù ù ¤”
+¡¥‘V:„—+e’Qd•MvÜ¢”Fe•S^­*¨¨’Êª¨ªšêZâ²ÖFh«öX_ÔIg]tE4Ý4Êh$Þ¢¬Þ¬&˜h’É¦˜jš•VYmµÖYTl´Ùa‹­¶ÙŽÉ)§qÖ9çÑâ]rÙWÍu/½òÚãýÞzç=ú?øè³/¾ú†è««Z5pÌƒ2÷:µ)Öt0x·Ç%:bH!‡jhˆeTQGL>Úè¢« ›à®cBäX8jl±ÇžÈ„D%d#4,§|$Ò>ÂpØ=Üþ"ÖgÁ4 ž±BäÏ­HûwšßÏÿObþ³ŸxöA#]‰Ìçó³»2½ðÚí—£‡ïm¾ç¹åí?qñþs”ýw¤\">ˆÞ{ëµ—ž{BahÙw×m7]wÕeë­µÚJË-µˆZ¯ Œk¶™¦›j²öÚj­¥æšj¬A@<pg«ÄU•ï.­ÔRJ.	_\±Å]&×sË5—œsÊ1°™]¶Ùd-²ÂŠzj©¦’rJ€S€:ù'›¤°üdU ,mtàÏŠÔ §X ZP›Þ¯À³ª-°­qÉÂÔ€úô'VÄ€~ðè»¢=Ñ#j•¾sÛT4PöIø„n
+è*:zŒ:M£ç€M×ÑÔ‡X±ËŒôÞ9é”öÊ©§äg. • rÂÔHÏåp\*ŠáÂPi($HÐ»Zã:U®U+sÅWê¸vT=Ï¤Z®£áZR5)@l‚ËÚÇÛjåò.qæ2S¡)Ç0ž«î¸ò–«Oõ×Œ%Q…‘‰$BPñÇa°CèÑŒ 
+†už‰«ÓEÊÕæ>ÀÅ6 
+ R 
+ÔÐ*kàÍw+0Æ‚çÞ«0ŠÅðÓ‰˜bÁÄ–£ªX*-zE""S¬Y×=‰Ûg$s$ô|Œóû3È=—
+B…¡BQÁ¨|TL,kÐ%iP‘uFŠÄèäÐ§qè©T¤U#,H·(¼`#	ø“ gHJXxR’Fo1Ð3=ƒOADV5Òµ<uÊ&XÜ$¦YâHäHæHèHêÖ„ V	¢ _2fqÆ¬$ ß ¦ÅKÐ½ ýóPB‹÷hÌ]¢€V —	ÒðR×[±hLe$z¥aJSK˜fÀt=¤Øâ²ÆB° ,¬2†2/—î‘ÊeMR6'¸0·“Ê ·¡I†•
+wqU˜ÆˆÈˆÊˆÌm„F”Æ¤† ¼Jf¶Ám•áŸ™áÇåÝFuDvƒî3~gÒkÜŒeRßF~í¼g
+$´¬ÍZ0*–“Á‡»¸0)-¦Ë†™Lr-Ò³ˆ‡·Bàk»)Í•I\ˆl GLg/XoJ‹Ò <b>ü<¶c¾’y\4ÃÄôï•Øe"0žYÍ.Ì {ÃƒƒjYiz0$š-˜c;°Ì”5Ü—d÷ìîÞëà¾€%…ñÉzm¼êÚ¦í2Á
+v]ä¸Èo¯¥¦ÓZÙb‘½‚±bCEü¶2·³õ½ÉäµCÝ}%ÌeˆoöÒ£ý´SÛB¼ðd—&êhhÎ1+¸kÃ?ŒcÝ5žTžtž”žµþ öCïŠÏš/¦ìë]öû”}~Vý¡ûŽ«;UŸ5¿±æŸ‰©M\á¶Ÿf·³yè»…h#1¬ÄÙNC±YŠa*Ž¶‚…xá,.¼Å«Öâ¥±ÀªÅt/\Ån)6Cq4ÓH`‰“y>¹ŒPz±þDí³ÄRd÷-äëwñÕƒø°‡”¼¥¥8çi“»Z¥ÇSá$Wœ²æD:uÞŸ¾ýQ1jåi?«Ü:ç‡-ìö„‹'Œ]Vu"i>ö¦§Æ8à-Üšy?¶ƒüŠHo
+Öð£H”‡qÞòÆ‰ºKŸÜ}{zøøýËÃ·Ç§Ç‰üøõÛÓvêå·¿žž¾üýø°|§– WÏbT¤êÊü=Ý>n×N]âöºMYÏ‰jÛ;"Žû¿3mö«m¶k7]›ÙkóV¨›\ePùã½£I*xÃæÊMkØZeø²Uý”f'åØCÉÊ ‰jš`µR¬ULâY«"Ø¥€iÚT*ò £M¤*K	”Cç„)M,KÜç@„¤IíÙY‹Qf)""J$@ÈŒañ!ééð7œá‡:´ƒyNÉò0ÕZAÂ4¸Çƒ"èªö¾qÜÿ}OúöéÜ’m7ö£·v£×ö¢]×Üˆ
+V©Ë}èqzÜƒžw õ Cë¾õd	sßYþWÖZlÞš­õ[Œõ[-x·riªÏ–z3ÔïPx‡Â;Þ¡p„Âtˆ›q .*0XÀ@@Ý%*íñª„B:Ì¨£tE³»£J	õq¨DU
+*²¢&*2T” "û™WÈ:å<!ß”mÃ™nœeÊ1e˜òK¶¤vKìH«{V*§?N©8duæuÏìÈmf‡g†WvnæÙ°3e"<²Þ¦™)œýÌ±íÈ†Ú¼Ñæ•Žþiz*1ÿ8š®k[JýŠ»8~h™"Øj6xŽM\`Ï–Ù§5vgŠ]™eG6ÜXš6l˜°aÁ¦oó_7íWÞ˜@ŽÔô`nwaiú°ÆNL±³ìÆVöc‰Yæ:¹2ôºAÏ“1[@ÍÌþ¬Á¡I…l-Àëá  'À¹ ÔŽM8·@»æ˜(‘
+˜©Å.Poº2 -úZAc­’Ñ0ôÖ¾3h#þ[Áƒ|˜Ñ\0v°z\©Á™MçË*@¤=˜A¬Û1Â5 ^‡þ\±ó‹`äf®`è *0¶A;0øŠ^†µ«°{k]ÍF›#Û òŽX$CƒÚôïPx‡Â;Þ¡p„Â4Ÿ…\(Ô2~õâð”tõOqwãjþg>G×(øŠ•'ë.Ÿ¼r}öò­'¥mØqžÎUÜ¥Oî¾==|ü/ûÕ¶Ç‘C¿@ÿÐ/Ø@Ò®û%û$ßr81" ‚±=ñ*+Y†àýú=d««ºåÜvCŽâ™æ™*’M²X—»—gûÃUîï_úlºóý?Î®öŸL÷Ïw/þy÷hYíý—€:;ýÞ©ºúïý‡u=ÎV§{þ»á¯dÁ¢Œ<rq©–¿2“<à²}È¥ûˆ†.`UÃ…\JÙóØkAg‰îÕº–Ê–ÚnÕ¿?UÞGï­ïZÝxÃRÚRØ¥¬©¨©¤© ©œ©˜Q!¡Ž©Š
+˜Ê÷1J×¢l#Jö>Êõ1ÞÅ¢L#
+ôj@¡*=*òµøUèP}u÷õæ1ú!XU¨P;	¥¦P&ŽK$£<Ö.ùñzõñzUÇèTøH…TøH…ž
+ÿ‹ÙIýÆÜ¤~sêðÓW¯ß\ž®Î¯>ý´†úŽ¾ú•~±å—ovWWûË¦¤ã½½ÜOO±â†¤^šŒ™}ùð©~ÀÃ·ì¥¼×é;¿Äã/ ¯'7=™~øQM/?}Š¯EÏ…H¬ðRÓ¼H¼àdØGÒ’>5gò„/“Ý´Dìô?ê9úé7«æ‘$ý“5³s*O²~zAÛ!ù¬àº=N´Ñ*B‚í&Ùƒ(ã'Z&v`²iqŽÖ½[XbÍ½»ÍÛµ³“m¡øÊ:_oxñ!&ü!›–Åƒ¯üÑ|µjôuÉ]Û)ÆÛ+È×ûÁqV£»-ZÈÄ%šªs·©{3pìB$É*oÞz	ˆÚÄªn=aIò*›–Œ72ˆ)x·lZü<nd`IrÛ<n¯ý•­²cÌ?Hj‡w_ˆ{ ›çwÊb5º»­íã‹²idf	·=îòžV/á”MËbñxIÂ…H’]ÎÊðâ7Ó&\ÒOÆRO%xI£„˜b€?dÓ²xð¸Q‚%Ipó¸9¼öWÜmbHÄXíý;Ž¯?D†=M‹sƒ»e±Ý]Êhñ$õ-¢ï+#9Ç‚O%ÆZSKØeÓâŸxüìèQ9 q¢ÖãñÆóÁîâõÛŸÏw¯ö8/;ìhñÿpHš?xHÒîþ†:ïX•<i~Ðõ»…_óQ”¥£#Œ¡ƒ¾”Á!¨f›²Ä›<î¶Ç7›¼èô7ƒ‹Í­ŸÙ*†3MH%¬:OÙrÅ–#'’qÅžFøËÍL‹æ˜¬YIbvÙ¹×åµ´Ê	_‰?•ö‘„úOëªmiA‰n•Ü5\Ï3¦F7™9%mE30Z2/*¢ñnÖ‚i³ñ+ÁÎ)Z9¹ˆ³ÃÈL«Òlô¬2ÈÊ¢`næ @±Jk	ÞÉz‚PtVEð}öFùfå0qG¬Pž£2H®Æ{âÍÖ²³Hd(&Š³ò!Lð>PÅ"Šƒ{	‘@©w^D\)6bÂ~gªSjÿ¬ÞˆaS×åYã"1I
+![\“A‘tZDŒ…ð­2FDYÎ¢pchÚšÜlXõ	9|¹«†Õ7õæíVîB'˜D:’v~+/ùHRW5î1[¹cAÃ*QL˜mv~#÷TkX!#¾pK±#³`BxCíÇÞ wÓ°ZRÐË–ßÈ]E
+TKVÒ[ëYDÍTXJéÙè@­ª´‹r˜Ut^zWùMG”3·‡¢@?-¤
+dš bˆknq'5±sX Ö6pædwƒÜwÁjì`ÓGm-÷ñoXI8\r‘s\x!XáA éˆRÞÈ—Æ|ã5Ñ»­ÜQ¶A•ÕÎ# 9lä¾2V«ÇQ·GÖ7rW‚µN‚ƒÏ¤¼•ûÖ"Xí5¹Ò,ªX;‹Ï ŠoG“ˆXìŒF³Eo„‰9„9høÌ½O03g{Þãør[ºÁÐºG0tseèu”¢–ºñ–)•ˆ†ÁH;z;Ð‰úÙFÆ\¨U±Ò0:P#9MŒkÑÆÙ$éã‚YŒ_8–<ZFf#›Œ–%’` TÅûL§ÜZmmE‚a	Õì: ´kÙcì	eOÃôlô"XÑ½‘#Ò¼„™!;ç˜&I®+%"bé+­H[ù££ãç¯ûw/^_<Çä¸<ÓTž¤aÍ£…‚¡I¡2“}ªã¤žŽÝÎn¿3UŠ*QÍ3ÐÊÜI‡U“Œ­Ü°~ï{ÈFŸr“µTo4òp¨-µS[fÄÒ\ÉûcêæÓuÉ:!@XkJ›…Q‡ £ÅÙ¬B™+†&¯ÐƒNº­'©+u†AÎm[%P¯lmô¤^î_^=<{quöú°»|7}FÐZ>¾¼Ü•G3Ýûâp5}‚Ç¿Ow¾ÝŸ¾»‚`ûË/¾á…wùçnÓ|wº÷íÕåÙáÕfçÃÝÕ®ÛÕÿôÝîùùž\©?áÇ¼Ò‚€°t”…2Ÿ—ØO<ªSG¨a§kÏu9²§‘
+-,an¿è0T­Jz•Ci¨)p"RƒêV	$Ê† ;Ô.tYýk·ÿ÷À×z¬Ìÿ³œ74;>µ%¹0Ýir¡©®W¾Š›q9é¶2çKLÑ—]U„UÛÄâm$<PÚŒ„¬£²„ª#¼E¢/POääŽðk£.áÿÓq´„äÊ|—|éîšfE"h²HóYŽ"^o,B™ë-áy\'kJaØ+¶>\Žÿ•nÔDºƒhi¥™½óf®JKc	%F¬Pn„m`¢®ßëÂœqÛ-í|´zËÈy(`‚Æô­)]3~Ö‰§k1\žtø›’Ì)e+h¬m*T4^G=,ŒÕE×o«·Šåñ0hÊ .¥¥þÆ¬ýÞX¦¥-Cn¿L0Q×mÅÕ¶heõ–ÑÜfj¹0É¢ #²LÈžç‚õ–½=Ñ©?»Ñë‰¾¶{«˜Žà„dôÀtÁz
+· Õuéèà®s6ë#}m¬©{™ë¹Î5+».×ÿz¤<ºa@ˆ–ÏyÐÑâS¨ônóc¤­û¼_V¡^ÛÚê‡Køÿ|HGæi¤Ò=âÝ+4Žlã0’÷Ë‹¦©Â¬f“•Æô~Ýí£½7³ÅÏí2ç¢ˆ*XÏgÙÛÓ>`:×Aëëõ­íÞFâ;[f•žø‚õŒ–XuÄ8<µ‰/XOèæŽøk³*ñŸ=:úÛñö§G‡—ßì®`÷PäûûWg‡Š|6ÝùòíáÕù~"³¿îßÜ=ZbŠ‰0R4¡ö-§9›%ì‹_âñ€×“›žL?ü¨¦—ŒŸ>å¾Nû/Ê“—9³{Òµ3Ey:4;O™Ùx¢
+¾dK’Ö‰ÊuöÖ’l¨|Ø=%îaÙuQÿ/ŠI<ãéÛÒJý…8ìq•#½Ás“Hü£E3,Úóoj{Æ½æš½€}
+C˜îÜN¿ÿ)y²y†ÇËÝa¿;Lßs^nB'‡V†>¢5…#‘1«x’:éR0]+TµÊ¤Ôê!Ùx²Õ%¹UÓ×5@ŠëŸþNw}Â}àþl²›–eµ;ØÞY;4KGcr*‡"R¨’-PFÂœ%Èâ€kM{Æ’öÒ-xciuÅ Þ«\ ”ê,ò\‚¼Á5GÐñ§H£{¯‰›\1aN&Æ¬ª§¸-C+¯7#¸	´­–Û«öÚ-ßz——¨¼/ty'‚J‹¾€êÀõ	ZÌTaQÙæ]Š÷j=bdÂ›áeËË¼'aÏoˆÀÅ{"uƒÂÌ¢ÁóY] ,·­@¹âvÄØ‚Ë^`ìÉ¿Y¯–=oúó³lþ¡ûe™f¸Ùè®p'qkÀ3ÜFß¾‡")é“ôÇñ¸‹ñXgôIyxH
+vŠÏßg‡Û‰ÑXj?,I–pÞj±K6	èóâþ.,§ôþà³çûA b “·gìýÄu¡ÿóÃýÃøu€y3Aï§0HTŸ'èÄ¹/ðp9íòŽ‘sžÌI!²p€Ölº&Øû¯(?þ÷Ó»ç?QèÿeÝ¬h–èŸWUf:á™Ó9ÍP=pZñå÷¤ß7[J—&ÓˆUtüˆ°_K2_!.u¸£ýûñbÀÇ±ñ£ø>æ2´"ÝåB¸þÃ‰ÅÆ/>.›Ž÷­ä;®üŽï2)Ñ”Œ'0µÉÜ»§OöO§‡Ú\ä!?cìp¶Ò™¡ÿLÆÿ¶“þúRýåååÝóÏ?=
+òèÀ®k4ƒ"gÿË^û½ñ¿ûÔj*ZíÒ~¯©èÍWçF4,ùðÌ°ì•Û×Û†Ý&N›J<ÕÒîö‹î
+|WÐ”Tn1„Ú¯‘%ßDÏu¥×Ž/ÇåšJ¦RÖÔ6!—h"í¹d	åË-ì³N}+«€F£óÐ~G™×UºÅ
+i}ÂvAˆM~ð•Pk,0œfPŸ63‘i±Ð.ãqæºvöf**Å“(]ÃÂ­y ›²®àt×ºŸ IÌdûoÑa[—éfj)} P½¡ µv³¼l]CÔ}L|…BùfbJ(&…}]FRÿÄ.R( ör:÷eÁ÷Á‰QJö–1?Àh“ì¶ÄDYŒú•¡z³	}„†ko!fºG¾§R›Ñ"Â6¡Œ.u·s)LOëëéÂŽ‰MˆÁÅF]Ï¯ê˜<ÜEèè÷õä:ÅÔ»8£ K÷õˆBB˜j-è´­'tLˆ‚fÄ×·õLµŽ1ñ+¸P¶åDfÅ”ðò@LÚÖSÆtLR
+g$ã¶ž2R!IY¯ä³.m£ÂHý!•»JÇrQeœ%©¢_­6þ›¥ÒÓ$$ )²ÖGYÐ…$ðaAÍs<Ûér2X¡.‡õ¬$Š‰ïpgÌ Úºžýß1QkÔJØ–-ÆÌÅ˜‰8d3Ry[O\êXã[Û“©X×e;$¬A_×sftL²'4EûzÊ@Åº’PTê¾ž¥E1Q	®Š…,EYbCb¯MºÄæ€Æä1z>7ÃŽŠÀê:%tÔ°¹iŸbîV-î‹ñV(ÍÖ5ÎCåÅ æè‰ðCÅm]â•¥°ÇEŸ^:‘žmëp‹Öð-CýÄˆªËy]ú|sEu\1‹e)B2RrÛÚUH–$Å@©œØúJUn]ƒ‚^¤H1ô© ›£ƒP¥]×}Oâo:foÞá\8+‡d·uFøST77Z.ÜÀ)¢KÖ•®_˜M"­ÿöö_/?~úðòŸ/ÿxó†áÖ]Îxxûý¥ð_þôé×ÿSÏùÃÛŸ?÷ÓþñÁ<~‡Ÿ¿~~øõÁ>~÷ËÃ¥™ÓÓ¡›{ÌÖa¾)\-ãVAÛ5» $"Ô@-2ù ÄÐ×S~xx)†Mùó‘¿u!jÄ2&=’VYÅÔÚCbžÖÁjK=¾üLççrs“,LÀÿÐ"±©…:ZŒO€!°v™Ø†D@hi'0²;àºñù=üð‚®}/ˆ&¯—­„EÅPMŒ£äŸQ­‹úÅâ½ÕRDP…ŒªÄšÊ ‹ H ß{ÚØŒ2$‚Pð»’›o©Iö:ç²€5ŽAÛHK(ˆ^¼åG…Tè*S×Õx#i,{oØŸ;ÅdTzb35§Ü¶æ€þÇ2æƒogBÕ²o1Á÷Å˜"ßS åÔLc c¶±4›HoÎ„Éß?\`uvc,¡ö¦y _'o¥½G®<=¼O(‰Úwªóm*†‘A2eÍ»+· WÄ-f9’£Sú%õ­ItíyÕ¨ I)šwjP‹Å™iÓt•¼mb—\tåJ2NÌ9¼>1ç¼e	f"	éq*nò
+b§!Ic;ìt/=Ëð[=¢æ„4VÃãI9ó`MâwLFmSc‹ËKÔõKÔõ¹KÔ'w¨ãaMÔOáâ ½ô¬o,5c?üAIÌj3ç{</NŽjf+lFìGèœrçe¢Îú2…Þ%$š2	É›¤«UaDŽàvíºÅ6
+è‚.¶Ôn 2äB¤Á‡Œ
+_Û]í!Ó¡x}€`O’gêÕ±u0mçúDœr$ŽøŠyÓ¿§®Ó7†Líž>„ZÄÂeêÿ£Í4&Œ©´ðÌ,øºœhÓ<¹ÒÆŒînržù˜ò›:lš¡:óîÈÐ{l>0ÿ”"GßÇ)n[„÷¸÷t8JÎQ›N:öš*á—¤äú¼%J	ánNÝM¿c¢“ú$ G©ØTe¡ÆŽœýÚÚ ŽÔs¢W%ÞËM7aÀÚF•
+Ë]à"q(°‚6;G
+e‘€+cÆ^êLx/M{"9Äþ•3åÈ™.6“( n±ÆpýˆÙ‘b`hkÕÄãR¢Q¤_1nuÇn´Í[i3¤ð¤¯¿KŠ™ag.žrïÕ¿KŠŸ¾ìÇß¬¯/Õ~
+ÿ¤¹Ê*E¯ìë¯›ˆšY8}§idmíäÇ™›à£}×ä	hö¢Û’'x–Aºv†š	´C…£
+P;GÒÛÂ6×õ¶:M	Ü•EoÓ¸¾÷;éFÇÆÑ\Á¢×ØªõKêÈKµ=SïÛÞ6Ž4œ¿Çéêì&×˜OêpPœ³6eì(x›6.Aþ9sæD®#Œ=RûäÝ{‘8Ælïª—S8KîQœOBþš";1zÄûÂ}¹ñš%½Í	ÕëÉ5ùRÎkšã™kÈù¼¥yf?j?®‰–F•Žý&?xÐ¨›^rÌáG±5]âÛ·í`LÓè)fz™{x+o½Æ\°f:?vÄð‚œe@œE¥Ç|Ö7TÉEÉö°ç>…mÚxOFOŠ{ÔæMÆ7qWïœIs¤×=*h{$øÉ½÷"qŒÙÞ=è½f+Ä©”ì5çÕ=×[®Å3×+ˆÕÝM°Ž—d‰÷9¯¼ÎsÊ×lÕæÄÖycÑZÃ\™¢r÷[¹a¦jl²¶Ç8÷›p=+<¾wŒFKA´ãQFÏŒNÉ8Ìõ¢Nòžø"°ïæ“-|ÔR±0€«¢3cj÷“˜øÚöRà˜vØkÜJWÞä>[^åF¦@˜¥ñëž>Äú›º‚l£\’¹ Çaš”{Á€æb”øP$@Áp'ˆøÕ0%™*‚^f'“ÖäC(Ç¶ ß¼é}ÁL;ÿ(QÞzõ;‘YŽÒN­Â&¸ÚH^ž2ääá»Ñˆ™(¼U	wnÇÞâO‘·¥F)TÕF¾K\xˆÖ·uH‹VW¹DŒòÚâÌ¹æ´^²r´ÿ—.RÃ¯©¾*EåZ}yd•gíH˜¾d÷áyÆ8…7lnÚ«=ôÒÀ˜F5¨9²qt`xuo'V¯ýJ´èÒê7FƒÖUñ¨ŸG¥ÝDyñ?•e¯RMv*J:þá¬å„âk‘]1RêRÐÍÂ«b2«Xwªü{/èÖð^ÏwÅ«$¢·10˜­QµÆ6Z†‹—½ÐŠ`äµÞ¬C¹ ª<ù+Da%/kq µ“sc²²7ø"´«Å†	Ô–É\®{ñÜŠ§L
+q,c¯Kz×Hc]›é”sËsJWÎÙ¨9Û)‡}½kž8gÇ¤68‡?+e:»p{kÅ¯œÃ7­«dw•V†¨IZ-®ÂÉ>mXÄÐ¤E´íÇì$ÛE‹Éô5iTq[Xø/ý¾/Ñ¦+YÔö…,úP•(=×õQdHÀ,ƒêÐ(¯"5mEéR§ŒöwóëEjówgœ~':§8Â½ñbcK5Î¯l½ÆÛ.YÁa‘ìÜ#[çG¢U1n!ÌôùÌ˜Ñ÷MŒÉyQûWÆLIp&Ý™ž;“_;FLÎpÜ!=_nØrž³Ôÿ£½êZí:nè/¸ÿá¼lhÑh4í“íö¡å¶))¥R‚q×…ë€kcòï»4’fïsÎ¾ypO	&ÇË³5iIZâUi=t¾ŸÒÚzxÙ¬¦¨¿¡%å+êKŠ’ÜWIœ\_™ïI;+½	îâë=Jœ3‹I|±© —Î›^ë*p_.É¯ÂðpÙ <
+Ga}$GÉ8:F>Ë*¥ãv{ˆÂ#nßž|›«(¾¼Œíê‰”	älbß7™k”J‹1VfÇ’Á?6{ fe³9Mõh¢4ÅÇÚçQŸ}¬%¶ï£F=®gÅâÜ1¹«àº^¾D€—ìW*ïó
+iŠ–]MàTõ¶
+:±'§4Êö=UñÜèªT‡¡&,ÐLe’k®rä˜¥WâÅ7§1X’+ÙÞ Ât¿ºžÝsß×z5*2Ÿ/bäÆÐˆ]‘¶÷Cí$ª^ÎXz•Z¹ìgŠ×Ê(ìžÕ–À„·F5­«fûŽi‘[uÇj÷®Î±V*˜.õE\uÁ™xïÒmxZêNÅ"™&®{ñ“ç¬˜ÉN!EQõÅâÊ•Ù%6Ä¹ƒºˆRåXÒEÞ‚u2ÃD\‚uÉiW{ÿÚ]ôÉ‡OyäÕGÁy<ŒSüëÑÿÍ˜6ÁV[==þËG¶Úò. ªÎ1ðàÝ­äùjHº“(U6Ü*F*ÜæÀX\çŽ.+@ÅÉyíÀUkb‚ð¢›í­6Ok¨šÜ×*Ñ2sÝŠ*…¨˜BôísÙRY–S~Õ™‚8•Ò…ZÃýk(»³a`Wh^ÖŸ¿öþî¼„ån&ú°[÷á"]_®®¹ÑU@ŽBwå£„eî:Ç™ïFýËÌ-ËÛMmI˜3§Öf¶ó¿šL>i_â{•±=j—yÌ–”å"óÛ÷»;x™ù£ÉsH³#Jþxw8+Î5Û6W'ÐcÓêp²ÎÀ«qy‘ÈÕ{ÀQ·8n,Ç=è°[•ÊceuX€×Åz™É:8Ã‡ûh¸ÿx÷·»qzòôôÝßñë«çèßÿþý/>|úÏ¿þòêãÇ7ÞøâÍÛwïÏà'~óùä9=½K§çøóÝç»Oøêþ÷ÝÏøËñãß€>ŸÊéO§ü3~Ð“ßÎ¼hôNjJÏ0yßŸÃe<µvÏk=D¶OßO¾ÁŸ·Ö1*kë~©îv÷rmšIÉ¨Øûc÷ˆãWßýüÃÇß½{ýñÝOï_}øùô@O~MÐ	šòééë¿~üðîýÛÓ“/ž¿~ýéáÛŸ>¾Ò³OO¿ÂÉßâÏ4"f%ŸøÊbî	ÜÝà^FuOÀßÉTu»jw›G¤6Ú†OvG/ö’<P‰/ýûIP{ c)ñPû¼u,-ˆ‘É@î¸þ¥Ç§–äpae™ÙLì:Ê:îoa áu?Ê§¸ä¾ò³N=@â 6UR…µ˜³ˆVIy9Ðü(§Ò¬•Ýª…Ö÷çÑ¾e&‘ˆæÏhXîV&(¶G:Ezk¸¼%2×æ.£d›»Ø„üìhâg+g7€ƒOG¼¼éãšYFmøë´µõì¡ðmÔŸ\Š,pp¼"E>uãJ„Lh³Îó«Ûn™'H]ªîr“â/Ú=øê¨ARr8‘Å±Ùsä6ü8ÊÕá¡2>LJ¼b6ûƒÛo™$HN²»ðÁáT›7Lr?°›öðXø—_WÓ(Qâ%ÇYjÑŒPbæQ”íû.îVM²Y’_Eh»æU°¾HÒ{T I5Wë³a£xV@ËJoÎ<¦"ëþT¤XÙ–˜0pARÀªaÄO÷«V‹ÃÀÞ2kñ‘7B
+ú[ÄG¢ÄK	3jÆ£óˆ³:,Ý¨ŒhöÚ"þßŒÔ„q8ÑêÌi\bÌB0çè%Â|nâ–­`Àöê3:ç.‹Y$8°ñ},L(»Ë¥–³ô%:qdÜ„Ñ-Â¾8ˆ„8k“Í ”wõñß\Ã'Õ×ÉÍR4ý¥5jú˜ÃwÝ,§ÓUÉÓ·¬-ÿ!Ð©52kx&Öõ§(ÀÞýû˜C¼:\™ýl«}YÍ§£ëoù4Û4G©½,ÃŸ¢Áé:á Iò–o`áHÑXÜ¦Y¦4üÅ`Å{JuøÑT«ó¡kpÄ3ªRŠüsUP«\Êú¾,â tÈAªÙ™ùÇË@Oâ„–¤Ì™`†^sêv.rlžG¬:e¥¬P‘Xúbi‹³p)ôvö7‘K¡pÁEbš£8¼Í½úË„¸Å÷`ÁµA°aU‚qÝ,I-³þ,v+†Lä«òŒ¬î-ö1Ã—?HSÉM0sÌøT³œht[†öd¬
+ø!àá(¦*{ÌrråçÊÂÍ*Œ«Ún-É¶-Àå™Œ˜àØI«»˜Zh «ù‚>¹š¯GXfr!øüÒ¿/è¿;½``–XàÐéõºê¹/5'‡WÊ3jäC2µÄŠôpµqÐáäÍhh5úQ
+¸KZqp¨ßFÊ´8¿šžÎ1¢¤vh+‰2úú¸—yPÉ=·Âb÷Z½HA &¿gVgx?(ZØ”ë¾NúæéFk´•¦q²ïa¶õÕm&•üt	VÄ›”þZ dEê‚-·¬¬…9x «PŠåÙ»f	vðhÛI§…Rš¿‚0¬1±£XxãâiuxÈ/¯¿åÓ í"EÚrLL‘ÌLžxZl€>ùE64[¬A®£­t=÷âö[>¬êÖá„`•ñ4Ì‘}ßß9§zqÐBS‹Ã’VUô\÷Bíð¶>%W´‰-Y›×CÀœ#z•gD3šCiž6·Ï	ŠÔ¼›£3K€kr®%ó“]#wL½9ÁmØ:¾‡Š®1œúˆ³²BéZ`Î…béÙXÕ# ¥¹[E÷‰¨5Óf ìtG-UâìÚVZ7¦)Hâ…ž0¦òZÑF³pAdQ÷³å7AÚ/s[h×"Üy÷ªˆƒ‰BŸ”h„…i„ê‡Z›¾^UãUÌm† ¼¤„Q]rÍ€.ZØ„…ÖˆKzïÊL.3‹ )âš\õ ‹J×ÞÔ—Q–Lá€É9òýÃ£RØA,¶±žP¦e ­¥aˆ]…•ƒÉ1FW™uƒM†Åok<ç²Û8ä]i¬æŠCµ,¥-»:ÄŠ5¢Ž¦p1Çâ«þst°:B·áÍgk‹=Jô°Z"®”X–Yò;˜¥¼Mè¯–ÚCMŽ"³£7ÆìÏ ¯_†=E¢’;X¤ÅèO[Sjnwµ“ Tn$&ÛÎa ó<‡ºjHÙEË¨ÅÈx°ÈÛ8Aæpp3êö%HJmÁ-ÔüéÛm£ý¼ÁRQLzQ1y¤0°KŒ/P¤)?ÙueMïµçjµw!ÜÎ²ždö:‹u^`K#tpT1Ò*Q“~²D¤²íÀ mB¹@øû÷{ºS2™‡†‘sÜ$Vƒ³³ˆÂ‰>ªþ˜­e­=…8o£9¸mš*èãû^9††¹ª8èáßlö±Z£‹i”èÎ“AÒˆ¡“k0QŒ2]*Ã@÷Šu<X¦ÒÝhæ`å(áÁ-•a×)‰ï½»ÓÖu¨¸28…¦M‡²ñ6^–¸QÔ>ï»ß
++C5äx–j‚˜.µ¯ÙuŒ&Í¼L1žfÞ­Vwã-vü4üèà…·™"ÑÚ©­ÏG[+mþ/ïU’%É­Ã®Ò'ðÓ,qím^¥î¿ý 0²«Ë^¥ÿ.2‚¡Äp$¯öÔdÎýÓa|Ò¾|ßÛQéa	± û¥Ø¸9¤—`‘MÌ³EJ÷º‘ÔaÓÙ<v´ôÈ[þý¡dvSœN§ÎÂe•ÝòY2Öú`ßîæÿaí f„×0™³Ë-9Ø®É8ë†kmuž±ó Žì
+è{õôZ¡¢÷EØšÄõªÁ¸OÏ‰üèºnWÜºH-íÍ¬3:‡Ô%èQñïŸ—õúèžû¨0·IÚrµã]Å±&*¹¬õ¯ºÆ¾A×DÇçboÿôýÞg]i­±¸©û¼æÔF,ÖáÏvÖØŸì¹â•~q¡!ôl¥wÐô±¶fVý}Ÿeª‡/%|1¦@ˆ8"WÞ^J/y¥Í-Åëç"l®¾ÞÜêM.w…^‹0”¦ NxXCú€A2k¡ª÷zÇk;Ð«Nñè( íy§v™'Dº•¯ËÀ´K›÷$:Ö2¢€Ïf°q/yÕ-\C€¥jžÇCñær@·´#1 ÛC‰g×’ï·® éò¬÷¯˜†àš¢ø¹è+ÜÖÉ,™ñÆÌŠ’`]|ôžp˜ŠCU=Y÷2¦Äù‹AÐÕh5ÖÃmÃMÛNéb¯9ÄøvöO¦]¼µ‚±š©@UäJ‰i9âÄ‚éaL–ÞÇ57}«Ênzp€Ùøs<oYdìléóÒí%":ø¤FÕF®þ	\%’S¼~2™©3½ÃÆ¯ËlûQ§ÆŸ¶Zêc‹ØVÀZ’ÅlMWíÂðf€Tö,ÑæêK½rŸßŠ´ãôä‚cõé•yx€W¿^„o­D¿>uj2ê`[Ô¹ØB@g¦¸+a/Â˜è#kD}P¥(ÇQ€rKBšå*#fs¹
+Å)ìd§uÁd¼ógÓ)íU7Á}´Ý{*Ð»Ú°¬ppÝ©fèD>’*0ÝëýÍ-ì4)7@rY™¥~Ócð¾…YII:ü x7[RÙU:ù½“ËTp¤ÂV¶Æ*1e9ïÙJÎ|Nf)$ÞÌÃ5§ÈÂ2l¿µb€*}³½ OA\åTÝUEÒŠ8 ·é`J‰o­¿
+‹\1‹¬â·>#¸þ#h•`­eºDPãèKÏ½Üp”3tƒp2ùúnUTX‚õ\ã-Eû¼AœJ8O	Ë¿ß¶Œ\¯ZêZ”¸â¼ñ£p~Ò7@gºv)ßðŒ f.1X,AþÇ4X?¿~¬ûÁEw,#­u[ÐÙ/ÂÖu{2ª »è*Q‰í£ñÙ]ô>@mà6¶¯'¼xV<ZC’Y ðšŸ÷ýû¨Ë‹ö=GQä®Õ˜\†T=ÍrÏM¯m[Ï)©œ²ƒg‹*<-ªÀxö„êüì"ý\VØ”Èn¢ÈujV:·ÐÜâÐ·3UÅ¹j,½)¢€×\í>»ªÀ1¹©Ì
+©@IÆ8
+¼³ðä·f…‡xO.>u¥9ÀÜAaçq­ü–éý>ö&8LjjøÉ¼0¸Û9#¡‰»×náè‚%ë
+Fe˜Ï½h^óG‰xvDnXèZ°
+0FA|<âéÑÉÞ>'˜	Kµ-ï)¶x!ž¤þ¼)¨Èy(L²M$ŸívêÅ‹i]î—>g”7Ÿˆ‰9×oÆëCÖÃ‘TU·ß/ÂåÈ|JF`=›¶u¯˜U)8Ø6Ã²ð>Õºf¾K³à´JC¸ Ø­¬a©îb[•b(³®ˆhrŸZÁ#ºìA=Ó"•œÏ~sd“¯Ãf.£'„ŒÁÞåýFÍÃÂ§nP°`Ï±R/ÜæwñP+•`?¶ò¬¿ñã'sÜŽþc(pu_„—äô:¦ÑÞZ—¥-áo5>»ÀS
+µ»óÕOUÎ;Á¾èµJÃìtv„òÖIAowr}Z[Þó·ÏPù0›%ØæåK3ß›¬k×1Ç&º/·78%­ˆÌÀPÎð#~î“{¯½'}Zc/+XãÂ³SAf´I°GJ KJ™«Í¤Ï™j“‚9AI•›4ÓXösh¢ŽTñf1§¶.+vBƒ‡>´ôýõæo†ðŠé»¹Õ}'õ¾5m³þë;6V‹Eýq€Ÿ¼Xœ–®_æ1ì”*4´É©‹ÓüøwVMÔA¦±9ÙIëÔû[¹”F¬¥“¹aL¯ß¤ÄJwp½¨¾ÏÑAÆðxî¢€aØï4zãš‚Qœýç–A/hÄ,`}².ì¦>6Ý/Æ	ln1séëé¼^Àmé-Úcbúš\âeÌ KºÄµô~O~q¦C
+pdÑK¿ÂsÐ
+q¯Q ð:î96ØéJ.ä„Jsï¢£Àü«šLâ5k6ÍŽ4@3ÝìÄid+J~s†ÑøìkPõçŒDO–çýe=å#bÈot9Uk'¸4õ×ìÅû@•ø:öK‹ãT³ãx®;²YlÕv€SH½v6ªBèÉÑqKgÂáØRÌu×µJ8+.aÜã^nÔ‡¼Ì¢£^îx¯Î0–]è®4omÄÔ,7)qx¿d¾ÀtiÞE¸Q 	Çü+>4·Šîv¸[Àç±Ô¤[ }zïÚè:€ ©€5Ênßƒg—YùŽ¦¶ju=Ï
+ÜSœ"w.˜×ÚL´’ðqúÎ›,0Òè¢c&†îEØÄ<w…ŽÍÕh¤}°~lN=å,Ü×ÌÛjÁ*Wµ~Q ûtÖ¯¥Í‰"ºtò¶×~´i:4)®­F]¸§´²­½Î.ŠÃßâHÀœùI†·¦î“¶	¤ÉM£c0ÖüçØ¼‰äóO‚·qøùiY Ïíj¹54®º<¢œ¶e¾}»òW¯E3»ÊþÖÚÓm¶²æv§ô7‰à¬’IGù"ë.—Á&(²1ÜÞ&í3% ê;Hé!?àQŸØ—$uªµŒÚ1üh6ù& 'ÛMŠüJæ‚YâE´™ØPB	Ã`ã´ßoÁŸl¥}?EÖû<6Ñ‹
+¬ž6Ì²jGÎzi†ŸâÜoô"<‹”jž­µp±Ç½-°´]Ð|ìRßÈµr\lM6lsäy­dïCý¸Í¯®ÖEbîìn7 Ja½èA%†‰á'ÿôIo† »ÕÌ—¢¾{»ÌØé×;­kÎ¿ÞùIUÂ³%œWm‹ÏJíÿ\Á·÷¯~];Q‘ê.SÏíCP°ik¦¼$'Ž|´‹i&ÿRÿÜ½}÷û
+<–ã£¸òŽuöó?„œÛ·gÞ‹šný÷¼û+ø§é£§þ!¯|òlÆ*²_¸@ÍáÄÈ!ëm„¯˜½~,ñú`Oº MyFÞÜÅèlG¸ÉÕºÂÄ ¬J›eô_?ýàqn\U9²<(¾ï^¦økÄ‚¥Eô¬ê
+îJ‘dðgÙ®Ù|qSÉÆ¸dÛ %¹´ÁÀê¶5ºÁjRJ÷yÅëö·ÃJ+»PÍ^ÏžqÅÜ¥L]žT„>rY€ÏC‹þYÕ­Qa´ñôBpÓ|aÛ&'Ìê À ®³vÞúÅ“I³o3DÏ®j£X áŠSà^íX<û»*à]¸!®~úYëÝ)‚˜ÎXÛGÖ­‡s²ï-–<Sž0ŽêòV÷ËSõl;¥Ía$ÌeGª4<ÿÄûnŒZjM˜sõÞ²c'”A‡ÇH.;wÀ[ŽðæM`J\Ê·[x³Ô—²PXž³£ŽÁÇœÿ±^-»vEôòwÉ–éª~ÃÈ6Î Ì"Ëðà:’¹ð÷¬êªUû8±=ºƒ#•º{w×c=¼åñéA8<ŠˆÞ£Õf¦’ÕŸjK5ý×”“?,ä‡Ð&c´Ü?zê«Øÿ¹31†’üDävd"J<€) ð¦=OúVÏ9Vç|? Ž¤§¤‘?ÐìÈæ‹DP{rç¦'[Û*‡-ü‚C:e§y#ŠrPÎXó GÏkè«…^*›Ž=Á2+`²Ç÷£F«ÑS8#H”Æ›¸ýrŸ­fmDŸU½ì#YÈÅá²Wá\¡ñ—¸¹Ù-¹]‰¹ÛgÊØ¦ôöýô™©=8×¬àÖx ¨%eæÏtyšqM´N©&$rRî°Ø c‘Ñ­î=×½Ï”6zÑ Ù–3÷£þQª³n'ëÔ«AI-w4¸ï6©©T"# uÎ»¦øeÑdª97‹u»rl/Ry§‘ø5!»j£©Ï|Æ‹+‡ÔzP„X¥N„-§RÎU=V”ÖfæPY8}Ÿª¼	ß¸½Ñ@ý1ÖS“Ð)c2-@(¡m;ïŠ`O²ŒI;A®¬ ï8 âÞ3º²X/F°g©Ãwâ®Rh]µrª°¶*¸¾üÖØl€ër™«Ög¾ .¶Å¯¬iq†	÷S’Cð† À‰$5¾vJ>Ì¨A¢Û‹‰}`vp²V;7f
+{´fsï
+[P+¯[Éíˆªª‹¥±rõµÙÓ¯eÁP žI‹‰OA×ÅR7LzŽxò.Ôh7æŒl}YVÎI ïÖhñÔY8êÍ‰àÕqÇ¼‰´ô>XÜV”4š„ý·HÜ’ÉmP=x»†¶9ÁÂF¶Âz¹
+’@ +F·<Wˆ¥[Yñ:œŠÄZ`ŽŒˆM·ì:>Ôi¨º§/mìnCWö÷qí_^˜”ìÎÅÞìcç(J©y,Çþ”‹=ß£âøØjœ‰Oå]³h äº”ÚkXºŠÆ÷QÁC{ží	ØëÂÕFß]¸â´Ê/îß9ôyÿ~7D²fØ¬Så®°lmre×6!ç;#`kº&õ`©’AÎ™ÁÂçïRíÇ^,Tÿ¢%‰3·Ë~³/:“L®Š°ØœÑ+cû`Y3<L4òÔºwÀö˜²cé)EÀkçþYY}CzîŸÊíÝ] b½—Ê`¯yæˆ`ß{$CBzÅ`õâôŽ`ß«ü}p&–Ñ„3/‚¾ÜTŠáâ¬E™TB!5é°T
+1úŠÛ5Ï¤>+w—:…æþ­ ±¼)MŸ4‚X	d[‰Ô5Ahr´,wHTñbøv £,r7 P?Í4“Ô1ÉåÞ.¡À-ƒCeáÕK½RáÑ×¢—vít[P‹Q|§–kœ_ŠiÖÆ©\}·Ü>Eîçç²Y&ùñ¡—ðÜóÂïŽp‡ØÞÄ@RÂkO¶Pã±ð#q,GgCCv¬¡§–Y\
+ç]'õ4¨Œ“±‹[7˜,˜z„=„`[”^­]û7ôaôÛV~kM¶fÛ¡²ÁŽ•6õŒÜ)¢°Oû®]
+»`ûƒu¦£¬)ô¦¬îS•0|°Ãƒ˜hžºHzû$”B»;änSïì˜®Ê 5>upÈ¨)r.·Á9 ]æÛMÙ§ÿ”=–7X±Vý(ÎÒ(¼Û½eu¾5*­FS†à¥•Ñ:|Á¥	KºÂmLF=R“`wC®Ä87¨iA­ï-x¨„r°è_ß|ûã÷¯>>ýáý»§÷?}xûñ¿CèÅw†K@¯ñòáû¿>}|ÿáß/^¿~õîÝÏùéé­­}ùð¬ü=~Ñb§ür6¼î…ôƒÖŽXoD*í¨6Ã¤º`51H‰€¢ŸýÚó>å·Ë§t‚¶ràLd²Ùj«ëkCdSÌµM”ôDýJ[‹T:€vîÿUÖžíÑ{e#û=FxIåMB>ííà×‹N%6
+½ƒ}Þ´;­œVà¡-í&š>{g,©]nÉ$.B?F¸TÐAñ[<R! à°çíó‡<_þc ªFÐ€à}<Ñ†üìˆNs‡·ZÇneE:>é¤Œµ["¦‹˜Uwè/Ï>ÎXZè°f|«É)•[q„yý&. eßÚ®•DŒŠ%ÖÖeR…¢^úÏ¢#šÛwð¤”™¶·=t Ü¹¼é*ž/•n+ÂƒjÛ³… ö–‹[„ƒ‘ªÅìMœ¸…"ƒÄí‘­cw¢Þìê	¾Et„0VJ¸t¨TÀ30îÂôU$-aZÍe]†RüvaûlÔ½y"?áÁsg­\Û…Œ„“xêNW'r@Ã‚$DAC«Þ¥Ûb˜%óµ®Û1¼˜þ8Ug.Ý¼ÒªŒå=¡Mx}³	±²ÏË±¼gô•ºöÀ,6ëÛàXé‰6‡ì¼¬¥®°€ò)Ä¦­LUwt¿!B–—*îÝ& 9C§mù~/ftu‹pßœÁ´ÇmP­Äa];`í‘e¹Î-ðd™Ø¢”$Ê Z$žp—YëêÅc=¸³ZÕÍíiÍ)q­Êº:¶P.bí5…—(‰‘ÙÄw™#&î¼ÛÑ³ß$¡Öš±HÁÙ9GÇèø³F½æh§kÌÚàPCE–;Ü\­s+^ Öèm £ŒŸ½c¥­ˆ”ûeæþ+…£óËðb_Šºì©×þ¹9\(áHÐRÎLÔµß©åyAÔ‚T%[.$Üé#,?_9à‚5aÎ Ä™1ê2ñÔÚ(Œ#-f#8rÚV"<¢ÒJZpŽNÏ^å™ém–^û…ïZ ][Ýb¢¯vêzÔàì;«Œ`¨¶Ë§#ØM.9àWœ×Þ,ƒÎ¼è}%h2¢®Vý^Z tIŽ;Hþ&x¾p¿uÃ-‚5¬˜ÑtëqÀ)¨³™›6#^´c\ë´{ðq néÜKÈ3××ü¥Äx>e:cˆ{<FxÄÐ[êŒ÷3[äï×›œ0£`lÖ‚ýV-ž;Óæ"Ë½4ê—\Kê´ ¦$Ø#ºã¬uFE¸†Xi¤PÛ=úÃgöŒYSOy;é.KEíNŠSwžgÁ"T1s1Ö¹°N¿j’0Árgx´ I™²êÌX(®ZBÂ:ãS}íKÏ‡d‹ýÐq½1c½P^.×—âºEX„bv‡fDkéqƒâT
+ÃV½ÏÃ2Ù5„Ïêøî_ºTÔFIò^¥¬ ì;5¬É‘ÖœtàÒN ±¹Endq¬¥~ïÌ¢'|ëˆŒíÌ‚Üåöê§k"PÞ&¿fxæÁ•°À«±ï"ÞÝ×¼5%ôQcmeÍ:&ÿo±R5•çT®Dòb)hnFB™ží¡öpVjêäfØ#q
+ƒ#„€áÚèy@OŸË§O›Í'Ó%¼„þQ«~ PpplŠ+zÄˆn¦ìWÓ×ºƒœmíøT3––‘Í¹âÈ½R
+'„ŸC)Ç¡y°Ò‘Í¯÷]ÙoìB[É™¥f³…ãDJ»œéÒxáh™8Hc„s–Ü·C˜ÿTž±0ÐM‰È!ë(JÂCœB±Z›ìù5Äª™Ò´ŽˆÕ®,èŠŽ²¯òûuÉºör­Û3=ù‡oöÃ‹—ÿø;þ}ûêOëÇ?~øçë?ÿ÷?~ûôô¶«eµ~ÿAÇæRd§2ö19†< §…ÐCi—ÒB—Kþ>#ÉîÂ²¬=»¯F3ãyrp=~|Nÿà‡ý8SÛPZ¦îa—iuÂ:Û5\±Ù`ñE˜…4ÓíèøÂô®Ïêj
+ú¿fê%·ÉjÅÑ‘møS.µ#=îö9áHìG:uZH#^
+x’QÝ¬n;´Á»ŒŽÁ—Ì?¼†„Ó«ô‡Ü˜Íƒq/RÐ¢9 oƒµ/åÇT›‹ŽåÇãÖ¹Ô–ñ=/&¶Q‚2^Ž¹5P‰â~¢#è|sOÁ£Ìé¬šuþ½Y:ª5;Põ£¦(¹ ^¤K­J R=¾`Œ´x­g£¢¤ùIä)¶¡åÊ]Á›  œcendstreamendobj65 1 obj17286 endobj77 1 obj<< /Filter [ /FlateDecode ] /Length 85 1 R >> stream
+H‰¤W»’äÈüþC›’qŒz¡v»ã*t®b"ÖkSÿ¯Ä£Øxqêu4Ú<6	$	 §½ŒR=¥°WêéñÜþè¡plû)?¾®û8àb0Ø÷6¨08öÂÏaï£ƒ}O!¦Ç÷ök{%>ð¥þŒ2ð¿±þéŸTS{„ÇŸÿáŽ4?˜ÆBz¼m{”íï/öãÑºÂÿè1¤ÀF£yqE;òG+âlŒµ=”<øÐH
+¦Ñ»°í!Ã9î¥¦!ìÄ€¼z08µ¡a!˜(a„Ü,“^€K\LZR&DJoÝñy+’ágÔ ²¨×²Mb.e;ñõ.¨­!Ö‡Ç·V-Ž”PšB` ì­þì_T¹ˆ¥Ö&µ,yÖîœd'|@‹W÷œGW˜zS¢Ãž)“‚­7­HÙ)ÇltÔªì‡1ð3}òBÎš$êŸkçf°á	JÉ¹([íV2Bü6©UÕéÙù‚ïÄ}w¹GIXj“úù‚ŒåwÓ”ªC—uLjÄÝð§+éÁÚhð?²Vjíõ¢¯Iý¢EWµŽÂUøKE¦ð—ê¹uv“¼#Ä¥nayå^Jr%ÿÝ:n“yù‰]½¥eÒ˜~L±+Øb50ÖÍÄJQÁvT(7“|Sp5“¼é_aTÆxO¨€bÍ¾E‡¶¼Òþ~¤Ù³%¼ûàMðÀë[^xï>ïG×œÚëÄÁÂ—Ñ®fB-±ôGÌb-ŸåZÿÉ‰HL(®Ü[ÿNîWp­b±•çæVäk»­ž[g'Ç;>þžÝ|ÿŽÿÚî>÷t:‰ãd,ÄÍO°~s?M°L06êL&$D)0Ë¥ì¹4c3ŠFì
+‡Z‹B‚˜PÉ{á"P<)-Åç¸S§>g°¦ÔòO_8ç°äû¦¼4á4åµ_ÝÆ^Là¹¹ŒNopØwëääxÇ‡ËÜBòÕÌ2®Ü¿íÅ5"Ï´>ñd¸<¦ž*ƒhÒÞÑîU˜ ×Õœ‚I:¸ ÁÉRFžò{XA»6%ž®rƒŒc˜öMÅ(‘­_…šb©G•àêós;\:êå³1ó^¢ñÃ¾f¸æ-Ý7w:Õëé5Úçç&…ÒÂÍ£+H±Š£R95-ä¨¥[ß²Á¤åÅïjK³}¤aà·%9s?=›÷5èŒâÕ£†^OWòÚiq$X@úÚŠeÌB¨<kŒ¶³¯é>?ö¨¥+^>¡“9'šwÜ<—ú¸dÞÝõ¡Ø99-âÝqˆ$>n:óìó ø½4uÂ€¼—f¢Gœõ˜pÓ8'lš¯C@þ^1é­)%5ÁŸ×}Üç«ª_›÷IòÐˆy-Z²ˆå"Õ	^6ÎËj%ªvû¶/nzè¦ß¼Æ¼dûQÍ±Ôuõ»˜„§—œ1`¢ˆžc†ÓËŠø¿T
+S‘´+ >^dæâ?#3Æ±·Ñ³¾vY
+cŠ¸¯bU°Å$÷nÊøï2R »¯ð‚\Ä#v5ªê£1ò‰&Ñâ¦²m«Å¡X+sŠv„¥¿f#ù6koJy<q[9¾ª?ïËm…ßËv):bõÛ{Ó$æTtNvnµGÑ'ø}¸JM?ŸÅ!6™Mê^¹~ãJ¸rôÚ|6ÒòhÕÀk’m0µð®ZLdg³lÉ¾žTçºÚÈµnc/!åKÝÌ1¯uaÝ}g9§»:¥÷DâèéÓ™ã±öq	9pi¹XöÞUè³P¤9´yª‚­7i£ušØ±£(÷Ï»VìY’GCž‹2°£´l€Yss±AÒ÷<i…9¨ÏÊ¤3vþ§'ÏqŒ…s	øü9k ÝA¡¤ß¯P„_0†4FïGÝ‹>¼ipYÁÞIÁ…þï‡IuO”å¨D Yö¸<ÅZŽ‡€ÿ¢”øGÕa”Æ}‚µ„jöû.šeÃt@x|IæL!cQ¯#`Tªº/ï¥µ)˜«5LLãHFgµË¨lÒz‚Ð  kZêI—¨@@ÂÏu(¤ÃÑðYýµ7i<—»3D×:ïlÖµd×¼£_ýÿçö³ÊÜë¿sœóšÑmÜ_ÿïwjpS.§°¾ ±¨†–Á>;u]ÜuánµðÖ¿+£_›Ûu¯)ÏÕl][v<äÎo\gZ]ì¹¹Ý8ÛÎé\§ÅoÜÀw×c?úd©D´rˆ’ç¬íUWb™ã½ælËE¢Ö”•A#¦‰úá‹9Ê@€¸b³ý+¤ÝäÐHÜ,iN¹ÞËŒÁÎ^:´pxR&þ\0º¬×xmí¡Ù~‘uä3®{!@ïnÅ·jç«Hºp³×òD(É0ÊÃÀÌk‘ñº…™©Ë!OÃë”
+Ž(­âþ{!t®v4“™Å³—›5Ö¹f<_;TgíúÜÖFŒs¦-%«áR~W(nŽw|øÌÝ³Lú^<[òÜ{tó Öj«—˜Ï·@~™Ø§¼²LXÓZUÒ-Ž9Jâ¤)ë!¨nÔS>NFS.ÅÐž“=Z²=Ùc!Ã*Ó|ç¬u‰DÞ%ËïQÊ³Ã¸¦ÊÚ"í0ô½u¼fªÛ¦Ìàqpb³VX\³	‰­1ílý‡	”õûr¤Ž¸l9­§górºMðÚ¢¤/˜'ÀìrzŸ ãx/œ“Ò”ß¥`ïN’¯í–‡:Ÿå›‚¸¥[Ê<«oc)µÓrW¤Ð%»,žÕ7tXáÖÔä9ƒª××Ï\ûqÓxoñœj?ÞNü®ýû÷§"x­½ñz9ÿÎòñ„æ‰ò×æÎ“×v3{ü)µN´çævç×vßÈnÇ{æàøˆë8®ØïÃo¡¥Ý®•°ùyíÂÓ¬u†²7¿mÿÚÆãÿ|üùïí¿ÚqÄ*Ù³Ôxm­s%ìÓò'üep•é¥ °¸¦`An¥ÍÕÚžÌ]W·¹)Æ!ý—Iw;¥(ÂYÑC€Á$JŠèÈÒÞÃTîÆ ÄâB+Ö–Ì+æËÏJÕs‚Ì‰Ìúý6ú{QLº° nãXv±bZ¬Úò‘I%®o£1YJsÃ¦YÉVèªÏNÛÆ×Bø'›&7Õ dÉ{•öŸž6ˆ‚§Ofc.J§ î5J 3ï¹ÂNª¡XZ0ÊÞUƒƒéØÃaº¶×¤lÙL-þHNƒŽšBãó¨Ì7P6·Ð7àSøÍxxÉ>?Þ?8Â¡b›)¾†qÅ)= ¶ZŒŽ€À¬&a;Ÿvt†>……ãÇRÄÑ—»¼ëŸrÜÌææ¢‹$Ï
+8˜X¹ÿ$ÞTZ¹P_gý,Ò%Û‡·#Ž©9WH®ä~ªó¹¹|Î]îÝ*-9þsË3°Ÿ%™q9²wÄi¦OnÊ¡Û‹XKxàeËE)âNpÝj±å"D³g¹ÀKºÅœ³[÷µùÒt5¼ÊýéÇúõ—BÃ¹%3#¤uhèeDòé‚¡È›Ã×¼+$ËÂµ¨s§æÙJq§œ“!¹ÐJL¹Å•Ì¨Þô¡²ó—-å¸°ÖPŸŸïÈ7õ^>ñµÝ†ãÅ½¤øÜ\u|mwBr·DûÉ8LH¯¢z1Y¥ùÂs~&ó@ÍU>HIÕÉÚïgnü@¸º'Ã¦|è¢—¹çê€ASÇÒ<{IlB»ÆÓUžT¾Ô|Ä,bæ™â?9‰ìãLzùÀk»Æú’ÞÌú"ñ™õµ¼ŽYšëéGú}ja™JšŸÜR/ƒÅH¤Ú²¨¶óŠ ›ÿÿX¯²ÉŽ#úõõbÔäž‘£Æ6íƒñ€1FŒF^èŒ¬éaþÞçDDÞZnVcBU‡òfÆzâ8.]†£Œz8Ì~Y²ab’ác”“F­Š>V@&VYp’bÉ"}»÷Êß§û‡{÷Äìô½;|wô~å¸ÌÅzû¸NÉŒ½j5Ïfe5T×=ý¸öõéžÑVés-0´†ÝæÂáŒ©âkt[Ÿh”	bfeEZ›h÷ØýÓ¹{`ú½ðJ¡ök¯É‹RÞUŠÍ[v«uÕQ¿lôåHìÚñqéî=ÅBígY°×F”ã¥8cIpÉu_âˆì9ˆ½èš‡šÕ@	êç¤hš¡²Uëð³úSx°¸QBÐ“®y]8ÚJ£ÔCÂ]÷ô²+Ç !ºrlm’±–ŠËQÇ†K9Jmi¸v!]'Žœ‰Ü1‰ãGLà“Æ/H"Ì½/\©Õò…³ÉD&¶k9.þîÞŽ]ùáp+·w‘ã™yô­Ý
+:3ïì”ªKŠÆèT/bÑ«4ÚØ¥¾=t3_¦ÞÏž§ž8Ø®·û¢"O‡›Õ{½Î'Çî–•l[Ûº¬q>¸¹ˆæ¯aiJ	3£ü‘Gv[kƒÑ¤†½íy"*çÂàåQªŸôŽ£QDæ4ú„©^jÝŠ)ë<¢$‰Ð³Pg®­Ä¦Í¹øêe´x¶6ÛZ¿u["CBuã,ÞÅˆTü±ŸiA{ŽM,”w¥žÌAsœ@Œu›&íµÉu\–à~­{–MŠÃ½œ	ßw×ªU†ÌÒEÝÓ	-Yƒ¼^Ï*Š¼*‡YºjÌ©"»2£«ZN£ƒçBQ÷Óñ•ü\åòqöé%¼>^â%hß øÅ2ˆ¶"­{ƒ„‘õ™ÚÙgÕ*s» :ë-P/£m…¿„Ü‰ÄWÝ7{G°°RÛµaXK—™¯Ûír4·°gÂ=[´É¯Z†í·xÛ©«ää¨Qü_;[}¦\B÷”{vp«6Ð%ã- ±0†Hž±-W×eÎ·äìÊ³¬ã¢æ?¼6gË/Kñ
+jín‰…7ps‰±7ÐøÆ¤/QaËÆùÙÔ —%Šè+¶ýðUÁãZÊÖdžñ%.b-=ÁW2bŸÆ¹¾³­|[ßèÞÑ=¿s¡&0UébE‹îr{£còb{Ñºu¾3Xc NÍ[
+áF;‰bž†fm–¸ª¨U[7ZR¶X!i¦Il#%¡[/àòä'•)ÓÁ.ŸŸ_%ûñ~Ú†G“òÜÕ	QÖõ|:¼âÎÊï&ëk®…:s)üJïìÒãqéÖãýô]tþ‰ìk1Œ	ÎÉ7ö“›S™„¦!±™WÙSZ×Ñ	1×Íæî¼l®8	ÂynF$D†9	FS?oú4þŽ"ÉÏŽ$ž¼RZ>®â}¼›Š 5<6V|ŒšÜÅ
+¨{r«!22‡QÔðÿƒrdNW¾R½Oè¼v™|ÉÊáÐaÕátïí£!ýG>nbÎ
+œv8ö¸l¬§ÃÍšÜ¨Þ²ÒË®XöÏ®×¦_W°7ñm‘+,]Àî‡?Æñ«¯oÿ‚_¿zóùû¯?~ÿíŸþûÏ?~÷ÓOïühÆoßÿã_/Ì_ýþýç£ÿqLéëC8¾Á¿o?>á?è>ýçíüñ[üø7LŸåø»ã_ÿŽßóäŸà}HÐltjs[÷3ËÓf©6Îg_í-§¯>ª+8˜+›Kßéù4·Û¶ECÈ X—I	Ì%YâP[° 4°Û@_&s7²4Ÿ|^ßü¬íFÇx5Þí:a/yhU	 ¬¹2QÊÈÆÔfòË¤6=cÚJ\ž—ûƒ§œ`˜?¸ƒWÝÌ@î©ßB”[¨ªüâŒ”ÂÅEkiÆ¸»ù£Dú]}ÒcÝÍ#çæ/ÌÝˆy[Œ5éYàMï ™çåÅ3Fh‹ ˜µ…WŒ\Ñ‚„6ãtÚ=dY¶w²cGÞæõywßó/5-Ü9Ñ\1âTUÛÚúH OG»úÃŽq>âñÍnz ÞÕ†-L}ªƒa6ðC˜±²
+šÐAQÚ4’r´“ØÊ‘FRÑat™÷r¸PG³­õ—ûp:úÑgŽu†QÈOº_ ˜•Xì3`)À@R>¯ÌÈ:SÁÒ­’ªøX!™…g¥q ‡¡‡IV9xçÝš%ÛéžÃl1ÜÇ”¨9qYÐˆˆ)ehŒ-Œ£´n¦k­Äæ®!g5hy}ìì¤)¦;hÄÏÎÅ€öŠ]0Ð¦5Ù÷	:šÂ³Ù[É(±iwÀ«ÚªWg¤Íxsñù¡¥éœ3[fwñ{b…!cý0‘[)i:v¥),óÐ÷qC“¡ùXY±E¯LDþÌ©ÉÔ1À1±¨Š†Z(•ÌˆÅZ‡GZòü^àãðdwHN=:Œ¾ð©P-,bn¡¾Ò&Èuû<X­:…VÎþ|
+Ng¯Ôeô.<C|$¡·3´Åû#«ÿ3Ó»ûTªÙ2fÃ *p`B¶ô>eg õÙjÕ“Q"<5¬Õdã"•ŽÖS˜XÿpÕhß—`äÆ^´«ðV©5º1JœQ±©ì,šPkWðØ?*¬ø¥×ñÏ¼@+%ˆNÕQ\ŒqiÕÌ%™ŽU»íÚÅCº«µf]hæÞÊÌ¢a™iˆhX–™»€ãÐý{@œè0^'N0Úä[Å†PO–Á«4\’ÁbÀ- Žö¾û
+Pñ!\d€©	„åo<¨è/Ö€AÜrŒ6¸Ñ‡¸Ñ¬ÿ»_|˜EWÝC‹VoÜB<3¾8õG“»Ó¹Ë˜BH+´©=øâuÓ~d¶f“ªzRÚÙñæË\Î™ó@$¨XÔ!#Ž	Ó<:­s9¸p?‚±Dàbµ÷	ÕU«F¯ôáÛ
+•FÐƒ<°³ˆ1v†€‡ðËPËBëää–¹Ðœÿ(#NI3‡Q«`>8”<B-øº’kÛFÝÝe*zè’«¶¯KûrÁ(|5£5ÆÒ'œL1mŒlNlñØ¹Ìl‰³‚*§Èá¥€±“I‘À§ÓðGæ¶‹ÜŒ`szã	“±‘k%à
+Èc^ñ+ÍãÒØ1f†Ò¨`ŒÔ|0"=Ý¸QjÅ¼
+˜l¿ Y©ÕÀvlzì6²µ¬*e|Õ4m.â
+³¡©)Š¡<o‚.4”ŽS"‹ö¤-ˆ9]éæDxÐ„ƒ@²’¦ÀÊÈ°,Ìˆ@ åA$t~_mæÕ\!Çô(²¨#ƒ‰B6s*rÎæ÷RÄ“Pœ`áý<B³XÅÙÉ>33¸O’ž@¤yf
+é´ž‡g fTÉ¨—@Ç&7f;gnaÜÚk´t¹:•rcX\£¨¶`Î‚…þ±Ï”R~Ÿ›èC0ÆØ’å@	–»U€m°Ñ¶J1ÅÜ‡âÒ·°ï¸º4Òf»ÞÓ2ù¼`›¡½¦)œ1kiF=‹s[½£Dq[î–•núáßÊ<™·9Ú|´†ç€ì`h¿¼[\ÚØ| b*ChÕRÐæÙÐ·p›62lKNŸ÷¦ý"É8ßW¼„1ó]Æ?ƒ¹ÕÇH­Oy™Š‡æu¿«cYá ì|â)ŒÊÊôboD»–%±’[Ó†½Ys–\kxa;—¤~ŽE ~”ìû8‚–±ýzôhC¶lñ¤‚¬äÓ÷Ò‡z…9œs‘¸«ëÚ…±„Dí¡•˜ ¬”ÎNÌ±t(§1EÖqû‹O4T®˜ŠšÖ¹]¤õl¦’šNƒàwO¬pX¨ßAð;I¡€%¨ix—âa<ö?º«mEÓã>Á¼Ã°/²t«Õ§Kï‹„ß$†`Ì²»Ø	Ì\8>à·wI*õ?'³ìÔtëSëP*‰XK¢teót]w§ËÄÂ‹Isï×»g0
+Ë§dÐ$—}	…5•6m×óé.ÖÛZ‚Ãm±±ýPÖ=R	Å"0 YTkð/–™žþ„ ¬= e!~›\žÆÎÞèáO#¾ÃCŠ¡ÝU8(|èCló»ì4ÄÞƒu^çôùøåð­Vü‚†~È_ÆËÕÌÖþâ;v}zçz÷øÄâ7wùêïëû¿=~zÿÓ/ÿÿñ_~þùóO¾ÿüÃŸÁ_|óøøááó§K­_Z!âçÛß 
+~‰ª,—z)þïÛßñË?ðŸÿúí¢—¯/ÿù®\>Ù…ßýo”&Å4°Þ¢X11D ünðõ9ÜF¨Šës#ßŒ<ÒËÞ…ƒÇÑvÃXIÐ¼0FØÓ-`ÔÑØ„'&rT{`Û$|œCs CiAÙÕË=¯ok‡mi‹ë¶…8…šØ@îìš·Ç»ZTéJxÌÍÃEl]p°KíáToÖôo=êÞXÕã#Ð øƒMI·„!×	:H# Ñ?š q­ƒCñÄû´•¨ºÀ\³(%2Afyîw~ÝX—·=Z†e¼é=Ÿe£Å¿_Â¿ÂÛDÀ­lwÇ»=@,f»LžôæŽD }‹8ŽÎœÍà G×l`KÄ¥šàvIêp_^¦
+VÏ³ÓKËŽö©ÄPæMÌœs}E«b°˜<}Ð×	Z£Il |”¥âž÷GÅ%ßÐôEÀÏS:oF0+iÂÈ²? üFeÜ"ã#á•°b§ ¼Ý7Ã¦×8°µY–ÀÝDNÖ¢Ôø±nAºuñ>8a:èS7ÌºÆ	J•fÍ­4[•Ãøb²Åó`î¬bAœÈ}Þ· 	¸[ç]	×š§±ŠV¦g.åÙ¯µYe4c¬¥ÕªZ¤dLžlÞâ€T‹&ÆGY•X×v«;êœ_RŠ=ïïÅaze–÷'S¾£zhÔôž6Œ3L¿Á°3@oÆ4Ð#X€ÅÖš+á1½Å÷¤©+Šƒcžv¡)nx{ì®žè‰‹€kí4ZÃY$x·Û}È¿@›0.¶÷ÔFc7~˜’'[cÓÍhG½	/:ˆ¨'•Œè$l™2K?]WÁ6·²¿fÓ QÉÆbÄN\ÑõUkÀl¢[LÀ¥eeL ehÒsuò:?_vÉî™<W,@¨~h=‰ß^v'4ÿq`Ñjï;AƒXÆÜYØ¥8ëÇæàÇÐ‡ÄX­F`ÛKx´Øò¾w“Ã
+Þ=4 3-ä<ÂkZ× ‡¶$—Î¼â¾éXO¬-a³ÓÛm¼àìŒul*Ž-s$[jg¬ñUÏ1—É¬êÞó¶±ºƒ0ç:øŽG›½#@±°U´ïWcÿøãÒ@Î-p¹-4ÜÞÂö)9%k”…÷õ±-;ÀV‚=ó[ÎÈN-mî§Òš‹¯_çÜšHåZu²°-ÿÝyÄÜnÔpÀwõ<:u°MÄI(ñ§|}Ïá²!÷8Œœé@NlŒ×3+u^vÎŠµx3]Zðk‹bøUn`á[K>`c¡täÉmîsPåÃã}("q¶ Ü4^e NNŒÒÛëæ³–É™4Ð¢ÞlæÖžß¿…J#Ù/_ÿ‘A± /}H±Ù“Eôvj©Ñ¦kk2›wFŠØCwP+$Xf¹˜„m;»Žq,2&àÙ„”‹™˜$5!œX³¯ÑÃÉãS”ìŠÎÎûmJò¸Ü_F€å‚Õ¢ÙÎçò«|ÂCÓ:\¡¨Ã¦æQh¶0x¼P}EBV¤ò‘HÝ=ÍjoÖ jåÑÆhªÍ4º§'…ÙŽªp§¬vƒáíS¡ëQ¥CŸÜO²¥AØè 0Ÿ]6AÄmXk!.s0.9 `”UL"}ÀŒìN†À±¿0°à+IQ˜UßlÊ±;Û
+Aâ;YÊÄ‘kèj’ŠÊ3N•4BØ“hrŽS°FÁ{%káÙ1;Á–
+ÚtM­zÄ~á„°GÕ™_-d˜	«·ŸìTMÎŒ2ÌN„6‰iØ+:@ðÏž:X½¸»-;fvsrÔòY-sAKSÜ4 p¬ºŽhô b6]ïòtH¨+ìOÇn¥·ÎÂo¾ìVRÃ»,»Y&F#´}3YwÆOì=†í–<;ç­PqääNê°BŒªÐÒœTz¶d­´BömuæçIG6¾F=©<”¼o¾#LQa«4žMN¾@Ö“¢LZðïCélícF›ZáõœøCV‚ÜyB:æËjUî[$ƒ8†¦æŸ3_†¯¦
+Y"çe»U*–Fë6Ïf1z7îçí¨SXImÕ¸Ô'BÜ·IVóPJvWÌ÷§ÊNÍ#Y`kGðYì¼E¢êŒ/Ð|i ôExŒìÓÅX¶È«dn0È§WÝPÐšî#$Z	9¯02rÂôRu‡;t7ÂÆ=oØÜà÷0ÒzÌ1ÐŠÜô…m¼JT½MüÚâòî$*UÃÏõ–ù<V%¡÷áÜp4.yáöJ6¤w~þÑnwõF]@:&»¥SKcCCPFÊVs`„dPdfŒçJÆ@iõET“$Ö;íHØr(Û€B(Ú ÓEÈQäb\9Í:û”šfkÚ SÕ›!‰¯P
+t „+(Eî£<•G—f+éå†u%Ëìêrô%œ«ŒNˆ@2’éÂ·pÓ'èlþaµ‘úÄ†~ç{[í9Š÷N²–zæ;·§nŸÐzæ»ÆZc°jKÀ¶ÕQ”àØÊ“bR"ä®‚›Ô%Ø*½Å‚ÚÓjÔ²½mÕ›êÓÂÀ·'èÎ½ÄxûÍdp2$r’Åi
+¸5¢C¢žõ¥„"ž1³ æZÐÁN5µ“X±*eäýEþíÙ£Ív˜<XEH>­Ðj¸ ´´hÕ÷¦û”ëMCdÇ"ªšÚI96ÝQL+­ƒ“Å¨G,×`º{^§Î±ûÖðWÂ½lÂ’9ƒ‰Rv2;¥ê+·èoAs­a°TÙX}H¸­IX¢Ht
+0¢Ä@q²p‰),‘býß	»¼&<JÚ­!J,y´½ö‹…#åtŠÆ0z <W—Ìœ'	ØÚTr©ƒÅÆe«ªÇÝ­˜+ñ4\OÒ®¦²X7cF ëâd æm×Ñˆ\%ð)o€2;7¿Ñªè‚åq5¬ÌuWgoÀ["ÀÑJªÓd°ï`;PMqm°]ã·¢GÌ@—4+ˆ)íJÆki@§$Ýí óVRYªÄ*e`óñbrs–›3Ym·£î@òÏè3CÐ¹Š@C$û(w’/
+Â^Bí3 æIÈ³•„xí”T.å®Ì,²Úc÷ÍÌ®ÒS;Ø²¥QÙÓ00*Õ¢ØÞfƒÕä¶¢ì35jUªsø'ç:ÊŒð\šŸê«¤’·hhÊ'Qí”&·¾Ú¤¹Xáîd&ªä.QÊ ˜_ÞiVó•%0¯sî2±$œÑÉ™Ä¼Ÿ£­:cˆèû(v„u,=õºdËØýž£Åi%ÀÕXÅã¶«ÜÈ–†¥2l‰Ômû²øöäï.(ê9ž×…’ØœÛµ°eš
+>\µá:Š–RT¦ÎzÉ6Ž—VµQm7&ÅE{kµhDPhK¦%µt”‚î3Î`›òo™I”…ŸõÉž…° Ç¼Œ#ÌƒŸô„gíà¯{ºùO†Š"°NŠ:«îÛßÉd§HÒÔÝEmi­6&‹@LþèA‚k™äÀT‡À@ôqÂÎjÆ€nýj„Å=x6M¸–§åú¦Ms e	wLá»êùÐÙÎe œàäß½m'#¹™¦ëã¸Ø£ýþIÝ)™TP¥n-—E™#Tº_y¢ôÂ·UüvêCwNnþû7ºä¨6¬é¯äøxgâl,ìº“€!’Eýò%Ò*£~GÆ^«êO"üŸ?—SXDÖl0½<¤á$×´ÒY½ÎêànÒ:@›Œï½.ØÖOa © 5ï_¯w!ÙX{Ð“vÝéÐUïïæ”­‡G/|—š;eGgbÝþ%' ÃÌH¦¥onK€µôbd–/©©¼Ú÷à©ÏÔ³H€Ô»* î®³!ŸXŽ½	,[ëR¨Ù¼ïxp£_Ú) nï<ZÆl§•­b~þ_@a·Ä·|[ã¤u~£P¸ëÌr?=úAdˆÓP¬œ´Æ‰ p£5Ólç¥É7âìr5*jñ,Œ&GÀG«ø ƒÄÑ1¸—‰€â_F¾¼RçOb•ñ¥xŠÙäOïö\€ÆÅ*àiˆGn£¥>P÷îT#Öˆyë8Y€U†šÿ—ò´Tr°ÿ,†izâüÜ{–BÌU]É¹QJGÏ!øŸº?&ï÷¶«Æ¼k†¯-l4Þ÷î·ÊN%”$@¯T²†‡¼õŸ+¡ì¹ •˜í_D[Ë8` W;~lP¹Ø“B Ra~ŒÊR ÊG­eâè<šàg	ÎÆƒcçÞç\Ì¹L	³Ûa}†Î!¾º^éTl€Q½÷¤¶Åékô%@OY¡ûh¤šp%ƒ\©-öžêà¶zí÷þª…f÷ÝçÐ'/®ªðË6ŒÓUY™uˆë#Rs°6Õó ‘´š S1Ÿ“ìo&l¥îÐß?™èR*®Kð¬½éTËÉàÖïËØõèëÌUœ«Tžó”pÄ¯'E”¨-žôPÑ2ÐæbÃsdæY>Km7†åw©ª„CÔ=‹9ü%tâ‹(lZ}Híl».WÓ«)ŽŽÛ±¸¬›µìq¿›3,.Á øþ¼XÕÑé
+`(æw¾ëMpÆ’É
+æ(Âö¥Â6v$5Sf¹…ünõÚx]ã·èOÏ>¶•õ#š¯•V™¶£F^omÈv,PUn1$¾ƒ˜Y~^{tç´.ÐØz}•Ð6Øh­»ñ¨JÐwJŒ¿|^Ï8ÞêÑ·_ÏfmÌ4|~è¬ñ,R>îÒÔks=®µ¡üf ‚^-´W»®M¾m¬¥ZAÒv¯
+<ß‘>aïË´½S¦¦#3Xfû‘#µv±PF§‹ÁJÛ÷:w«SÂ§Ömc–z¼'Áä '[*ÿë©<YoP–0ÈZ6ÅYUò:„9»
+CÇ?+TÁ ½w5°£(e`Ì#½ÂnA×¾ëU2ïüÌ“cœ0.89RK´d×î8¢?àˆp‚Ý«@¼QÞ¢wÄÜ{ôr–Ë*hòè(•PFb{Ó©Vo\–Õ™å}~5
+ÿ¿ÛS¢K€{Ø50=;ä=®‹5Ô1f”l«Ù]#w±›Ÿ„»ÁÀÆÖtô/`_Ãh¢.™èµ9Á>rŒœý·`fÚ)`²
+‡ÉÀ€n!¸0Àó¤µùtŒ±âFæˆmdFpSË™•–àìv[ÖÊº·xÔï0Œ7ìlD¿¯í‘úFP©Á &* Í]•1×Ñ:Y\Õr±(žj1Ë°\Ùjcî§käÖY9³ì·ËláÜ­¹y¼¥¸‡û"Ž’nžþE˜‹@påjJðŸÓ¯k¦¸¸µLªàÈçré­UÎ7§9#™J1;£›ˆ/ÁÍaÌ³QJÁý°ü³6gTyþeZs	>f}Îž%ó%¸ŸJ <[ÉØÆ¾°[±Ñ†Ç”M9PÆvj–<[SÀÇýå4: û?Þ:ðÉ †8›¢·×®j´Ü„£œ_ïO¿®™zs;™¬´ÞE®â›ÐA"W7BçQÉá­OvêøÆ¡µ—Á³½Ö)Íè²ùó÷ÏëÎâš•YI¿Ðø½³+
+Þr_·w¡šÚ}=èOz3Ô3×ƒX˜FãÑh‹›5é9K¯£KªË†N.g»ímùEp¤oî}o=Ð»!kÑRS§ ÈŠÒqÖ°aí8Ü÷¸ðOzvèÿTÒ¨ýÝ•k˜ìË	‡€O°Ô\VÆ.ÀØJr²aN÷)¾‡T™=Ñ69.êÙ¿Æï\g–Vê¤Oþß.›×ÅHh !´Ò³´1 :Zí£îkÓU«]ÿ_«é­}¯·PÔíÛÀ	ý":)F0°B'hÉ1›|l3èLÄOÞ·|C'«Û.·z ,‚ncåÁ£Ãózù¯–Å‰‹iwFîÚ`­Ôb]ÛàOp"™i p¿s	ŒºyÖ¸9Àÿ–²à!Úœ¡ÚdÀgj\H¨’;~–ÑžP•S^5fEæî}È]ÿ•¼vMXÎj:r¸Ç7/¤Ë…“ÿb—Ú=ð*¯<Š“ÞyVûM(Ö&š»L¦µ÷+9PV4Úµ¬ö&Î¾+¡g}pAÃc¿¸»Cî*@›o)Š|€üÓY²†B)©§WèéÚÊá€eÌ»)í:lµÌk`ß³w+r6@©–;î1iýª¶=]GÞÒùÎS€Ä²+Î‹ú#VlE­kEšýT*À:ïšö=rlÕ…!¹;ÅéŒ”~±Ô	µ@0ò‹pi“*l„tz½7òºôF>ª-³/ûz-=ÁºwL—–œœ¸	R]¥uVÎöÁ³»³{T$•ˆO®OáÎ&¶í^_t*ªxrnZØr'èÍ=ÁâwS\kËßß&ïéãð_bV·N¶%"Û*ÏB•Uº:ÚYæP"ÿÄO:2–ÉSÜ³"Ówò ’Ê™<€[çä¹Â9@m*–£á€M¯öä¦g5[-õr‚ ùKÛg[œ5Yç	fv’ÀŠ?K]
+Ð»HCÚ¬¥¶Ñèsƒ÷µ„Fƒðz±5ˆõUøÿi¾ïý_a!FspUÁÙñuáTErÀTã%bª%ƒøÉëR8¸n¨¹aë’Á%Æ™sÈÖÇ[¯4@ÙÐµ~SX"IN‘å:—<1)Yé6I3v©µÚáÛ3åO‚~WÓZ™ËC¡jÕi2š…à"ÑÌCÄRFQÕ«æf’3iš‚n«NàýözñÄNÛ"¤ðô‹ð²Ã%1¿c‰z½?­:@ÖU)®ªšTmIwB˜F	¶¥³PDƒ Gè‚¸›|ÛQÁy;fª]²Y#ô‰m£äúŸñª[Ñì6‚O°ï07û"F-©õsi¹HøBBÀd!„°x“ÀÌ…ccòö©î®Ö™ùfaYï¸Fjõ‘º»ªÄ¨ô‘Çã)ùÜº2'Q%¥äñwù“ëþjÏ¥!RAÏQà¯Ri’Û *z.mBÔ6R›šÉàæí…<¹”4f»§fÈ*Âý®£¾óýv•0*ÕÙ©Nh"Ÿ2FÕ8Ö Ù˜anÝMŽEM1~Ïí»Mn_’1¢v®Üc-®íR©þ9P,1Ple/ýhº;×gÖi’Æ­×šàeÝÚ"=W›ðé)„µ¯Õ“¢®F¬>”‹ãØ®¡žÂ8J0y5.<ª®–çwNŽ¾s¾3ÐèÁZtÆJ`óŸ¾Ì¼T½Židhß+·ì#ôÀUCòö`‰àÈá5XlÃ®2š“’×O’ÆŽ…Ügÿ)o2¹}RßãÑPçQ;e°ËÉG`©B!;ÂÌxUÂjH‡å¬JqÜ‹^ Bé¹v+×Bp2ªóÁÒ)ŽÇÔuŒp-HvO?«‰HJffp×YîoòÂ`øDŒµ°=TÇýìÏV‡€¬`Às	mý ¡`2DL¬×Ó7M‡/ã1ù‚6<Ue­´óIPjl”‘ýTµse=¹³¤0‘LÓ½;½8ö!¼öŽVÇ‚f÷y=ñ¬âlhðŽÙ8}®MA%3AhÌ ·}ô#ã†ZŠ‹ìA®ù¬±£àè¦ÊCü›ÎzŠñºÕIk¢Ò‡Ž ÇN‰ Í²\ÉÛÒæƒPŽ¼M²^Q2H\nìÆmhx+9RÙW‰V1ç¬oÚ(ÆžqÔkÿŽ©nv¦æñ¥#a'3dYŽ²úI¾tå~¸À‘'õÁ™îê!ÀÚsÐ6ÓÄçüð66©MAß·•˜j`€: ÎVß€cîä/“j™•EÔ zó^×qV{¶kžYÙë	0ö!1Q<¡ô\;úõ®gØ¦šOÃÖx-¥ˆr®OÊ)Sî¥INöº	æsãáëÊj©_-ƒþÊìGöVêz`9C@XSO°@ãºók!j¶ðŠò¡*ÀS,Ý¹ÿu»¥üÂHÀðÁ/&~Që‰0ÒàEU&›^aS¼(‰¯YÃöHácþFkÀÞ  ú×&CÆ#Âý®sÿ
+zžÖ5#ÏÅ{Î’’¨ƒ·ðxaÖâŽYžŠPV¼Ú>~ÎÔ×$Æ±éØX_(B„õ€.=â-ÉKgGS™1ŸìÓï¸µµCW[ÈUré8ÛïÒ·ï*ñGüÏÇO^`²ž´aJcX4¹`ÎÓ¢oVßN\atÆ]9J5~Nè.Ä(fdÅ¥ 6L‰%Û³¿(Xò††Åáöf&Zb¯ÿÕ¯Çh^iVÙ3³4GÙèÊü™n[«å4-¦‹¬5a(€3Í^‡þÕ›2Ý“jªši}"ÜrÄ­¢óÌ)“ÄëSøö~:›ib¼’UÃ˜Á[Ò7ÐÍdX«LxØP´P\æüÎÙ…•x¹rÐÞjÈ¯wN¼Òj›wÖ{çà˜ñ²+á5Û¹á»Õ/¾n‡™ªz{Ÿ¯-‚£³&à ö&AuÓ²©OŽu} ÏC‡—6åÇTÎP
+.§ç-ô,º.zëšIåÆæ™ž©IÏˆwéóz 
+¨U ƒ¯¦0œÕ‡
+àœ4j{Ì ñž˜Â …o ØW%AjVG¼G€k{¯(ÑUv§;ªÒ·,E¸¶]\«^Lø¡·ûGêK€î0r¿{ÃX‹|K´9Eã'ðŸ0Âj“aÇ
+ÚµdTÖ6Ââ4%hÊ†ÛçÈÝ+wCŒ2¤[ÌÜ½üì*©\,¥p IƒöñAÀüzÏðÖéc~CÍn¢”Äê¾îÆ²¼ÏQœ‰()5÷ïR	B^ûwñIae³%ÏŸP
+â!3ÀÓ``Ï±jŸÃÖèÃ§;"Ù}ä¨kXÍTÇd»˜Z•‡Éî  Ôx?|í‹`ð0…Z³)rp™˜ ”¶G‚Å™Ý4±…YlX–T+)ùw•|Á2½­)G:
+ÀAí6R(ý€QPšïu%ÕjÝ¿…WXƒ »{G)×’Æ .54á¢33h¹–ÂÍÀR¼û~ši…â’Ð^rInØoƒÉÛû«sÖŽÈ+IÎIS½öEx=„¤4ƒöúó¢/!‹VxÕ”·Ú3òHðî¸¤>y[ªOª±.BåòÀ@ BSÂèW»nîŸP§”ókr3|Aêþ»ƒÏM”ÂÕ†`f0ªë hÉ2Àê2WÀò?c›®pT•êŸ3ÃÄè9ê¿ua€iö3À±&®¬ÜÖf+ºËàÍí¦ˆri8Ëu÷´$.ã»t_æƒ\TD¸BðpÜ›{I:Ãi˜wVSêv÷)§~¨9CÍÅ2ˆ¹ckSà¼	qU%©Ã5D×©Êr’vJ8o¿ÃLÆe_Oô:£«¤=è”DO„‡øh¼à™£Õrõhü:È•;{ÄÜ‹qìé¨p±ÞÞ_IÎšFƒ³(“´
+!ÕÏžýðvñí¼Q=Š¡É‹(íˆƒÖÏ§ŽwöSÍZ$££7´sîú{"¬³31}Éµ6ôpW
+(¶ä^˜“28äk	§g`_´ì‡w¸jsîAš‚kç»W41U9Š$uB3Áº”Åíõ4-%Ï ¶k&h”ú˜ïžÿx=ë<lo-‘]SAa©J²½+Ú Ò’íõÅîÔ
+-fšíFã¦V©îkL`ìîôÇó’©A‘‰Ûó’zôžÍ›Ûû«¯rËõ¸ UëU´³ð6\_f]MíyI{ê‡¤rª¸ýßÅÎ†ëgÀ‚Aecv¨À«q˜v¬hl·µãžö•­9L<2n¯º^Ä°â¹ì¡”ß&pù¡!Ê_”ÕNbºã¶ÚÒSíPÐ&²Ê°’q‹îqŒÈäÊB±oíø‚
+î½Ó¯¬Ö¡RQÅU¯û
+
+¸ïZùi¥…T2Ôòs[°ö[Öy]Å›ÞÐ=ëÛ+—Šôt¤wç?ž‡LNíè©ž‰õ°VoÔ #7¸Uƒ5t @|ûÐ+'3ÓwÏ’öÑ¡vØ*Yw\©Ñ r«Ù»š±ótžjX®Ñ§wO‚Ð†›û×š'³»°·ëFçç‰iã§sCa|Þòé$4ŠÆ5ßÞrEŸ}p½««c
+³évÑ·sµì+ú]Œ.)Åð‹)Íèh¸Õ¬‡P¥å3ÖÁ§¸Ca¥‰¯¸,ÀA+·Ïx1¶y!.ßMàñ?,ç¤ÖÃ† {mœª.×“áþcú¦gÄ ¨ÑæDzOpìFu	Ï„Ï=©Å]m Œï»xLBÂ`ÄïC°Fv®3Ÿ Êåòe˜Í”N°Gex¬^:~Fs1ªN‚EOÔ×	db5ÅÒ@§”,!ÀTÜlÅ[..>ŠßÀ¯cX}ûa?|ñåÃÇ¿â§ò€§y(þçã?ø?Ÿ?Œóûkåo¾þýúÇïž?óãÏÿùçŸ?ýôÓ÷?>øÍ÷?üëùüÅ·ÏÏŸž¾ÿü õKÄü?þòágü#/Ïú~ø7 _úÃþö÷òðÙVþåÃo—@;­vrs 6ú¹½Bdclšó¸å®·Hìzöþ„¿?X„mÔ‘xò
+¹ý_Èÿ¯–$9vv‚ºƒOÐ¡/%­{ë[8ÂoU÷ßøËê”˜ŽÙµá,‰(ü+„ãaŒwÉFvÜÀ^C†¢ñÿRle„&`Ïhb~&æücWõÒÎo‘àÜN]jD>|ÿßù±sRxKÃÿÊŽë^2iØò2]Ç%ôC¹PˆŒùp©‹¾%í '=ëþ)V%Ø>?”øP88Ìæ1ýþn)LxÞkü†Z„ºÅol}Ÿ°4ÃøÜ‰S:1FâÐeê¬8ÖNKáV¯{ËhMÁÎ«àOÿ8!´îß
+wSèSg7²{£
+£'Ï¿_’ÄÚ=È–DX<;]Êgƒ2>æœÐÚº\/=iXà°	M²©šäo?ƒM³ÀƒŒf¬I¤l0#Õ-fªcÜ¾FyJü<5§¢kE@N3vÓ”ÉÃÕ‰âð!`(õcY„%ÛA¯
+Ð2û/¤Tù/0/|V5pFô´qb†uI`­øË@fL@ØÐlïv®hŽé‹hZØ‰H0¼Íi¿ÿämà#NFÃÏoY’
+»ä‡êµ4ý~ÝžÃCeƒ¤ØšÅ“â©¾’¿þþPÿ’y¯”°¦ë/¬Õ°ªwµTÎÁžö3oÌy¿XŽäxP¾¥M.ð:á‚x ˆ°‹18àé+8sçC+
+’÷—ž*ýv-L1ª¬¬w‰ÿ¾%à KŸ{¯·oùÙÍœýL^E#ªyn÷³¢~,ÇZ\æ¾D#ÎªÍö¯Ú‰Ê,¨Ç°vY#Œ¼kä¹¸F'!m×*ÊudÐ¦|#)ˆš$¶ö5®_s…è;Æ'"ïém™T¶k˜·Ðº„ŠëK£§ÝŽdÐ3ÂíùêŸ	ã&3žsž·„å*!(™°¼þ¾Na4	w‚'	![¼ªTP«ˆ»íÔ skZ[þ:¯Øõêö-¶¨4ÊíÔb	"­"Uÿ^^ó$ÕÉÞ¼áâY.^*/%wËÎ'aâ—_»·œ‹#ax®âLºbTÝo–µæÐ{äUlp‹ºŸyDû}zâí†ËñÁQ^î5‘|Ë»dýðÑyE¸~_¼w*°en gNsmŸ’Y=4{ý5Ç•On|¸7¹;IôØ<ñ‘øÛmN'î=IØ§Ë|fËeÜÒõ,›ahœe»Ø@§£öº}ÚÍÐÊ™õš•]ß­ÜŸ|¯ÚYr:B#æD
+¥?ØÚ<q@œó™g
+·UŠ¹38¹C`rÁÐÇdv'Ü2?Ýodñ<ÎÒ¤[FøÇx‚ñ.Û·Ìi]Û©[ÓÈA¦kµRço ËeâO	#­Ê"ª  Ôv7K0ú6 Ï+¹ãíÀÑ?aì‘ÕÆÔ ±F‰§Gv¬Ë, –Ç×èªb¸R‡8eYàMeB+Ÿ+o2è2åÖûö-ÜNZ~fÖ3³[8¹GU\—E•ªý`CúÉéJþzÀ¡þGæ£RÂšz¨¿ VÃªô:\ñÁÝûÓÉñ¨Bú{_ÍÍ7D»
+Õ·FµC•¡%ýÕGóœ‹ô×uÒ0áqÐÒ›Ê¨m#È@W¾ŽDÛ·ØrmÛ©pï«õ{ ŒÖÔŠGÚ]ä¥NŒs*¶›>”NTea9¥»Yâ#Eè #$.f8#­Ä\dCêÙ~ÝÓàbÉ\6«íÆ@¢µ®‰®õ‘¹=_áÚXzÓèumùè“JºÿíSæ‡úvfóŒî×c\4¶PëWË<)ÛbÃZ«&¨°+>²{¿žˆˆ{àv~­©ß–¯T¦“«›AXVN}æ:»:0nßbSÀv·ú@o(E¤Y ïeŽ·	;dÅï•‘7sSxvh#]q`§™™Ôf£g•F™OÝ_RQ¥¶VDãu°kM ìÅ{Áày³‹–}º¨Zd²Á„áîîx4}IPš‚¦Ó½ïrÜÒ µ¶,’Bu8eìq½Óç¥žu`œÉCÒ!A!•íšÑµ±%W›–mRNkì¢«bãÂnLí¾ø<Þ¹´±Q‘^›ÝÚ¿Ö(r+OÔ){°’×Êë_¶é‹«àgCx'4,ìa­{€ÙäËkƒE5ýº)Gyø¦pˆçq…:õp°ñLÛIïAÕfŠƒ¤ß¯G‚B*Ú=éÕ¤=.){6„xáŽJù‚Ç’ƒÑ‘ÑªŒÍRWÕ¬¦0œKCèµ›Kh T<‹–å€‰Öš2á±Dÿ¢eÂ¬”…‹ss7åð”,¬CP‡ñÃ2	JêfŠƒ„Þ¯Çä#–B¿HÅÕUPHÍŸ (á"P´”a4¡”üS4©*FëuaqR°‚’ÙÀWYKæ}dHUÌŒB–CEþj®ìãWÆG¶û>yâj"1¯“0¢¼,)€ †ŒâÕ„”	m/Þqû0J³WÃƒëûjï¤œuVTT}wG|æý~=q²“Ây¨'Ä]ö2¯Ú.ãê2¾$÷”€A#P&hòoQYEk§Ö®§b¨èL -8SuƒF¥e{ä½Ó(Û§hx(¾µ*˜)9õ„‹ãdáS&ûÏÈÀÕ{~V>¬‘¨˜‚º»[â=¿÷ë‘‰ÎB~+/q¯Z¬²iús“ç¬¥ÙÚp…‘“'ÈÁÛ]ãzp¢¤BÅFsŸÍBåVpk.YÓê­½¹(½éSÓ3­æÎô~ˆ:šöÌ¥bß–¦ÝÓ¿–éÖBX5G}]ŽøHíýzd!ä+¦ÜwšúiÎ½X•­¡‡ŽËN–YnJÝ‹ Ãk±¾»ìoSA¸à’
+)vjë†8|U¥Ñcëå-pù"ú¼XŽÖ¤§á`$íÞz±žçÞZnM{.ùºÕÉV?<õ†Ïr-·<(¤¡ë$$\ç¯0ÞÍ£/Mñ&Øˆ[ÂÛPé¬çÂ\1æû*z&ÏaH
+âR%;¸÷÷ë1†Ù„™‡,=ð¹q/å%2ë
+e³‡ÁZší¢½79 JA1X¸ò+"ksÅÇñJ&Š»J;Íx‹ÍìÃä¡d¬½EœƒxÂvÉÚ†ãYt³¡Tdîf¾zæ”H>ÅH6#.;–µ2=¼u|¿Bå~¿UŽËaçâ‰µzoLm–8 Í¹ÌCÖ"À«@uyQ´`Æ÷&6€;2XÙø(I"Ÿ<j°}õ,£b¤‰£4L”1ŒäÅmIÁÔ‹å“()EºðQ™#e™g¦³|Yí@“+C¾Pç¸$¢ây¨²Üï»#øx¿¹{`ySäÛÍM¦9XšsXÞ|Ç0¸•¼œföc
+Öå4ƒ­a /]~,µ$q¡TS÷Ú’ñÂz°¢Cv*d &C©Ë€«1ÇFK3•ƒ¬3AŒœ<H%Zey ‡üWbg©„EàÍÕ‘¿_Y†|<p—¯)Œ‹€¦<e·åFŠçk„ð
+æÚæu ^°TõÔßãWƒÃJ¶¬jÑ*á¬PÆÔ}$KÿÉšùäVÏØà®¿T5Äkæ„_%}
+(#,zz?àÕeˆã[Œx©¿„b‚ é´l‡bS#-‹ÿ”ô÷ëIþ¨N¢’ºÙÝ ñ÷ë‘¤€ÍâøœòðX¹6§%¹¦LC¨<ª–@³î ÅOû•´aà.+oÛ¸x>¬é%?“U˜Œj•l–aÏžV¯F;Jh)XæPÞá ìv-yø¼ÓéíÍÝ‹™(wÕx‘åô |X$A5E…ç†7HïýzfbçëX‚tÃDT‡sÓªb(µe™QYÍjéæs ÃTþûj[‘ä8¢_ÐÿÐ/Éà!/‘‘™ÒÈ6cl+¯1B,³+_`æAÖ"ü÷>qÉšî®¨Fà7³ì2s¶*+âÄÉˆlçQxÑ8‹Ú‘Æ=nÃ:„ª»ünêhfié\‹[8Ûþåpxò·ø¬ü‡–Òo3J]ü“åaØn$7Ož7G7lÈ41¬mÊLÖd¦Ú\>M¬B™‚0¦ë 8ÿ¥@oA¼¿87€3{º6ã‡¹£Z½{žœÜÝ¼ÔˆLsÕÍ |W7«s‘äYí¦e)¼q‚™Ãî¶“[w
+Çƒ?Ý®ˆÈÄí>ž"¦žNwHé?(UTÕ°ü7t=^ûñ€9#T†¢™œkë‘ã¢7¼áòŸÃ¨ô&U™ªƒ©›ÿÂí*Ì8fÎ°Þƒë7†î³ )Ù¥“u·tÑ³»Ýo8 ßQ÷<?îÔ$*^XçPê¹áëÆ—Ô-FÑïæ*ÚŠ|ä‡NäšÃ—ô‰xz“î&†)¡Ç>ÅˆêÞF:Þ³¬ÓjÍ­ißÚ´F:óQqYZ›Î2*2lˆ´Ùœå]MÖ/¨ô*´—ÚŽÚW¾§ãåtÄ\Dñ¾ÊÇ@Ñ9-%À@y‘šø¿²y¯•†?[`ö”a3=›ZÒ:—¬ùY{ ¡IŽ"ä×r±ÌX›eõêàž]&:¥lbšÄ%/ë9ð<è#+1š¬QQ* ž`óGÈ`ª³P·]‰×nß‹®"®|Ùªca-—ÄNW¼W` Ô½¨¯œ~@‡Ö9¦.$ù  ,FÙwŒQSÖga0ºIk¡‚¸¼Q¥í€Ú,tø¨l]pKdù4&ëæí†E`»Ôœ¹äºX»úw°œ¨M?%ÍVl¨«"¸.EG`fÊ›¦Ø«‡%ë®&BýDB4yåêƒ_N‡|„Ì°<Ä<ú%Mtv!Á`Ô¶œÝ¢6ŒW{¿CtÝaß $€6ë°`²wVÓÒÆtö†%ý ÛµAçÏs®‹ß¬ù•êï;E†~›L2«ÎäÚ¤D~@mä•+£–ûUq Î–³ß§÷r:d"äì€ß¡UßïÜØí…Ø¾¥ÇX¹ú*VGññ8%õæ²ÍÁ!y ÔM®¥ù¿a-Âªí¼¼}.˜Fvx½\JSUîW³_
+ÎÒÌ“«ƒ¸ÕÀ”|¼f-|…Þ±Òic”Sž†BêcC³‰n•ŠŸX¬
+8±O[þöq>_Ûæýù–îwÕÕ
+ïÍ‘š”¥î0¸ÓQ8oLä.k3ªÈ´Q·ÝpQ¬O”ºj¢¢É$1›_70WòÕlOÛ¢#¤8,ÆŽ;ä$_³ucšâ”OYPkñÏöJdqCYIX´tàeÎâª:ux©:8ô6ŽVsõ°“4A}´À²8Ÿb9õæÔü0™†ƒÚÜÌÜÎËO§;‰JV9TÄvnèºñÌsF(®|ÑÉ˜±¿8¡Réêpc_N²Ì^”ö\4xI-d939Øtû¡-¹i– z1öjÍùl`E0I§hºã-Ã°ÇÓ*Ÿö_<K){ýwUYhXÀ}©cU	(ÚŽÜ×jôgœ1Ø`,¬Åy†÷fÍ^x&»3°Fh©dQŠÚìØÒyZŠ$uö:å:•=Lf+	@ˆÝµ÷)kæEøôö¹gÿét§RAMãò‡J	5µ£ëñÚŸ™¡I!›;æ-s(‰êjv³úôH3Î®	Ö²K—d[cDÛ«eø©x ’Ã:·tWÕÙ<.h¹K:Y„ÃHê#EáÍ;xå6È
+Òx?JµjEYnúJû[EuÄ?ú`Z+J˜çƒ]QÙ6ÙÙˆù<µ5ã}$ÊþþN(«!ì5Š/ê•“Ý'þr:ä( ó€÷ÔFÚ”h†MÀ–²ÅÂTØ1²½Ÿç¾ŽíÉÔé;›}_-“=;œ8¨³ª¸‘¶ÖåÙoxMÅ¯Ry{–Ø+×³ÚkÑX3"ç7Ù4í6 ½Qvåæ–ËäZ8,{ ‘1ÝênyØ µ—Ó!aGäöMThÀu«—fÁM¶v vÖÁ\‡ß
+©yR!@~Õß¿œ<cæ’ïP»¯Áaµn+ûÃé×ŸAÏ7—M>MØv¶1€4sµe,§,¼^À¢etõˆ]¿kæ`®Û£6SïÀÛ¡ÒkGR¯þÀÕìOÜsYS¯ŸÍËªm‡^bß¿„·X/}Ë*`ÀÌþ7NÏÌÝ«‹ul9§ÃÐ8<UiâÚ×<¼±$®®å„´-6øT_d’/=8zÓ„1ÉlòËçñi ê9\T—-“MoÕz¿rÓG+’¾Ž5qRs“ ´±Õ1M1(N‚d,§µÉíÒW½{Ò6Üb¦ÂS¾jÕ>ý¦Xù+Ö4¬~Ä”‰HHh½ÏmrÞ¸áb)ó¢!Í‰±f·c 9ˆ™œ†E×¶@ú2‹7EœZuñ]£A›‰Ig «:»åtmñˆJy¥º	±Ù€Ô•g€¢šx•éfëëXî9äàVJÛX>ör:,Lá ÝšÄÂƒâ„eÓ= &$1$ü²+õl#¶ˆõ!'hlktv:“:€ ¢,ÝEaòÍ-=ž£ø@žÝøXÓ:o‚´9ëè¶xãpÍÕ	¨­Ï~)†ƒ>ÏÉÁRô¨6]ë[5y£{h«B7¸ž–†n3|ùÈð-ò§w§yþâËóû¿à§_}õ»ñýo_?~ýãçÿãO~úéÓ¯~ýéïÿ|½‚¿x÷úúáåÓÇsù*ü
+ßÿ|ú¬Ò9Ÿ“þyÿüò{üð/@?Ÿéü‡óß¾KçòôŸO¿¡ÒÈº(./¬±èe¡LŒ›=òüt·f&æéúøíW„·Ìùh2Tz;£{dÌ$¹WxŽ°`û2CqùïûDƒupZT»ìz<,dÆ!Ã`µëP@ô~ìˆ¢=°€}šˆ®#ãâñt“–Ì@Ñ„‚m «¨FA8Ñ²0Réö±¤	»†˜oƒ
+7v–Ô#Åìd{}ddÓüS,ë“€å¦Í?¥þMÀj;#@ˆ—©ûøÝXQFoÕG¥o"@±æ(†8©wÃªØôÇÿ
+0 _ü®Ûendstreamendobj85 1 obj19315 endobj89 1 obj<< /Filter [ /FlateDecode ] /Length 90 1 R >> stream
+H‰¬WM¯]EüùwƒÝí¶Û=³‚ÇrV Ö]‰Q)Ê,æßOÙå>	–oé¥®»ÛÇåò›ogw¿†ÉzLYzMó ]æ³4³Äôê}±†/ož—ÍnÛÕÆ’Á±šœº
+“ÁóvíiòxÖy±5^þ[¦kÛ&¶|õz¸÷E½ÎïKu,ÂcëÛKû‚Ö-Ø~µÝêfÏ·-™õm…£/|¬¤­_ÓZÜ:~—ø¸d7ã€GŸNXËp)dšIÚ§{Íû´É9Ýç°c»ùR¿¶Èç“ wÄ'/Ww/ÿ¥ÍøÖÑ>&p\¯e ôòÖœ  ÊŒ àŽk{Ep.«†z¦uÞ]³ÀÉ ÆùÕwf°ã[|¤)â®ÌvGØ™×½Q+y¼áŠ_ >·Þøºü€vugYõ«›ôuõºt4€Ì`¿´m',š)hü\eJD.ñYV¦­â0,	¯9û±Çûtî€­À(´ç9?æ¨ :+ jz„Ç3Á‰@?à8D‡SzêLoB¾VžîÃV)Ð}Uö=/íÆà”fV¶›·h'ûŽ²þäê­¥-:y¤©L<ÛzµÄô¼tÚµ†V£/Óª~Àî»àÝFÖúDMN)Ð×Á†±Qq¾[µàÙNùªÎQ¶h¼]5•Ztu‚Yç‚&8$·­ÑYT§³)ò‚¶ÔMAò.†[Ðl-=ïU°Ê¼TðóÜU*(
+ãywDÜ[FKÚµ‰ëš—ŽÍV`¥Ã~AØZ[„µ·WÜªÙk¶™.z°àB€~íåç‚uí¬˜Š0‚Ñµ,«vµ®½R(È<)D\Èã_ëè…W¶Õç¹¡²Ð’­à•ÉðûZp¤Æ³ÇÖ8EN+éà˜2
+<‰G¡	³EŒ! ™C7I“¢•iÙÙ6.Û "ò*Û·îÎ!´p*XÛÞÀ‹º‚õŠ—â¾ö.x§ÿö,b8•VØTú”/>ë8Š<'Ážã[r ô˜{õ>G`‚ð”“ñÛÚîIñQmJÞjyyn°à}Õb–ŒPpu!HHY‚uS#³¡1V'†ÊÅŒp{i™Êž‡E›÷²½™­ús|ó¡õ…¨ºÑÒK`¬ ¨+ÓK…ß[~j"Íïè6x­Î•“=z\IÂ˜:óûñ{ãhÅ_sJ6kŠ¨>¿§ÿ8YÁøõÃ­=èfæT¨‰Æï´É(B"-#¾ygZ¦XPÕô˜<*€Y«s1lÅÒ ·Rè`T‚S^ ·í[‘XÏ»fË‚ŒiÛk²6[»Jâ-E²˜n¡¸ÂÀj^Ì$N)ˆ/$íy:4F‘ˆæhÄ ?ÍØ)Év¨&òüRgë(Úx>êþ—Y-¹ Öèd&º²Ýd‹Á&I`èT
+ŸB«U@¢8•PzröÖe‡Ôy\ÑQÝÏS²XP#3¢&Ä&ƒ÷õ nô ©aoÁm¹øÔ°Óÿ€Û¢­ì	’SWõ!è»ÕGÕ`üýÍ¿~÷ýû?¾}~xûç¿½ÿïã€¾üÄfÿêñÝÏÞ¿ýãß/øáûçó?ï~úóÃoaûÕãXþÿÞ´Ç9âÃë^Dœ”ü.¥Xƒ-ºÆe—ðÍ¹Â^ÖNõÙR#E+ßÚc`
+6¯M*‘Üýôâ®iŠ².*q¨íš;lƒvá0A”#‹Ó<fÙ œøü^+B_ÿ’Ž€_'}n”ÛïJ¡‹+fi«pƒÊÁÚñýƒ³œskÀV^’³"œû°6øÕíuÄý—çYÄ€5D<µ³±k  eœóí'A!³ë©½˜Šø(·r5cÉ ,îkÁJÒk Þ#+3`Œ™“à
+ BÑîå¦©ÖS6¼—›æ­[N	·.9Ñîí€ÿ—‚ç+¥˜õ+;UÂ“Ê1ó=[R©*G}m#Ô³ •Ú7ÉLr› …HL³»ŽÔmº¸E-œJ‰¦HJM Ê‘û(,ÍZñkè¢‘:pR_€Zõ¬‰ü¢Þ|¿·Ú6ÍÍK3)eŠð—ÿ.pa˜›#°ÌÎ³ŽCå/ÂsR!ÅSI§ÀŠ´Bjíyì"7ÔG±p¤lùäKc‰•\râùå™á£Ž˜©ñ”‹ß¨ø§pbRNüà@×C@–C/­(ôg¥uQÏ¼t–é2~ ¸‚›o‚§gRô¼Ôy³^]ƒ…ëœG£–-&˜>þ¶€^‹€ªb¬>[áÌâŒ@*y°Ö Ä0w"à9ãxÊ0´ÐÉ-µcT3‚ŒÃ'Êu”D»¦òˆãA\TŽ“yÎ§lš–J\}VR¦r«œz¢)÷V
+Þ…B´•iŠótQà’dž`®é÷ù%zžªå'ÎOî­þŸµTLºêm¸9ozÑ`ÊVl(uaî@¬?4Ã)«#ŒJXWu q¬E«oÙU»³®ÿÒëôR	çÏÃ#w¤H'·ÔÄ|žßç‹,Àr›bOªä×>ùyå¼gBÑœæ\ëË*ÎDeÌäÌx|une©j”à’\JbU›+E9¤ÜšgèÎÜ'ì*Z¶ä'‡XdpSÉ™ìRKM\«}F;ô³Ú&VLXŸYÚa8î¦Ç€¶äW|—p-‰¯’¹
+<JØ=K[[ó»µüÖÚû^!Vo.Ï–˜ì¥Ä’ô_ê¼¸6) –2F´W‰òÏRðŠ3â«Ï–mÆÇ[¥y:W¥„sy ýáæIpËéFT\vßàè~©™êMjgiÕùÍÈä	æ«lI—Yçm¥K_éÏ‚	B!—-ˆe}ŽQ[cÂ`±à}¼ öÇÄ>¡ý{ÖÒ‹¥õ6åL	ÿEoÍ·ŠñóÁÎÚ’ðÌDÇT¸ô"h]ý€ä€-v³óýÝ¸ô¶{EB!€MK]ÕÎ»Q²«–Kñ"Î@AûÀEüHÚ¼ÑMBIÐ‹wÔ«;`r
+ø8º¦nb‡äûyßSñ&fww@*ÔymËOø·›Or
+¥I?ÓìÔOç%½H-åP:èá€ºW%‰€ýØKr›ëß]ä$¥Q†bý)ÍpMªÿ¸/¶ˆC©ãsgùŠ¡èÔ*ÿ[ë¼ÀUóÊµÖ›Kµs©šØ -é`n:yÁÁz& `ÏI5¦1D	¶Þx«sê%¸v^;*«Mî(î²?—TŠC‘AË!m¡yvÍ~\
+Þs”­I&/³feæ”—:-ÂV3”¹`çÌÇ,¬a6Öù{§„£ÊÁôHâ1Q6‹ëUøLå1!gÈÙÁ4ß¼à¬WÝŠ¥Ç|‚y‡s°Y¤þïK{ÈEÂ		“…ÌÂ.N3Ž“·OI*õ9ë=›Ü„aÙ¡¦[­¯¥®*µšþ·²KmMxKf5¢xª±WMÍÙ;¥Éâ—æNÊ¹/ñsòü1ówOûòÕ×—·ÁorB^ÄÞþûÉÿ{ÿ4Îßo+õÍïÖ÷¿}}ÿíÿõ÷?½ûé§?¾øí‡þñú	üÕw¯¯ï^>¼¿Ô¯òü{ûóÓGüÈEïû=~ù' Ÿ/íò‡Ë_ÿ&—÷¶öÏO¿Yj#Dn¡Š&w@+1è^¢¾ÆûíËpä“x×§WOæO‘ÌIêïEÕMJ–·ÅKx!<×„§yã æ³ ·ñN€6‹8¨ÅÛŽa4þ%6°)@“ü‡çÛ$ðé·ÂlpÌá)…‰ù`AªÎ–`Ýÿ51°fž§PÖÚj…-´ö}˜@f†”©—ÑH™ëveMjx®ÿJx¬HïÒX— ¨ƒðwy“¿ˆ{;p
+$ØÓ+´sjT#A;Ö,áO®Þ¢ëã ×ˆ{á³?t1xIKvf
+Nškû.‹`Å´à
+á~6Ï3ñŠüö›Jy^EÀèLS½ Á¨ƒ`‹{8ÍžXÂÇÚ^ ì±/uäZ#Ò‡ð¢·fs gAÙ˜¾µûc ¬…¯n›Lµ‘‹§·³Å“0°éåaTgÖ¶ÏytL§qœYæYvÀ«nÿèiê¼ü4x‘AŽ|ÈŽ	x±t6±5.5éò˜ÁºÎÏ{€¿F‹ØìR;Üà9VÀ¸àÉ‹@¾…‹—‚õèMM3åÂ>Ÿ–˜ø:ûCó§úrÐˆ•RéYüÄd“Û²¶já³#–ø=¬kp-î%ÁDZ+iÎíùaRÙ¿sšß®Ùfxì„eÅ5Øv‚Ò¨ùäòÌýuïE%^	»}qxØÔÆM{®ù<¯¸]4,àdÙ
+”3$FÌåMXl2°V
+Ì2ö#¶Å¨Ûòœû›Î€á<r¿Ne€=Ë¼<Là¾îÒó%/½+üyß­\>[
+[}ùåB›²NáZKÒˆp°êç1É¬ùþj=L”Úgkëƒ¤Š[æäTK':j‚ó“RKäÐè…IžÄê’ÄÐ+û®ñ“QI¾€Kåw¤¶HáÑñÿƒpvxààÃ(šƒ#/ã1Õ¤Ø*áQciËëI7{gš~‘oÆ-î
+CüB¸Ðm Ì!êvî¤¨÷‡XÓC”Ýùüm;«žÍµp
+•Z½<<ž/Ç†—êÌ`¤ÛtsQ!¿*.ý˜®>…OUµ[‹8ØXÚåaXž§v-“$¿Óó8\vŠÊ(V©HÍéÜ6W*nÑÎŸîf‡ÄI+%mé¸<<ÞòúõG‚ñ¢k¾áI—`0¨“<?ád.®ÖÉsÇÇ„ k;`	ÖÄ~­#$Å`·aÁC°b7Ø˜ÕWW›`Þ3šAÄ•X1£Ž9'Åf××j+3«L¨®+Tk^p'—-é²N”p´¶iQñÚ«	yŠ º_	nFé(R0yÎZ‘Í Xl‚Ä³ÜÿX™¤sšMâE}†ÎSüsa®›Ñ©û¾Iý.ÉÖI]œc{“8-%)‡ÃàU”Òˆ—×¸¶¢:dxnòi6óÁãpï`bà–R™TMpÍŒjí}2Øq_Ýdlp­ÓjDr0Æ¨8l‰ å‡ìŸš_;$Æ¸ò-´$Ž ÝÜ^ê®Ü_
+û°O
+×½#„šŒ8‹‰nÍoªÉÚhsëçX¨UóN¬€Âí³TC·žý…âmwÝã›P`#Ž‡Ž›¶ªqRiº¸½^ÃÊÖ+WJG³±"DàZ¡O6‚´vÜhØ?þJ¸Í%½¸v-J/¾ œ}‡·íÉ¸k&c¯NUÑO—(Á*Âíb·–ÛAÀœãfÌš3…®:¸¦æIçæóùœ©ÓƒªqÛÊ…îÄ¹LÒbÌè'èš3}Z»©Çè.£7£çß©Jõ˜ugØ:”„ÞÖ¹~„Ýôc·OÜ`«n-+v7¿R€m´• _)°­·»¯m;zWNuÇÒ}8ËŽ5ôÕj–³÷BÐË•!µ6V\[Ôék§Êfï’—ÞðŽGÖÄw^ Í$Þ•ö6”˜À¶…‰Y€(Vuz<yÅtÒo´j`bRƒÖÛQ©bœŸ»…[n]acNœçLáˆ15/ºÏóQ|hv++˜`«•*½+[Ù•,ÿaÝô;•½˜Ÿ+\[GMNé#S5LJs*÷µP(wFÀ!(G=LYØj­Ì™T”lý‡¹ô0u0fUä&AÙ‚0+™:	Y¡Û°˜ÝüË3Ô2Jš-'®
+ç¢èïÐ³xp6z}Áë$\ø8çŒg vNl]Çq[¥ç¸7{TqnöÏ]™ÌÌu”šæ sÚë¸€=rØ«J#k°9xpjpµ/4ÒE´œí£²bÉäWgÁLÒÒ„pv33ú}¦‡I±Å‘,°¶Q¶©V‚4•fú{¾mjºÌObáÆ1úŽÛe–z¶KÅŽ2¼ÒŸÍ½x-R[I×“F¥JMpqr[CoþnÎèv^!LÕßÚ5±*<¿¯Ûvi“2bf0Ï9²Ï¶Ôã{CÁ­OòNS½üúÃÔ Û+ë,f!	+Yò9\<J–?Œ’ÞØV£]”¶Øëˆ`=åo£¦±4²L½+…Eß–Ê6ÍöF°ÙjÕ_W”†Ôrw%+$˜îNñÞ;Ý—jÄŠoÍ™DéU-Ó£’JVÄnª¤UR¹ëI¼÷ÎýÚsM§eAup`ÔcÿÔä´Ð«`T«<ŒÜr%Oà}Œ|SSîökïB§´¹¹Ö·QÙéÖ­ìå\àºÊÞzÒ—Åu%ÕèÌk0D:(»Qú…Ž‰êÄ5ãúËb€‘6FÌxÉµ0³_e°wU™àbÞ)>£N¿qÙ1œEÃ”><ö!F1³ÕríˆêŒâä-¶ÞNà)[5¾Ší3¼BdkïèJX$_¤n2B­›…ôGaàˆmQ1…ÍÙ†%s	¿,ó›Á—¶PÛ¥´‡€Y-‡[D+	Ð¯‡ §ôV9‹ I"þkALécé°’VÀ¢šÏË ”1óçV–¸#Â®ï;<@íÙ[e»K5­çCD1¬M›ƒ·	W.Ý#½R,¨,ÞŒ’ FgåŽðsbÎ¨1«¹ƒÌþ .˜u±ïŽ z'[ZÃb ¼=VìXJ3r”Ü,ök¯½p)V)ÎƒµEVƒËÕ'·ÏÞé=Ý¶ˆkIæÒâ‰Üù±Õ%Øór†±³ÌÄ_	hž¾§øðfÑµèq¶RÒŠQÅµµ.ØAþöaWÂm®dßÉ÷‰‹W;vË°®Âté wÉ§8%ÓÚ5e3ß–äz'Ü¶²ïcÂøU²Ø²”)é<¬uß´´k­XŠ†š´Œ9ò,ÒžÁ]ÓÎaHÜ\{n•C¢ìi³mOÖx±¾ú¶«&I³‡]¥.Ð€˜;Ô-*bvsÿíÈXâewô&ãKÏÿÈòÖH½‘Â††˜[´ÛArË-—ü~=Q·ú
+@†ÔpWú\ðÓÒÿ×ÀîŒÀ©é—àˆXËÀ]œq7½ ×®& Ô/·æÉ‡°åNI/ú~.¥€½‘à>â½S{]†uµñÚ3^
+¸ÁhÒ2ý:pùéê{ÒZ¦èyÐ‡È°oÅWXõÊíÌ'•À»¶e`>ŠÏîïlJ¾"’b­QP¬";ë3pÅ›(&{k¾å”³ºÀÖÕ‡G—Aµs«ùá–m–a7‹g´-'?´N"€ô£í¡x7AŠå¼	/|f1Y]«?"¸zómK&æÛ+ö4ÞjGÎú]G< ¬iýIöìê}íKy²@	»Õ<Â/ñsìóXSb.¡=[\þØÚkð0,â&·žª²ûÈ!V›uŸï{|ÊÉ‡ÿ‚G×1i…§…”aÏÀÇ£Írv<z¡l+Ð˜)ŒsÅ0áM†¹#¤òš%6ùƒã¾Nò¬7–ÑçÔ ëøzFßU=žÙ/gqBf³)×È&9Å6Ä±±h¶å¤]ª¸E«9µU6FqT•0ä2”`„Òp;Qf§6‚¼ŸÙ¶´ ‰;ãäÞ¤‡í+ l>ÕÉÁ/áÑðj[¸cdÕÕôˆ+ŽÏð¾w©ÜöxÕ^o?­¢ôï­]óÄû¾õx!PbçÂ°Eg~ðÑ¨mZ¾­ÅÆ¹;B‚†=„QlšÖ€ÑhkXÁjÔÓò¬3ˆ;õ©Ð¡¿°ÜµÓtW›ƒïÝ%eëà[~´\Ø–ÍC·TËjîœ:	1“Ì%%áVÃê¾¶h*0ìú7ƒ=ò­9ïs”õôÌ]çY,m&Á0„©y?¶½ïmÍ^yø›0):®ì½gçfuõ*z`ø#N5É˜„})3Æ$¬§|×Ý7Ä¬[O`KõÞ»å	’›•jÛ¯ïr¾M‘â,ÉU@«cKáh_´º¢†80Z1÷ƒ …$“õ—®E2Ø6Ñ|ëªÔœ l°ã’í;v(9Æ[ø®žb‘%s©²@Êø«nülOŸ:5P›|äYçÉWÛ˜ï;ö„ô+‚¦Q›ß‡&p\"e×A7Ø¿›¨gq{M-˜ñ^k­¸û+éÛ¶|V_iÜýP|¼yOö[dêµŽò}ö¢F_mÎ—ðÑæf‰j´&øe±t@ªÎñh”r`<õ'¢Ý$q!2êYÈ}©˜ËÝæ/´½ˆ+îØY’mvÚçqd+)XàP¹ku
+ ªûY%ï¤Èê-°KxŸšX·xÖg–}qàÕžéêh€Q1¤¯Q¨§î\ê.°Çõ‚x¥…% R¥âøÞS©à¹£óì4ãž5Ç’H5zuµp@ê8¾à×Ž[{ý˜/°`ÃæŒËrMû=4PZ*Ô:Ël!ÀË6±ÅâY¸üf·žU‹LFt®3Òò wh£«_t½Âºfm>Û5$¯:{F×Û‘–Köã,WÒ»CÕ÷†qÖíG¨ìYã±ÅÉýþB…WÚþr$ÆâQ™Õúþö»žZŠq';=%ç§O©”o¥D¼L"í…‚w&?wk\±—1€6ÛÒÐ"‘gÏàû›ëú½Í…Õ„¾`mxEéŸûrÆ¹O*EåYÁ×cÝtŠkp½DW»wŽRœçpñ;œÆ •Àœo§ªºéýñƒ‚vŠ6cü;÷eþ®â¦‹,üûž‚*™­×|[çÑ%žU´l3x—áõ5IÂEYÊï‡Ñ†¸ÒÀT¥¶ƒ€¾–†þ jIxõÐ›L÷[jL9êŒuê:Åà~zyu×ý!-’ÌX×RŽ@'XUAÑn˜«T¼·N	\6PñGúêÊõB˜Þ»ÆÙ®Â.
+N£äeäeùÊ­5ÁÜ‚d`"Û,×åº¬–^Ï¶oJ¶·J 8Ç%›v{Î®Zqþ\MUŒ!Â£ Õå×½ùˆaÍÒH ¨¾UÂƒ^!íâ…WÞ ô·D¡3 d5;£H@BÏj$vGç9 ™dø[CÔÙžtý›ðè›p¤Œ¼Y³K:u§r<÷6\±Lànå.XYx·ÍUŒxÔÆ•ài|o{4^[œ§#í|C€^1ˆi²(‰`M‘qj8"#>½oúîqÝ<\UÒ¦2×ç_i4efçÒÀÊÔ®ò…ï©A×}EG&ÖlPÝ*LM	TÈm‚¶¦¤{—twTÍ¾£Îïã<-[b6¯Om¡ïì&lHÕ‘žžµ…feQG$È.ÆU6>Ñ¶·èþ·>ËOˆ)·
+Ü™´·&l•»õöö„`²EÃÀÈØ^OŸÏÚÉ².FhÝÌù «©¯ãáÖ!/:Œo8«‘ ÂS/­‚EæØŠV(â÷«¿îå¦“×îí‹í%r…3i×Y]W :îî®Ç­
+TÙÅìáv»FÅÑžÈ	È9Ä¡NvS{\˜xG½×”G"‹‚¯”ÆW^ÉÑ¯½ÉùMXt’&Ž6«œK%~ª—NµEwí¥ŸäÈ£€™®ì[8¥©.¶xÔwè{÷©Œa¼ïEI:°ê,v  Á(Qu°2ú”Q­@‰öN³s®Å£P^ÌüOpc{¾.=:Ï~a¹[Ø&ÔÏ{¾ï?îos°@Ï·pá6+	q2œª™ëL;trºË¯u?è ,’•VÂ*ÁùF=2ë^}>ßö§@` š‚u i@ÆK€=‘öö€§)‰‘EOÐ«´°N††ÒAƒ¬âY«úüMX¡…ÌÝëƒ©Ø2¥MÎujÔqÿG.êÐ¨­¡.Ú© y?Ä|ð,ˆ€·wNY9åé,9¹$L}ÏŠÿpô!‘sêþbò‚3År}Ž£}/Âò=·\~yéÄ¦Gð¢¡’0ÒÂï©4NŠ©Ï#ŸzõŠÝÁý®·Reˆs«ÑÐ“/8íÙÄëXÀcKÃþ¸?{8tvÙ«ŸÛ‹þŸõZŒc¢<KŽ¨Œæ:xÖ»C]ìÔSþ…ÿ®Ý´;:•yÂÈæ%xd	à]ÕA‰aaIM_k/HyÕŠðzëÐ5|0[ÅnÐœ‘½Å¬Ã÷^FæJËƒÊnäšÚ/ˆ•+¹ƒ9ŒN'ÆÒ<éc‚`µGmWE'–³ƒ”ÛšB`ø-¥ã¢_Hßê[‘ÙEO®fr£—ÙYÅwníyt²bqÛöK Ñ(g:0m¨}Ú¿`XfmZ€ Püyoj¬"|¾¶žµªó«‘›o¸[%»Ãü—N6æûMÙ„!ÔØrˆ	ž~ŽÆÖó@ìš=kŠ@®‹­VÀZÚÕHWnøÍÂíK`]2»[LL¼J¥Í
+>|Í¿…©•0*`—÷Ì’2FÆbU‹]x*^vXµ,0·A‘Â÷ß¶òEuv°¶7AÖÅ{È¼îBy—Õ©ÆIxùV «ól®…n&xY¸Úzvÿ«–‹Õ¸Œ_ÿSŸóÍqŸÿç»Ú‘#ŠmØ	r×)2¢¾Tí”ns‚Ì¤óýÛ€" ]Ûk·xzÅ>zR…Ó!¹I¤Å‹«	¬ÎÄßÉþ‡Ý„–|Y]&.)ñöÒÙx…½ýû¹ì©ålLL—O®í!¢g§„\—ö°ŽuË…„OèS.}¨Ÿâ4PÝµßyD”ÛÑ‘Æ4 A°í~u,¼.ÇëÃr\iƒ›ÑëŠÿ¤†Cµô	€Õš°E}¼6òÁì‚á|ñC‹¦þ$ü°~–Á ¦„Q-óÂò—†jÿxm[—b$o‰h¼ÎK¯qÕnlåu•ÞœKXÓ<Zµ®Kì7 %Ëú«ÍY.øõ~ÑC™Ú¼jáY%¹ÍÝ$°æÚc*ôüýß4)vWÞµ»‹áƒÿqàtÎ'Ñ÷yQ‰à
+}Æ‰Ö°þ#/ÅD|­Ò3û×š[¢®êÐìÑ|4ÒÿCý?ndÖØ®»øÜ8«û%¶0löX÷ÿ© .M¹_Æô×÷g\BWÏ»0ó)x«GK…^ÿ ÜÜÔºëªûF>h½Þ‡þëˆTZ7œÊ9<ƒš¶ËÙ†1Ù¹{Ù 3×·w0›—-úäÙÇ»'×$»<‹L¬9îëþÿ ­¥?_ ‚Wg"ôž}R
+xÉIFXê¸ÄS}¯$áËdB»ùCŒ´µ›YÖCã°°g¶`5ç=íi“}ç…ÞFu©œ¯`]¸?ññ.NC¶Tæ£© ¹ì»³ÒÐ%pÏÈcóéGÖˆÒg(´¹ç¢HÐýážKÜ/²íåžÞV
+cyÖÒ|Û¾ZAÛõL Ë"x¦f‚­æ(E>Ò5L€•V×,K'we9Œjƒ ÷Î ïªÅ0£àuVž…xt]•­òÓ©÷×ïúxÌè0äªî"=Âk´ÙÑá¢û-{fdÿk³Áf¬C¹ZAVt[O'ßÿ¶+j*Ì Çß©ñ~úûÝÅÇ¢#GË'aü"6ññ¡ÓÃÈkŽÓíÖMp[©o/í¾Ó@¿•^×®ïÝÕ|¬å $Z€úé¿™}NŒ™ê¨huÚX‚ñ”Ê;Ñ½³ nÿ À:¢Ã[zßìªüÑéPX,¿X<<FÌ0À ¦ÅÖ†”m¹K¢ÛFSý¢¡G5UBãË·©þ¹™¼pà)µ+ä²ÚètÌ'áj*ù
+ùG-‰±»Ò?À£nÂ?Œp AFjå@þ$¼–¬Ÿòƒ°OSŸMÊ¯Fžû,¦ÿ´üN¢ØÄÈ3–‚õ^N8&O¶*Ñë!
+š¾¼$kJ<ÀËým?ýßF¼Lw¹Âg³Ûßt+UÎšœE;ožÝK^a˜6yµÇ5`CSßGÓÙ¶T`Ûô qÞÌ¾ºÿWµ›oÖRÁÿ9Õ 	Z}—¦RÖÐÜ»†–™Ü1ö“qòk¹7-­l4k0³ÿjU.ø­ô‚1ðÜÍ·ó']LC»Îé]åðþòë{}·_x°ç¼r1CÚY¢vô¤¦=`“KK¶¬Ñ»C
+êo÷qMGw(¡9\2ì²÷© œEè.WÌwHØ? ÅlA«SX(¨—5>(ƒ»)0ëj@ÏqþÁÃ»ÈÊ‘=<ÝHkëí‰eM½CB «æv9üÕ‡çYæ©td{ø7íú7Ê¼WB¢ë´u»ðW-¼ôÈdM¦Aäýjâ×>’	ƒ•ä·tñÔÒR\Çæ8G‚$H¦ÃR½³CC°‡hJÐöP¬±Dù	Œ=@ð—úÄvÓeá;õ3­(Q’×ƒ©ª«µÈo“ˆh_p»/ö3ý?ê X&™¦}¤
+§ii˜áÒbŠ
+‡|{Ú§ÒØ;éŠFù$¼Æ“¨v(Õ‹úØþf#Ç&t‘Ì0m¥í@Åó[R<À•r×æƒA.­g¿zô"ëÓŒGké¬¸Xs_ÝÎÌÀâ6•èØµÒ-”¦9ûrî|sÀËS¨n0ac³”½.#ØMxÖ‘w^7t—óÜ#\Üê~úô ^3$£>î¨ÛOÂ¾—ØÈ;ýÅaZ
+0{À_m(GÑB•}ÁÝ®ñzªèÈÕ*°±O„ VßF°Ó}ˆüýµÕ‡Ö±Z11œÉ^11>	÷zºÿÌï‡NÃƒ„O«|¼6Â…™²ÈŽÖÊ¾Ö[ËáŒ§µ3gˆe–ìÐŽ	°nþ?gªÔ QB¼îðw€†qÚY¡{Ÿe ÀGÁ¬F°«è«WÝ£ðªzãõeN:ÚÇ¾¿ogmõb¿{×p0kò	:Qï\1çì<5è1ÉqµF> É ¤‹1ÞÃîûë<¯h«œÈl›F[4ÛáÓtÛ!^õÒ^Æ-Õµß^¦m[QHv;~}mÝ9¨v£:¥>;,À|@ÐAìZïü¿¶2ÔŒ§Œh–=^T§‰Ç#Êýí•[2Û±Áðh—[cih ÌFpª[-‰~W·¢†æšº~sè‡þç
+KÅ½¿Ï›™ëêØòô¾	:ŒÑjŒ—ëO60÷†<Û­zWTæjô ¢üþ–Aˆz²½5mé
+ÁÞšÐIÝ¿FeŽµ×£fä' .ÙNYû‘”aKuQä}Ÿ.2î{þ’ÓKÆÁ;sI%\n™{¹Ô¢±Žg2`ÌÊy{ƒ$²²ØÔ¾]~Õ`C•hØÆ2Ê£ˆ¯72ÎW—ÓÝ¬ª—ÏÊ¹É½j°®äÖÄÆ–•Vk#(é€É'»×,µö Î˜Ûè–¬²I{Kõl*lh
+Eý,Wi/nRøsæëÂ@/ÚÞY3?ö”¢R.ƒÂëÉ$­2ãžuÌµºŒ–ül÷ÅÝ#êñ¸VìXJöU'{©¬2‘òË¿Š­MVÀ°èÙsðáF°ÎÑó{:KÌÖb#Á(‰wþ¯Qˆ½³ëwNÍp£¬þ&¡6•øÖüþÖ“|qU€£ÕÅ³;7Ü°jJPMò:PrÀ»ZŸß<€³mÔ¿_à«L†ra	]›`¯zÂ·>'~jžÅÇ;#Ê<’ð Ìªµ`µª‡kóFø‡	¥à¤ãâ€ ”rÉðLºµŒÅ×³«Fuö”nWÌ
+Uè–UI–©H5‹‹,À)N<ô¿¿wbÑ\	j™9îïeÑjç 
+pÌëTó¿ï?ûOF±æœÈ ,%Jû;x$êõ &iD\™…§`{ñêþšƒ'Ui±%kc“+.YnOÿFŽObÞÖÜ*‘d­Ò?ð”¸4°Ÿü‘Ç{òÐËû)\
+¸e©DJl³Y•z]M1†cmåúAÛ‹ š(Âkb#ðMUÚíJårÇYx+çPX ÇÐs
+×£’÷Ï9®Ñƒþ9º4Ð2‚=;î8îÍ°85à4F¥<\¥ðÚ³µÿy°KÓË8ý÷ib
+FZ<×Þt¡ŒÁ$¶ž½Þ`¸+³¢§†nJÀuælu&v©ìÓŽ2_Ù<Ï—?W¬¢žQ¨I[ZpÇÌÍ3íÝÌ,3xî3G¤/Ü=Ñ£9?^›ŽRÿçñ€7F)ö´â©•(zxêù»IŠuN`$[K‡ÄÁ¥ýù_7x¦MnLEéÛíYëe‡Üú?ïU×"×qDÁþ‡y1HÈÝUÝÕÝÉ“¤ä!aC‚ƒ‰CF¬„£À®A‘1þ÷9õuçÞ™±Ÿ³,hêVWWW:5MwV—h	{aÂ~™”1¬Çî^OH»ÑWÙ(¦ƒÂ¡Pg"@œûéR­xóðŒjxáÚ =¢úiØ·Æ>`†³þÙ6Àæ«©ZR‹À ³é …%-½3R‘ —ª‚+–„aù¨)²v‹†í×L"Q±!)6¦sÝª¦åÄ¸dí¤_°m„Šêew#€ÈäÐ%£ÇºEc9—)Â¸-+cÔO—ÂŽaMÅ5JfBMk
+èA’¶Ð+5—‡{ÀÃ–³.#qn9³BrÏNÕ
+¢¥Ü~!4µ~-«ÎÈøbq&í"‚L+ñÅqPÈÑ€Áòa¿\.ƒQ“5ÓÉúÏ°Ö¨ÚœVÛé'·@¼§š
+ªPgzN‰­iDÙ(VkúëÂ§›qFn˜»eP¤‹ãcÀ,“öGo¸TOSÇÍVhb(°·ù}z†Â;d~ï¤|ãü·[`£vÎlqÛ[J_þsØ›•¾â¸2K°Ž2[”“3²)©sM%:ˆ÷OIÍ&¶n†¶”ÛItK~R°z)]_!î6)8Øk‘…£^^» ™[‘–KÒË&Ö§Öˆ½ÂúÊ÷c2d8RGÆKÀu`qx†Qi¸UDŒñÌúë–
+`=t˜*nØ’àf(0ƒk†bš5¾:-Øsêä/!.&6Æ³¿†:Y«§ m&<«§“}CÉãëˆº%%°¤ÄK_Ÿ–aôÝˆ2N{7žj¬¶"Žž<Øfk‚#æarÏµßL¿nTcRÜ<+×Œ2Àxç8P—[Ê9×Ç†^øÈÛX#…ˆX4²•Ú9«±÷t®JÐÔ‹Žl$8à+'±[N‘øD†:åd¸ÒÉï%8®W3 7Þ#Y)hñ sf‘•¾}GPs9Ý<?´»ªZ!‰0"x[*löx¥fNm/˜
+—{AèT³]|ºéWüún^¼<}óÃ¿¾xý§ùíŸÞ¿ùôÃÿþó·wŸ?øôäà›ß}|:À/¾~zz÷øáý©¿„R|ßo~¼û?åTOÅ~¾ù	üÿø/ Oíô—Ó¿þ]NïÕö«»ß6ê à	‘Œ¦­ÚV¸[
+‰?Ã÷G˜¡_Ù6‘½ÛèÙÅS„÷×;oó}¡ûéœþ³OžæúŽUí ¸j@$Ø¥ô »’~ãî`Wº«éÞ³Š1ºc©S…ÙPœnˆv0tS½²ÌÖô`ö]Ïmk%v°è&ã–Vd AÜ"ss AÉâº"µƒ–9$l(ÕÊØ¾VÅ×ï[ø,ãsLy¬‚þ¹	ú‡;OJ­ðeßsiãx}ªf÷÷”¡ScÅù[VaËºP981A„dªîWàª{{x=´*qü¡I©Î\âÜ• ÇéxL¾r¡åNƒ*…â${^Õà Àúœk;~"ùÛÈv°GP‚ëÏ ,vàÃ±(.–k0h%‚-Ü(ÀVÊÚª¥3sÐ¦—ªŠ
+È»ïT–j/(Í‡u:hÅJMa%’#ÈÎ.’¿d'Þ¾‡ÖU”|ä*†P„Ú5iAŽ' LÍcUåÀ éVêà)ÒìW
+NWŸ›ƒÕ—ÃP#kÇ\¥ mËrP¦8†¡›	h>uí,`‡ïE·ZÕúfi²ßo Y¾9à.ŽRõvÕ¿7Eá`³îœæ÷}Œ¸ìÐÝå`‹`MA¼,zÕt`}o0Ïé¶hâ.¢Š×
+LVM¬qf€<¶r™SSv-)ä7 '	{Ø!&î“•î]ÌøÀ@’!2TËRòûŠ–¨a;.sÄAÄõÙëkÄõYëm9<©˜)ƒyÈ[ÉîÏhRñZCC5†Ôw:†
+¯TÜ¶ÙÒãØ7ìî)Ø™
+8KÐeÖî`ñðÜW@ag¬ðë ®d†Ù©	À„×Äº´#@aäÈ¯6Ê4ò&\¾þ¹ÓQ¨:ãQ£¬	Vg÷êåŽ`G‘êÜn¢ßA¬+aÙuõqhØ3ˆZ|X{˜bû©€4ÉÙ¤Å˜Xv¯ý÷ËÙ÷ ž3`ëmŸÛ¤-&y¿iÆ<Q-–bÝñìÎÃçËe Ê­6¸ Q kÄoÊùkÀ!¶64<ê,þ®ËšHIi›^û+n+½B¡.û¨|.‚ÈŒ`ª­qLVÖA—5€épnÁB.YP£A7ä;™)L¿$±VíkÈ¨Zo,Ì½†“Ê#Í$âtS„=@¬~ñí—¯?}þÃÇ‡Ï¿z÷é§Óï ½ +©&ä—§/ÿþùÓÇ§ïN/Þ¼yýððÃãWß~§¦/O¿áïñŠO5Ÿþ@ñáW|Ö©{­0Pƒ„ÊMýWO‡mEº¿;Ìk…¹ô>ú¸Îðw‚õ ²q0!«Óõ—N±êJZá5™G[PM+%*ª.Ç®˜­ðW4´ÃM|zÕ•s F¦=]EšÓAx5€­·…1‘vÅË%YŒv«ØvŸt»º%Õ¨¦À‡¸¹™ƒ·¿^ñl¢g¯my€ÙÝÃTqta+&Ž.Q÷ðL¥ãz¹”¾.ƒÛÄ©‡‰qœ÷Ñ]ºxÆèÐéKv’Ñu	xá­¿¤ŽápG™nðÑÅ³Fw>±è‰Wá‘çãÒ˜nG]<êg|[©}?°{S¶óý•u×™w›“gp£te]`·Öh¹Â
+6»­Îð.À+'¿±B¹8ÏcÃÕ<:¯B‘ZGZ$Ð¢/‘C3È¸Û^{$¸P·½°ñ›ƒD%@›¢îuµ–Úi­p@:JÀ#ÔAÀN[v’7Àl–ˆ Öd;ø-)Åò<Jš«üŠ´
+eÖ§\¦_ású½.­£Œo:y¾ê&]SÙZr³>µý«_ÚŽ5ìšPóœÏkòç³ƒ4Ë<Þ|.’]!üŒƒû»£‹³èUÛUëQ_ßì™žÝc$²‹â1`eí®r0~»Ã³÷×^mÒÅEX¹ì;ðíÝ%¼³ÍÃàE`ÏxéõŠç’«RìRh×Ç{Óžr¦°ƒH^ðXñNÂ|IEqÖÍ žïrºö4¯BHN¥®Ç‹µ§º<t°‰%+â<]ZšÜö¦)m_Á“×<ßíT*!uî»áÛMÈ =Ê $7@q½z(ø„[\îð}Þà˜v¶7x¾Ëé¾×]wÇO™û8î¯`†Ûà³“ŸÃÉ3–\]‰®¶¼U\aRTÖ+Y=T-Ý…UÂSÔ*8¼Û<|®NiðéÖIÏ: ^|TÌ°s¥#¬åe§èhšSÈÖSŒ«tÐ½4	Ðj cZà
+ÀÃQ\ßMñPÅ’QEÐg6C ¶e“_áŽhf‹ÄÀØllµÜ±Ç­XŸK#ípßÀrþ=Dð²V,2Ât¢üó¡"ÈAòêéJ]¸óƒ}eÈ¶)á|ÕcQ²	^ØJ;(ˆ^ÓC Á­ vÝi-ª±*ì ›FGPkéFZõ£U"(#ó‡fíÿ¼WÉ‘ì:´`|(*àr~×6à_'úÜŒ÷“Ä"‘R½‰9(:úÔY‰5‘Ë­~g¡lQ­"åe–")ÕR•ÐÔßîÆ”5´S³ï¾ê¥3êE²' WUÃø¹‰k¿™,Î3xt7 ±:H ‚áéõ©€¾MºM–§1ìmâÁ×‰ Óš76€ê¶“&ï¶LÇD¸Üû[«@Á=Â~z¸‘
+‰éQg5~9ËoÎ6 
+óX:×vä†ýh1ÆYNâÇaCýþþï	qPeNºš„“?'ëpÀ-™—˜×Ï9p”<fxñ;ngqgá¼¸ùñý_âà=i‹çÈUÎeñèëóéÇµö&“à•ž“M<j‡ÖóŒ’•Ï;ÔP•…¹'–ÁÖT·FñUƒ:èlˆ3§Hê~läÔ›„„
+éº:ÇÇ÷¥K3´—D~4‰Î#™úTx3*èüÛžFçÕÇ	|í¥s*×¦NµŠ HY†œ] nì60†VXõ=¤:Ø›Î,c°%§JŒ\‹y!VpÜû[¶ô.Cöž€U¿)¥ºØe–XÆI_Ÿ?'«–—*›p&rCHò'KÀÖÁs$ÕÅÈ8ÉïrïƒÁ›)î~w›Ùúq¸vÔÓfT	„ùb‰Ÿ²ÇlžêÀÀFy,ÞýñF‘(g½y•±ÖâóÍ®ç|Noh,k;Æ\4Ÿîi‰MÇ¨¤ÅAjš9©ïJ¥8(É4ŒØÊûÇ/…°PÅ3û‡²žËK3ŒÅ¶””ÞM9XJÝ[y€WD'j+DëùF4°¿«F	lãßCf•ªƒÈ±±Îhï<ÌÔbn Jw€Øœè¸€S)öRÏþV+&÷èfª¯ÝT- iÞ¦÷BÐÉð£­¨²ÖFqLHõ2°šÛá¿Vãòš†*9ìØ”¤ì
++¾¹„Á¤V¯8ÍÂgH€ÎÅžƒÊË&ƒ§]Óm€¶šØYy º¾&Ò™ÊœY9z‚XšÈÎ¦ž"ÛXI‹,ÉÝ]Ý 3kþ3‚ «K¢÷Îxyi0vŠÄq’HÏ¢)<¨H½a*ÿâ{ g‰rKTÖ£k¹+É«}¢ðR¢ÜR¯^YÈñ0°Pÿ^k Ú.¥¨×ó,GjÔë,Å0Œd¯a€½Öó{¯bÀ*¤&ˆqÔ$;ˆî`í¬'	”S¢ÞgÜµÛ²1ÛÏŽÖ%n%7€ä¥«È v"s6õfÁÊ–€Ééªœs5üï'‹›>…EDŸê¨Ap3XâM„bëÝÃ
+zõ]jž5Él»Î‘­ÈªfË0_¥¶öf{‘}g›mEZVÒËk?ˆiJUû¾Æ.¸xÄ„óºÆ~gŠF|?ÄA]´âýBm-l³•»·|jNxàÐU,x 8l›dç2OŒoJ°¤î|Å	úöï¡ˆ†Yø€óÎˆ3ˆÕIX[ÑÌHOmÒý(ç|áÛ~øIØ0êH_œ=	 'Û (~í†bÒÎ§ÌÒ¾Ý VY5lÕþ¶¢äf„;ç2\‡¦a‰ì-ØRL§º³Äœƒ­×ÌÆÊÃíÂ˜‹v•¦|7çÐ¨€¯|xôpŒ'÷ìÝ–G½Î,¬rÙg«$´…yp‹kó÷ r…íÒœ­¬vUÀtxÛ÷Ð¬Uº÷$‰¥–Ì`¦ …è p“•DwïÍm­½-âÂ±p¡	 ô;¹~Ÿ3wa=òÚæXüþ×&/†­¦C *‹˜Qüú¨xSSÔ1+
+{lòòº[õ) ­jÁê6Ëp´šäÝ01qlðÑ^È(%‡[¦8Û[ËSßP)öÃ	4QJ¡W8aº¼D1eë§92+Ý¼@·ŽìÃŽ“Š¡”&¦Ü¡Š‹­XÏ!´êÛ&'îLÍ48°ÖŠ7sm#¾O’ÊÉpßþzÉ*«¦ORÉj­)X[‹ïñhô}GQ~»÷™¸oªt‚¾œÄñ!|¥&½ìôïŸOà]üç?äÒÜ#ðl$Žoô¨˜„È¶901´H0ªmƒgÞ¿ü©Ö|¾i®×æÈ±ðèK8<=t·ËY­†$·µH[u3/>>]ŠpÎèÒÛ‚1ÕlÌzµit!dÈ§ø*Ù"Ès¤–jZÄ(fiÊ˜zâÛ!È‘Ê‚Ö¤¹ú€¤³í‘eÕ.ö=`W:b¦8²øÜ¬µÊªsT²…yª“?¹ÅÚ‹\²˜.ƒÝ.W*VêpO¡tôhæUìÇ­~Ã!•fdAö¾X4¶Ìã ò¢Kã{´rb¥åØ«8x.1€UÎ®ÏÌLIæB›3Sü6Y‚RY.PA¯°NÒDG‚‰”Ið·êëÙ¨eDÁ˜Ü“¹©°^\Ò»X sÏêul)Ã2Õr_Ôâñ½°s)åúÚ²5?¯{pL÷žH „5íL¼€±òÎj«ÜÙ0¨Ø³\£aÇkUà¨Ô½d.ž­ï{YÂ9ËÓ£ä[Ò›{ÜeÝMÊÅ÷ÑZ(;Nyw ª@‘üÁ€lÒvZ@=úM·;ÛòÑ°Þ™p•Sþ†šôÎÀ4êÙáNœ=?R»Ûð¤åÞ\­¼2ãÞT†×ô¥¼®gÉ	jS«qïÜyŠ7B=î…|TgEÏà†$´4½ÌÉ‰„)¢ñ[ÕýÊN¢3œj|Žß»°=”ºËÈ%„[xª†ÈPñà¹±U.ˆ;òè¼uÌªI$D»ž¸Óþ¯ŽóÐ"¤úøç2äýº¡B¥ðyÅ_`»ã)ù8º†$ÔèÇY'Î§*¼RŒ.©ßJ?y¿õ!‹ÿŸ¹ïEáÄîøtØ	Û‡KPÞî¸SC°°½•°cºýdÓÓvv´…ï?™ÿÜ¢0-3&ÜC³Œ•¨“ÿrúÑþÏF:3Lú¹P#º<rpR.Àš‚rÓàv›cî´žÍÇ0¼ð‹²ÕÅQ˜øs‡§C»Zâ¬KªgùŠÍ %JkM/Mq1àÁ
+<%–ÏÌp®2ßlsÕ3ç~LÒå Žý«Ä[$Ê)70¤ÔZPs©ä|)„t¿™¶v¾È¶pàÑö¼•hÏÐEÝàD°_·Kþû%¿ØÌœk_ôÏÞãaéU‚Ñ]T„Þ¿-RÛÙÒÿCoÞ,x0k«\[¼ÃÔÊMíŒÜÚÅ¶$«¨]Äm~8Sí!»ð‹TåÝè>F3Ÿ«}EëgËé¯w<'lf8ùÝujfµOCGm‰×—ÃÔú¾]ò¨òJƒÖe!c µ–)ëì-y–k9¦œ+åˆ^4ÆyV7©}‹Y6“›Ï5¡éšÅOW´ßÃÒ³ì;UœåjÛE¨û	Îõci°)âƒíåÝÛŒºßÚ±g:XLƒÂ‚Ú‡H)—]
+—ºÇ ô:¶ð¸µd¡„_%qÔ¯¤÷|?W=ˆCµQÀ¿^=Œ<Û\³h‚åÍƒ4Œ~K6Ëò»Ú|+HŽašß%72¸rŽ£‰­Ð;Xñ`!Õ8Ù¤saíªÆÀ°Ð(*½Ç°;aS¥â QbKYÊXõóž`.—cY¸]–W¬Œ©Ûýx¿tî’ÄÊH6]ülàº}"eL)"P°™‰\ZqKÖSè®°à–‚Ó{¶æy¯–Ë®úõw°¹ì§´5´M	NÜ„L·ÉªŽ?K[Ò>{«Èà¦iº»j¡£­·–¼x_N‹µ•K^ûý$ýÀ1µ%Zw«3Y]C´´Ÿï
+FžQ®­Z[j/f8€{š4C¯}J>J£ 9·±«²èˆ€w™¯è²qj³M«ƒ¡`ƒ¹ÅB,Ð]CãrnT=Õ1|ÝÏs0^ØÇg‡‰K·LÍ©ç«P¨¼ã‚~¾†Â¨ÕzZÂÖÍLÔqî³f#=¾ßæ/I.'Ùò§[¬Ñ…Òk$ ˆË¦Ñk-ÉNéy""u€c(nCíPß
+§pôSüö¢’O®bÐ­£‚{pŽ¿c Àÿ´»î{]‡©â/­”Dž| `ŽŒonúbÍTôDWÏ·î6ÖésFÁŒ±[Ü/çÄîG&‚ø¸ä2ø¦w§äH¦Ãˆ /7}ø\T¶õÜvÙŠ+!X>~"Ž!ºŽ·ýù¾Žråû“/Á~;ŸÍ;Ï0ÞÂnö£¢{;ê£v	µ+mú(T‡OÝ×ðêåØºFKÄôrøùé,í?¿v§	‹…óå®¹=Ñv[ÑÇÆ]CDGÅ`"0 âm¥HÖÒ9%)Öam¬}Tl—¹mÃZû¬öqƒðc·³É»ã`³îzú³î‡0y‚ß<aZÁ?¨è¾64¾YAÎ9ÂˆiÛË‰G¬0ß~`¹`:s½	þa¬Ò8€iÑ‡m¼ge9±(S‚[-	Tó1Ê­}$·†=´G˜dgrŸzlºÝ Ú	ßG§Š‡Rîw–Z•,¼)/Òõì ¤X^uÍÐ[Ÿñ^¨¸tc»)/{¹A=œG~‚:>[ìÛ$—·›âÅÑ–’ÂyN÷`»KVÖ Šß½¸øNa‘@Ð<Š «5¸¼rÄv]{£öqcô×ÀmØPXøNd	w`Je‘ˆ4VWÉÓf{Ï;wõ>Ìf»kúÛuU¾8*eµc×%ñ
+öÊS·‘ôì`Í­.cë*„™çe¤eO}Š¢mÙDõDä‰a+åÔLøåãüºá2+ÕÐŽG/¶!No`ÉEüy\þ<~á!'Sõ³pøŠýß]ç YU™¨¢i=ë­s‰ÓLM×$B—{áûø8&Á³§ê¤ÜÏˆÄ°®œ™ÁRŸçUÖ«ŒÌÛÉÅËUŠYAãÊ˜ú>/Ê¸Ï;P76/á|Ãíkèoþ5—dÄyáÑwX³?Þ„òú¼¤äÆçDK”F1P¤G™yßp[.¦¢ÀÀùŽÞÃeKÖmð”—oŸäòÅ——ïþ‚ŸtÀï5SçŸžh	l¢¿úê·ãï¿yýôõ?ÿçŸüþ§Ÿ~øñÕÀ¯øÇ¿^ðß¾¾~ÿòÃ§‹|	•_áïw¿<ýŒ?‡ž.¿ÃÿôË¥]~ùëßÒå“Êþéé×#c.By¥ãÄÙÕ#!IrÝÐç#ÚÒ•òÜ@oÀKÇë´í·Ê[F[`éAÊµÚHœðÐ‘h°L
+âHÒš`ÖGlm¸$¬ -„	é.ýñ9Rõ¤´wpø×AÇ&ÌBþ5Õ6\–¤8Ø
+fÂ]ûß½éÚe0ÑÿÖàÐnÃs×jò,®,+/5LBƒÑ ]`JÎîZµ~3¸æ²›™9tb4wm.Bÿ~ôq#Zû2àdþCƒ@Q•É#Óv·"f›Nqƒ«pw0Qò(`ˆ;×v&Bµ¸VD'ÀZ<4í”FŸ.¿H;'ò5âá1ænä-™Þ¯Ú;º¯Î ×®&˜Û-v/éÜr´c/.9D¢ÃDÆ{qUÙ½'…Âö–<®ÁQ4'ç?G`{ŽÀ-âZ)
+zlEž=2q­+
+CùEô»»“3ü¿=CØÏìÊU	d´Ã<@'
+Ó<C¹X)´¶–ÄÀJµzÚt¢&6¨…~æâOé²W¤!å Å%ˆZ	«XÝp„ql“,jÕjŽ!>VŠ¿Îàö„
+äaJ@¶B¢ð<;l2a–ì¶VfƒzõÏÑÍÊ<'X{ë«l©×aïØBÍ¡ž$6CÁŒñ˜‚ŠûçI©qu8³=•Ö4(¹9ˆS){Pz—¥`{ß˜Ó|,IŸ
+øª+Î·Ð¨Íˆ¯èZ®M‘<Uˆéháÿ±~WšUC­7`ÐGŒZï¦<Ã¬‚)¦§%ÿ0E•¡QLu\;yÐ©ÅÀï:<p¥ø×âP•ÿuW«LÐ°šF6°&‹òC¤ÙÀFÉÓ o±-~À‰jàÁUcÇRÂY)ƒ—‚â“’mƒT]Qì f¦™…]#Ä.‰ëÔ(­f· ´Z\–jÌ(Áíw¹î‡¦r¡Åõ³XcaDë”ÝŒVÝ6–ioøríAï5×õ5°¶±ªG
+o
+NžP a@éa”‰‘%åFe}¥§„ôKø¢µÐå®ÿœàÃî\Ë°N€[»šÈ}+2c^=g©ÛTlsƒ[5öæhíäpmi¸h£²bËä Q”hk}SàÃO±­h`²¾Ïl­×±*r‹ÞEqû÷=x)Ù¹háHs-á]wjIUö½þ’GÈÚ´êêbgµß,½†U%ŠcÂ}ÁC–,èÝ´²¦O¶B ƒùôˆv	*·¶Êf¯šÕB2uW@ª×ý¢e#T·i0çQwž–_g–8·Þ¾¥3-§°¿wrírQ2Ö÷2â{,9ËoÝU»Îöª—jP?-QX`¨ª-Û;ðþû}Eª(#§„O%øv8oF,eÄ[Av5H»ÆN]ßs‹û¹N-éÎI²wƒ¤Õ~ÃœÛÖÕ
+<!J{ö‹ë£/)‡GÙ­CñËžU	¼%°¹úæÌ0urYtbÈvc]¹T\Ü–ó€¹”^{wÖL;X„wDx)ð-?’ÍJXýñÙ¸U¬Ç.›WÁüp_qåd±" RPN6æìšBA¾Žì0•
+h@lÓ©ÊÀÆ1U3-Ê•$XÿhFT ²¬ÇV÷Ÿ]VjŽ…\²=VQ‹i@; Ö*íæ±jÛ‚2­cÉ²ß¤jVn­,¦¸HêÆøÄæ¡ÙŽ/¿Óf¸¢W$t}|zKô®Î7ß¿cë]¯ÞŒ@D“Åxa‰$ÛhIÔ;5ÛRF¿E°Áâðbá÷ß¿“­»y½©wëåT[žÞ¬Ã»ûFuC/h’Á=Â…ã3KÐåž¶²KVXhùæ„®²=Ö0
+ìcå¨äà [NIìÃA+J]“Ã a3¶‚fN6²úbSGðf~U›½ª Û{#3·ª»9éL¶i išYÈµ•l&”,Êh*Èðg}Lf"À’°ºƒà"5¶’¯Æ0›÷¨ñ<óš‹–P}©bÛbèäç¡*Ôc éJf¯½<‡1O¶ÉsÆœÓræ!þy#$c]™M¶­•Á6PÌà°Ã¾¯Ø¶9†“õ6ƒ¦ÖÌjê4f5	;7iDNœTÈÜyÃàà4Ò¢ UÖÜ™Y³eÓµX‡÷Ù@Ôÿ²^m«qAôöæÅ A°»úÞö“Düàà`#ãD&³¬G­a³BøïsêÖc%ržÌ²hö¨/U5U§NIäJââoÃG:ÐsÒd"D¶Ø©ä²®Âuq’AôoIÑæ}Ûc¬ÊÅ[xÞ¸×y™'J\Lr•f™aÙÿœ½p†Î& úJÔé‘áT½‰wÍ$œ
+Q]ÕÈ”,¢Î®†T4²‰ J:±±Ü€®s&À^J1`lLæØàr²Æ–bÓ„¨:ç²¥#gÅDj­}¹+êÃ'°Ü…zØÖ g¤jGB=®Â$ûv("×t=ë<:XºØ¡à9{‰«&šVE\>õDæjHSSÕ–ü*™lp³ši:ÍP]ÀÖeK°¤(ˆsÜ~ðŠiu~iÊ²œŠ4ìª°KÞÑ‰VýþµÁ¯¨"`ÊÝÖF;\VæiLÅ…^k¯¶_æ-MÇ:¬ÐdS¨¹1…! d°+>€4¬}×hj¸Æ/½Ìò0žAÖø~Š¬˜-8íª-Y¾Û|kéãG~ãöG-}Ô§GýG±Œh—eå¹€ÇZ¥Ú„ü”Að(
+(]PÈs*éZ,‚i^·Y–N2ªûáãH¶¶€£Ì€aÃÖ¦$9˜WÏÃ:=×£åkCŠØÃu<³Y'Ãº	v€ÝK ¯ÒšG$Óæ¨Õ/|¦òª„Š¦V«iîÏÅ«ŠÄ5‘w¯š’Èn
+\ÙÁ:¼«u{‡ŒTÍÙ–×_lm
+®`\0¨v5!™ÿ	6ÓHp8(á°73V<ð*Ö¬ûÌ­­û§,ƒ¬#s+RðÉç˜›?6O>>;;¼Ùo>ï·‡/Ës@'h£·ZO—gïŽ‡›ý§åäüül·»»½ø|ÜòÒÓå,|¯\n¦YcB¯¹5ÊÅgTÏp¨Ú‘æ0Ú|Bu¹S• œ8­Ç|=Ñq¨üO6E˜¶3q¨à¥µb/-àM*ÒÔ,u2ï¿\Ø}Ÿð¼ßŒåät¹üõÁÓ“³WýãËýÕùáîï?ßnÇëÃ^ÁóëO7ûðÉûý~{{}µº|º	Ë¾—÷›;|ÂBKÏåüø	º_òòóòÛïa¹âµ«†CdXZË‹‚4ÕYà×`HÍî×¾ÿ¿ÈW[÷¸êÍLÊ‚Ë{ñm|3¶Xp#¡äð/0þ&^Toààìeàhùq¹„»˜ˆpé=[—Ð”Ð6`KKØ;Ì•Æôe±&e;³Ã`ŒgC¸#òÈÆµGûo3¦œ”œ]`ap’&ÀRäÐ'ÑÄô”Ÿ
+ô46Dö'ôå¬KAåÅh‚ûrµ»hdïµ*@¨qSHk¯N#Ì”£sªŽ»ˆê˜„À±Æ82[…u„bõú öãPø,‚
+Œ;RRƒŠ¼ó}dÂàâàî	€.`ËŒìHìH¦Ô ‹chÿ0 é+žÐendstreamendobj90 1 obj20164 endobj95 1 obj<< /Filter [ /FlateDecode ] /Length 96 1 R >> stream
+H‰¬WÛnÇü‚óûb€âÕôÌôtOòDZ1 DF9NÁ2–‘dJÿ>Õ—9’lú-”–ÅÙÙ¾VWoJ³ì½¶}­eÈ>•ú¦µ”}Ž:”¾SÃt×>dûæ`(ï•§¦ºwV?Ùìuƒ¿<æ.¸îT[¾ÛvbrTöVtlqáÞâí"¸ÇÀ±³š=Dûèƒóý±+7xV
+3Ñ¬=Á^´.+e;ÚûÊ{ÓæŸšû”"8J¥ïµ›?wáîwjÝO3´éÎ½Íx_öO»µÞ/} §:öË¶{;ËpKë0¸ímŒjgyîczœ+üÒÉÛßýlÛGãgeŠÛÐe‡¯ö±ÚÍlt'xÃêZ÷2‹F`zÁUã^ä1„*~iÙëBàþÃßn5{gþÈ³ÒúŽ0Ø‡
+\¥é&5xR»½_*îYx_˜-Zeì¥Ï°´ìÅ3hGgPÁÏ2lø¾fY˜¡³Œ€µF ZYòìà°
+É,ÓAÄoÀª¸ éBè™m{–p¥ ûòÀ¢¦#@”½KC1E¤PýRñ)KÕ½K)¬âfUF=TÃPó³/L¤ÙA+ðÖ2)¸®QÀM¼ÑZ±PåÑVXÒ¨Q$ÁÉVlÿ>|õããówwO^ï^½¹½|w¿ýPÙ?½½ÛÎÎŸRÙŽonÞ¾y{µýüòòíõvóæêúÑö;œú~èã:ûVvBÜ7ÂC±â.xèH=^\hûè–ÂSiÃ¼ê»…ïÆ‹
+±B-hæ^½‚G	³½VhÁ»¶øx©V”H¶ÛØg³k+ªÉÓbí&»ªçª[²«ƒÞ'aD¯{ðuŒ’·RaT?O”–yxÿUü9ú¤PišñºÈ¿=x'ÑÕ=ð7Zrr·OQß¹Ëuð“°µˆ@
+zë˜!±h˜óõï%:¯2¦…	†´AY<FJ]$0îxøÁ¯ì!÷H#bÕ/– Ôºâ_Ô[
+Ì°{ûƒ{E}{üQaŒ[£Çd/ ¶^cRdoV‰ èIV€Û˜#`En+%b­»U"‚:-˜3Sõ”>non®æYešhŠ•£pÏAÕ Ý"³ö±
+.yÖÈ¬Ì Ë&ÅƒW‡ø`@/Õ²èÚú7hé&Y5Ð»JD¥7öÌ"‚ÕYœD™CCÃVÀàâšGø(gÑÎƒ8>œ˜×‡ÿ8aQP´iõŒ±‚†ÅŠA1”D$;é©A#¬ÁÍ£Š¬’iBƒRˆªíëìÄÓˆéŠÂ’î%6aÅ,Ñ‡–t/p–5A^ ²æAÁšœü†±z#.§wíš¯æêLHû)ù)ñ„¡ã1éZÚÄÍkŽFL§¼aH”FP.´åZ×µºÌ‹$HK[à(QÓ@'Éz3%??[OpÈÈƒuÖt^Œ@|¼ZPüÛ› 6L—ö`‚Bb]à”–²c®o5ÆC'ËÂ@Ø>êmE±ÐH
+aíq®8¹ZJ¨k€6ç]É } ýl¹A'Ö1g‹ŸEUY›^Ð[Ô±zMáÉ&ÿ1ËÒ©ÔPS?µ9W¥"hÛƒå{|¸ª³Ü›5¥52VÕ‚q“s»‹ñ™~ì¡¼:ú{ú,A1µœšÐ2c´…˜Ù_L»50Pä£j´*jf„MõVóýÎË³“œÚˆzRc®•¼Y|¼Èn'0|0›Ì_U)¦^™)°Ìs³hbøE´à±	Tü	Œ×+cjÛ ŒIhcc¨{’šZ
+5ÖcF€¹³ZLbMN4¬G ©»Ÿhrûuô'Å²õÃang¶ÿÀÓWçOõÇ?Þ^]¼{ÿóË¿^ÞÝ]¿»ðâú§W·_Àg?ÜÞ^Þ\_mŽn	oôèP¶sü¼øxxÿÈæ˜i‡{üò'<üÐÇ­oßmÿüWÙ®ìäs›ßý½¹úBølLM¾ï.ÖüìzýŒÎ}öÅ%¿vÉ-Ì£í	¾ÿ—C˜x2õÀó_‚çöYlMáZm†@ç T©èÁ˜»=”m’h?{¿Ôìwå™,hÜ]Æ v a5ÏBúÏ ×à¨Ì±bµ.™YôþèI83'Ü\[
+O--ÐÔI`û|üÔ9àRâó6v­™œF§D¯ÙØƒØtšû ©XRÀ‚`Ñ5¡§-‹nÏ!y©Pë¹"Z¹~“s;ÙÙw‡Ø=0·Eƒœ!ÇGŒQƒ’chÒCF45.Û-•3ØkšCŽ+÷ÍëX?ðìœ[ªØá +Í®³´Ì+7j'&‡ú\ªpä(‚áN$Æ9	Ð±…ƒZ Ñ(™¦P5&E>ÃYðˆ©8™ud{åãèœ%}0êLx¶ØÉŒÃ-,c5WUxÚc>ø­+‰Õwè0ØÌté(êÂ¿`á*!tÅ¶ÃÈa·‚¬ál5MàÀ¶`
+z/‚ò¤Çˆ,‡Nº(çö©b!*ÜýtÁ\¢]8Ú8+Öò¾ªi–¡Ež,±A>ÔÆÇÃúd€Ø›ô†Ydÿ5l¦Ê		 2n²Y—”âÖº%ÄNE4¬ 4ÂŒN±¹,Ënâè(äå>5#SIÍxrqØ*•¥7LÞgŒZ†kñ÷×«ý#÷xòšN£}ŠËÁº}È³ Â‘ÂQ'–‡Z³±ðLœýöá…òìk‹JC[<Ú÷îÕíOÛÙÅÅùñøþæù›»K;ûåRÉÃv˜Ø-·Eª<ôÂ˜QŸ`h¨ì´Ö“À"Ä©Š ôjîW2zÃÖ_ÛŒ%×†ÇqÂ}ïÖiÛ5JÒW§ÐÅj³0.0ÐÂ+Ò<%Z+B;!ðW÷cMMí%.Y­û©äéi‚D]Š„´ö´Í[Ã÷>dû: ÇYˆs™)ÚØzòCŠNNT‚Ö<’”‘dkÏÿCÏ.>;ñýËË·×¯¯o¯0ê_>}’Gþü›Gþvÿöú‹JÐ6½µL%yìÕ´¿Ë·ÏK"ú~øfy“kŽNM"›(öÅ¤Z²"–›ë˜SFÇ¼UŠËIË£qEá$çW–H™‰¸µ%al¯	Qô¬M„`oYz¢¾= P\3çj«¯Á7ÛäÅŽÚ)ŠimHíµ®I¤‹^³HçàÓY¡bœÞ¯³²¤Ç²VmÜÍ–£NpÍc<¥Ìuq,I=5:Êˆg´Ä#Ð´¬‹¼[ŽÙ:‹yl7Ê³œ„Öm r‚Ÿ‡u]Ð8Ñ%ÓÕº“ó[id!rÇ~FŸÞw=dCcù‰N£Èª/B)[B;#ÿÕ¶‰%F”jN'“
+U_|bMÅÄmÐP11}o9f¦±d©.‚'c‰é,ãÔÝÅ$‡a˜œÿc¿ÊVì<ŽðÌ;œ›€}‘¡»«ºªûR¹°qHp1ÌH²fæÂËˆyû|µtŸÙìXäIyF¥þ{©å[t+1‘§ýDû¡\;¹fîiv`9ÒæÜjõnáfÄ
+êÆCUÛn~‰˜ëÃç Fhd£:ŸÌ ;h ƒ©<eO)ˆ´DhÀr
+aó…ú>Y‘§ýöí2}vY·ŠRí©˜\Ç“«T!˜šA–1rxÇÐ=¨ÒFÒ½]ê8Š63m³Ä!üåˆ˜Â€î9­M£K!Ï5ûd}Žßª•MÎ™pZ"Hœ`<:ê^Ùïo×RÅÙ·¼5ÚgZœ=?åçjöó"g\sÆ{pC~®q+ôn	DÂÊ9×ä‰ôýý¬5qÊ•kAÿñÒ…0ÃÇ"G':úN3`¶ÎµŽ¸žÒ¾Ô&Þ/öË:óQ6¡H#óŒi¦dË²%,q]u¶†^rW(Öâ¥5k
+KàrÍ%6–aÉlÄCÚ÷çèõÞJ+^ïx`²£…ÜÇäîºD)ö”–HÀqW1Í¾cÍ´É[ŒÄÑ-B¡d³Ï‰>rGIÅèsV5çLæÌ)í®¦ \p…˜RÝzoJÍ‚Ix4nŸI¦ ³4V¨“ëà?»ƒÑ å¾ì“ºÎ˜ ²¹¨TMrŽÒ§S)JeÓr$µ-÷€!ß¥K5‰Èf|ŽÓZi½¾³&”².»Š0'tM#û…g[*©•ßÀ¢Z¦Õ.²t„-Žâ\`¯êš¦†hFïØ4úùÖP¢ÌÀÜÐƒ6ÖZ³Oû([ê¥…ÃßjÎ»üO"]sPÐ¢	}Ì,V5å‘b±SÎ®[Ø5~MFò~3‹k¡“f’©¶…]ZàâéÎ¸<{ý?ËÅg§”‹iâg²æ›j‚‘a_eC	éí¹æ2–ˆ ð,íÜkæˆ–z‡ºœ¢¹¶™…¼L6+çâ&‚-™ÜÂÕtø
+ÏBI'~\½¿<ˆÉ¬yLºë±®Ðák;c„e ¦žvÍÂ½dÁ¼yQ;çZßÀ;Ö‚hISöp¢<ÉŠYÆRã|¶…âV×Þ3ÐZkü†¨ FŒçÌqß»'×™Ù]ÂÏP`ŒÈ—`îÍÓ¥<AzãÄ,Š:ÌúÂ½ÚRCmÆC-ZKÈNßô2º¦³ü_f*Ò˜Ù€Q¦pnÍN»L%¡)‘Ð?Ðù;LÃýfpÀW)\O3PÏ[ ¢*®	'À	ËÖ^£ÚÈK.Å…šó‘™\3—6vÝg•’e‚šèFƒœš,…J¡¨šƒ½I¢,ÓatåZîÐò{[çg#“”¸:ÉE¬å¾ó‹¦ë«!rìÃÓÖ<.æ©:Åô;n‰SCáB\57¥M„šª¹/VåZ´®½³&
+~w”Íñu~+T¦	óð÷i.¯Ü({·ËãüÀO»õdû·â+zÅï»óÐw7Yu•~I†„7]žÁýÎUó±:w5ÀØ–XðÔ®7'«›½µ¾ +ÔŒzdÄŒ‰ibòÑ*T*Þº'€¬UrìZã?ºCNÅ@j>ä@´–¶=ÿPÊ­çã—¸ÖlO[êöv™M·¶Ö*|¹Vc1¤&^ük‡á/yÝ¦,ƒB-‚Ç!´OÃËGjl¶÷dþ!«ç^«–>ß‚x®}ïçætµª£°Î0iÚ¨1_-ZM»f¡@_LÉ±£´´‘®ËÌÀNÜª§ßeñšC,æ#1ƒ=Ä,^6Cô;hÇ¾xz»dÓpá8Í)IuƒáÜæàd%h#çÑ}oßqžæ}$ï£™>KIhˆCèSÏžY¿*a]ª{ö@ßTê¢üÔívýÇÙÄw*ãº$ºz¢R*&1%kÁx5ÖGaB	¥jë¡ù\…œŒ5ÐSåî˜n‡Ü5¡‰í82Ó™kK›”k¡žfTb-ÒfM37C†Í«_×á&_,âÃo"³ôõâÙ9a¹‚ü²3ã‡ûVBÕémëÕBÑ²Z½#ÊR×Hw)™¨‚D®‘nY”£äÅR‚ÀŠÉ[rS::Çvš©¤¸Z
+Mº*e“¢MÁVÌ$ÅÌÃÆà#|ÌFn¦o.3¬Ô9	íAäù6ó—‡§|ªüÿœ&Èlý‡üZÊûòDi`èÓ^JÛb¤FO¡…µ/y%¥d_/Íµ(•)>Ÿèßç)<k)é/?#(B5¾çÊžV}}rQ`		y_ƒé&	Âf©¶Á6Õ'HìVÚÃÈ¿ï î×2îÅ¿g3-Ã´Y…C{ ØšƒY…ñß€OtMÓ9ÏfnvOêyáWÜµf]€,­»ãÝ½!ƒŽ |¡¯ÅÙ˜½ÔÁƒ\%@2›¸H‰T0‡†ÖoÙ~ •îgA6NÞ~X»°	¶ÄÑ¡JU“	&Ûÿ­n•‘Å~ÿÐïtW¾8[X…~vvç/·è´Ë›ÅçŠÿ³'¡“Šîð^yy&‡>>|ùOg˜¿ýF–A!%®%º”¦ª½F‚&¡¯\ç(œn—Ö‡µ¤Ë¨“j™!P'g«¡¦µx	@¢(×v_LÅ4}CÓJi© Ü9ø¶…tI€qÞ[Ø¡YC*àŸuÖpCb²n¹¡êR4ýÉgwŸ
+ß£Œ½:½/‰ùñ1¹“jKˆ6l hÖ y\d'i2„3H§žcwƒ.ÇMd?Ï¶ §¬%»¶A‡<D²Lˆ[†MKÂù074,<Ã{\ GÍºVÛ¾r_4¶[Fí¤‹|pÜ. îâRn†¡Ù¦ ÷ÔçèŠsñ…‚…¡nß×f/êÖtZ}•9D¶£Aj´ãûáj o;Ú\š•UT¸6£ÍjÎw";ÍöB€âfPg<¾Æ½aI¤ÓˆtrK#;§³…Q.‹
+Tî”òðCS¼KMñvøû¡öïLíÿâmPÈ?‡5¸Z,Iñ08QÃ¤ó^£vÈ,]Á£2í¹žëÒV&ð8ÙR$¦ãá±–Ïi6'ZÀÞœ‘ÖjÝ¯À´ˆVÉE*Ô¥yûLÌÂTŒKRÇ+¨ú ,‘ðàU§Ó†ïSÂÞšÞ›¼ü•á‹³¹ûÓ³OÇ¿þrýò“~þñ»¿óÓO¯~¸Žà'¯¾ýþú^ø£××ß\½zyðè!Ã‡Z?Æ	V²/ß8$Ü­Üá3üòo„Þøð×ÃW_—ÃK[ùÅT ²×°"Å¡Žøü^ À$~û|ó8â]ãøÄ¤óÙÅçÍTü¡0lOí|õßvþ÷{t{ïßx ‘µß9aEîœ `jy2züúõ½8ÑÃ—¬Èñx!n Êû;þB”ŽoÚ7oçsÊ3q7Æ”8ù5¬˜Íø‡» ®†¦ÔÊìŒX'6pßÅ¥‘¢®wš„¨‹f…Dã{mU]M<öTrkæÑnµŠÏ8Š)ƒÁb"å"¿Çm¼™ö»ì¬6fæÀžmAS1Sb%p…ó^Âq/è-ÂÉqˆæ™ÁÐÚ£õü¼Í™Ú£Aû8Dà˜}BÃ§úÚŠf3CêØÂ¨¥Òø¾/(#è´14×ZP
+E¹r¹rÔ„×“ ŠrbèFëIâÇCwÌ¾¤1ƒ»YósRMI”­O®‰Ä“Oê=Ò_Ñx²Þ4—CU
+›l„	T¥¬Š°uÉÒˆ–{J¬4tw`ÿõÕ’cÉqOà;Ì	ÉüçRû¼ð	^Ý†6º¿ƒÉO²ªž<-hfáÝtL=’IÉ`&  ;E|­½í9°¥0(Î9Ûj‡OKjšk
+<J®šÔZw¥
+Þç*=84T”UT%+PhBR_²Ë¸¹®•†M­Ì–ö$/‹¯Ê[I^Û—0ßÚÔ‚ÖR*ì©a%@bgÏE{ ¿Ô6F³­ÇÅÚûKº-rY[²èÒÎÂ‹4¸DÓ[«;Wl ¨¦ç3éph¥ˆ¬ãTŠõë${’Î†}ðÅŒÕ•qzUˆ³bíª<Hüë}†2é¢©IiJjÑF›Øâ»¥¤àM;´Ì­><1c´jÜªšÃ•v²6µÄ$JÐ«ôS«+µ(ã1äÔR™’e~*µ´\¶r7jÑrÔ§QK'Æmµšß:RîM­ìñëÐÞÌÒFæco÷¡0KS#ÎˆÕæ©
+ßm®6PÖ^§€z²„ÍÆ»C¯Õ¨P~¬VÉ­Bß~ùMKþŠ`¡ËEÈÅfýã‘'Iü}Oï‚ oÿÞvË6õ¦
+B-¿± øÇJIùKI¿¤$§Ÿ’úó-Ý-ý=Kw9ûÂî×bû×ßŽr_"#É&#™AŸWºkW+Ùöyš‰÷×–wÿóåK«leÇ‚•çðç¾¨mˆ“\DD½†ÍÈûkÛAàÔEÊºP3ëéOÁ+Â²¥Kïª“jªåâæ£Q}£Ü%ª«U¨H©ß®(ø«ÉÏÙïßB©Õt·zÀKÑ«á]èF=ÿQØrn÷ä|y0–¢h á	£ß3ƒå3]ƒÝµŠl¤à]Á[bâ·þØ`ô`ÑýA=Îc1¼çñv“ˆ¿­úHJr¡Œ@ðæR.Î£:è‰ÿX<ÞcR ÍWmóö-Çõb4`Á}@-Î`ñ¼çùöGRŒ­Ÿ×°‰³@â Fø8X=$8‰/IŒ„÷lÇÖ8à¥ZîXïzä€“óó$P»,·ËÆÿÊŽK·bMaÑ$7®î»^Gk5úCT7ÏÕž,=¼÷f-dº BØ¨#ý§ÿ|Hž¤¸„ÔËêßüÁð$ƒ±æö±áAhîyGÙ2_«»9zÇññÒáÇ^S‰ ¬3L3©‹Ëv•üN„:Ø“×ÐH!ª—ùÆeusòD/&>.TùýÄAÇo0pp§ï¬êYÐâx¾‚Ÿ¼ƒ™Ó`öÛf¿k€Âõó ”´™âJ¨9­œVFwLµçåyññ3¼/&y{©ûðHr§Ê»pÄ4÷.JH:ƒžðÃÆ3Ëß£¥¨­HIÜ` Q¥%Yõ^èF>Þ7eÎq‡s¿ÑñêèkY’&¨ÈŠÇú8°Î•d@¿ÿø©#«ÿÅ‘µÖ@ûNX+éŒp”çµõø±_¾¿´÷§Ç/£Ôj¾ÅàŠ"·~¾ù¹µñ+[ªÌ<•;(Jfº’íáñ‹lòêsµxç5™[H÷b~|<Üÿç[édÛºôÓŽˆ²èÖ¼ÜeM^¹GU·Q…NÎ;†Ó»¥4à§Ã¯þ]²ñLKˆcºïy÷ýD/6~nk[kýÕæêô¢¹ìðóÞº ö»­µÑÿ„G‡û>o‘×©â4Õ¾\p·4¦ÁËz†?Ö[¦7ª&„	ßín¨¿>Ê-Ã–ÆìÖ„[½ò}PëæsÎÀ‹ò
+¥í§z>«‹û?CÞ"‰O-PÆ!Ú´¯"’R{«¥ÜkG)ÉrmµúþÒ×ûã?‚ÙóÆì¯SZiiÃn“EÊÑÒqìlÑò°=?U«¤Ý"ÕÀµ„P»tÕ|wU½…2RDYOÔUšÍ9¯ô!ð¬thL¶Ç†|\A°âpé9îõZ·†û¸ûþ³»æ-Cð!7È§ò+ç¤Î›/˜õÖV×H+6:©ÿöaWý%
+6cÚäÛPã­MÓ¸·dÏ¡gÉ&ýÃ‚XNsù×ªNù=Q‹Vô%–¾æÜ6jÙê\¤ªW,‹O»êoà/Pª:öå–9{IïVL®-' u¤|CvÕZ‰fÒweþ’EÇ43Ç?ÍrÒš`ZæO¶ 7yý"ŠW§ªgGï1hlµ…šÌ¢ú‹û¥Ý¨zÀ@Ì„íœ–ÕÃ½=¬^&]Æ¯öÀ£¬ÐX9Ÿ>ËoM‹Ù±¹Q¤<˜wbR¾]JÖáIÜCV‹6óðSÉìN%6£NJ<ËË0®QI×8ÏØJ‘î“úK´!Jß¾5Ÿ•ÁFFßfOW91toD Ëšvxyã·¸ÕlæÔÓàÓ_†7§6/Tk–u("CÎ,ëM[H–ÌAOÖ‹å¬6oÍg5•xÈëLijsÎ¡]¦×“ødiKÆôJoES1NÈ|ŽU´ uèÇOÂÉ¼¯‡©Ûw@6È?êŠWÙR–µ¢:OÕlQmMMÖ”%­@8x}W¤Ã³îC‡RËLñ–’½B600”jm^dí@þx9Ü,8æŸ3‚\Â@¤÷d/Ÿâ%Pb¸	 Ócn¾b
+Ê²ÎSÊ4Û4"ª¡žÉê‚R1äžbÖ#$®€kŸÚõÞèq¡yÏ¡?ÏrðlŽb][SX/woÆVø›Ô%< –‰0}p–øÊgEaedmœaomµ0%<i@}RAGBÖA!ÍÔÝÖ”0KžR^vÄ!W‡ïï“æ(sfQ¤p¿ÿÑy„sÃ û´9Pø¼û™½¦_V­*XL¥…PDtòÆ‚r¢­IZ6°ÀŸIÜÄÃ›cÜÒV±ëOu¾6}—;œù­¨m(cvêÓÃ’£'Ÿ`ÙÃãá“ä=<_Ø|ï§‘Î:…(Vûƒ–3ÓàØ4DèDÌ¿ºÄ]»ÌVLö©Xœ~=P*Ûž¢qä¯Ó¦j/÷ØÑÚ¿wvó~ïgÜó§kï,-þ6,-_Þ=>|Ûsx²üÎ[ŒëWXžeÚ‡°è€Ùi.ûøÝ{LÓJGªsûiVðq!‡§2ÇðÙ}ñ&;£rhöÉ'ÙRÔU=ô¯fè4o<"ÏÇgo†—Æš`AîøÏë¡ÎñU
+©q^Ô«Õ9~ï¢×0{«¥úÈÔÔv¾­dáôëÇO¸!×í†¤o¿üö‡$o¬–çdZ¬o{—tñþù¼¢ûŠ¬nÆ'¢¿|iOîËÚß¿¦€q÷îB‚÷>í{Ö‹—ËKKGåêèîw]É­jžÄ3Ê`{ø¥œ›£bLÙâµepJªÓòRÈRqŒ³äî±½£À¿u_Zmd´>­x¸Ê\Ç’Î6"0íÇØëªð0KÙÕ”ÂXŠ{Û˜É³4œíÀ !¢˜NkyÍ;Ê*¥ªix¥›°Ž‘†Á÷§h§Âö(©©¸è6CaÜ”>8
+©÷)}é¥ÃF9aL«”û2¹øô¦a {sØ~èídZ$™67õá|² ÓMå[>Næ{#<À³Ð˜B$ÏcÂ®áu½Fvßß±GyHj{»22…}¦	ÂJÌ{ò8.FHÎÄZ_¾=¸4]
+£wÝa8@A´©Åë­Ÿ¯¹›¥›R/ïévi9íMpÎå‰ÐæVÉXHçç8Ýd)jó³%…×°`E‚åÅ¦¶c‰Âf»§Ò$•Ã{Žcb|jóSÙÊ§qW»GVƒÞšK`H¦¹i8¯ºî³têà½jðhÖ“Ô,™€õvÛ­Úí8]²E_ÁbK­¥|åe×=_)Ò7mÞ ‹Y¸š†YH2¤¥§õ~š0Mµ"è^Ïœà‹¨Èão½ñU“ÌðX	m˜…Ú˜6hpÖÍ0.!ØôA)tŽ¼ü_ö«m¹m#‰~þ/®rª¬sÃ%~’èØå-Åv­’Ô¾©`‘¥ .ÚR¾~{¦»q#)HŽ#võb‹¹œîé>}šÄ‚­pÂ– ™ƒK«F¹›*1v¼a¸t';&1˜yu[å1“˜ê&Ô>:Ñ2,¬ÕÛl¬\–Œšý€ ë±ŒÚò.ŽN œ6€êX¹? ‡lÂãç@¸YµÓA˜»pµ†’ŠNòlå"yJ¤å*1×í‹6V'ä=¥@ÆI¬w˜)’<+ÓOw£>ýþJËô„Ön…µK[‘8"fœ¶?TOCuh’Mÿ<À«š+Aý~þáÖ*Œ’áæÊ?OÎ¾ëÑ@c~£ó–‘€(eŽô$ÐiÜW˜¤}Xc¥¶%e RÆ5Kâ@Z ,á?K}vp”–ÈŒRŠ“½{9pvÒ 4K_¹ÁÉ>ˆ-RhmÈkn§±íãSê æ+q{kÒ*áÍ‰´YÄ*¤Í=­Ð<¢	±vK^âÐLv‚Ÿ’Ø±³OWauÅfdÛÜÂˆRÌ*v%<49¥Ó¡E§°e!øô®´®œjŽ1R##6Š¤kœ’<Š¤k›|îÞS5
+`g„“gDçZ^e¾‘‰Ñê$Ô–ÀëÛF`ÚxÆ]	Ñ8¬•ìâåûTËÎêÓgôùÉNmo†5ž:õ›¶ÒH]$F“òµZéŠÌ.<®ÃØoKXk`b¥ð‡A@Æ8Tª‰á†š¬ÕYÆò.säÞZAçý4©:P0˜i'm*¦3áøAAqÙwâí|HWÝ<I,ÐÙp‚í&Y„F Lh/èMI:ÒêjM¡~:˜	B—2Ø=”ÂSî@X^Ý¥Š·ÖÈ kúŒHÈD‚ƒæXS#(˜ç6»]«²Ý+Y¯: ¹çÊjÊ“u°Vp¡X}@Ï'¬0$qIEò@$É  ,¥èÁ¡ÆJóþJsJRÃV´'o!**Px¦á¨ÀE‘‚Ó§Csbg4²†L£vaÌ@E†¶<5n“»>Žb´…ø»9tÊJ1PhÕtZJÜlõ6ÔÜò› Í‚ŽiöËóªs ËO¸?ÑÊ%´;C6›íSš:éñl ÂO	Ì¥#CÆØÂ61ÅN
+«¡Tßyi§Tè±Æç”Ví…»à”1(?jþ‰rmÁ9–8pÒÄFù)íWÕìç¥m‚He;T?l—n—øÔ®ìÏ£7Êm' ‘Q†î~ e’-Ï^’È„t—ŒÝ»uˆD:ªŠÑ/`Z2¦sÙW]˜ÀÆ„ß»I‚f?f˜ÆæŽîÃ„)¹Áèjµ%GÜn2+˜tPg½TÜª-i7U+qXqV—Œø&:tñ×²©d0¿I;Ž©=ß$~ŒUÂOòAƒàQ"ìgÌ;‘ŒMóüt•¢dµF÷"¤ÙH1‚âé'Œ¨ÙÂ2¬8¶Ê §8rä„;+©‰†R…MKÓ¨þÀ¨C™ÐqðRœô¢‚ýD ÊNq”3œ³`s¯ÛËe:ÚÌ¦—t\s©kýµÜ7ÂóQ¼u€lšä—	îoŠÆÎ8¡ÚÚï’„´ßrÚ@º¸ý¢­¤€•…ºaêŸ*h
+ŒJ»ƒµî3’U¬„@#ÌDLvÌa°?ÁXÕñ£ÛA(A\‰Žrb®µãUŒÉ–µl«²,Y#ë°xã^Áê²QVÅÝÚ" ©Ðô:^È½’„",åÜ³3oäzDÕÉ8êªÈÁð-o	7zØú4ukò¶o„lâwµ"„Û=ñ.¬en½@ÝŒ–ÜQnDI¢† Z½ÁÇâ¡4`@¾Âƒ
+:”bÅÙÎ‚‡ÒÅ´ã„Æ.åŒ®ÄzšÖVFÂÄkµv"¨2Éû1Ø*lžµµE¬ˆÑÊã€ROk¬–¸I!¸:£F2@†Íõ”­Ú&~ÜÈï‰!iR¸Å+]kåh® 3ÍCýtè´ÙÐ¨Ñ" ``æÇ’ˆÛ±¬ŽIðmÉí©îV™w„¹ûo~’œœ˜ÿ¸[ÐË¾ž¹]AŒe*ëŠRD“tÌ”"ØF ÆÌ]`DM¡l]+Ó¤ï'so)dt®Iaˆí€‹”ÍAs•¥	Ô£í¡†›‹;•{;¯MšËvFµ{¿mda£M•m„äU€šñ,4êÄd4m‚ù5Üc%‹2¤³Û"³D/™UÄâ$jl0.…}T&èØ¹v×¡{î‡V Y« äýHÄbL=¿‰ÀÀŽµ;OÝƒÀò+©b¥`	›8=`Å®¡°¥$&2ÖÐD²Ó*Éem‚f*""#=¬?èãYÈæÓƒ«±ƒpÂ$MÅ´FëXS¶[Öûê"qµÕÑØtV[‡Vbòö¦œD¥Š»bÔ®d¥ce·Ž¹¸ÛÚØf¤Ÿ„ˆæ·ƒÇïãóŸ‹ùIµY/>¥uU…5k<ÿPŸª¼¨óâòðÍ'Ùe^t?|XÙ/"ÀOg¿¿{›/á˜ƒ£æÏÉOGÿúåôC9ÏàÏ—ÎøÃäè¬†3.'/¯¯–|;´ÿéUöÃäÕÁî¯_ÒåÆ}“£÷EÝÿXß¬Ü·£ãªJo†—f¿nªÏ›eVÌ²¸úuû}¶È—ó*+Ü÷7ù¬ÎË"­†øð„[q½¬Ç<h0Êï†±³²£Ê?oêlm—Á‡æÄŽU¶Þ,ë»xâ‡Œ·ïÅçt½­²ÿl Ø7cÎ 5?œÀîûTl®>Îêô‹]}»CÒoº€û®¬ë¼ž-~Í—ã¾å™[ì‡K=à¯n[újÀ^ÓòjU®óÚKòÊ‹±g8+7Õ,{W¥«E>óã-òb˜Vy±/ó=$.¶¿\eUZ—c­uÿs=°-Þ‘R¸wBŽsö?B°ÅÒ×Oùõù×|^ï£Ù½|ÁOpû>,²ür1ª^üq‚ñxl>æÁñûóãåj‘ž?ü°ˆ_í~+òz´Å—ŸÿÈfõI¹)æ°è¤ÜWBìSÏƒ[	îèMv1yý<0}÷é¢JA@.?”ùúydòkdò„x¾ÓÄ¤ýðæybzž˜þÎ.ý<1=OL‚ç‰é±ð?OLvbò¤Õ?OLNLïÒÍz§ÅÉró—ÿmªÃeº9±­9î6.}Þÿ^ŒKëzþ&û’§öŒ'2]ô!ßK‹¼¸XgcoæiIø“IßZ¥‹þ-¤äEEÌG%¨'u0ß’ óQêôë{îÙ*›m–iujU ð–ú©Ì‹úôóQØc4eAùÿÉéÐx~kxús¼ô'ôŽ–ÝsãÚáÁØçãfß2/ºÖº¾Yfc~,‰=gå²¬~úºÈë}{\Ó9øŸ6ÕE:ËÎfé¸kÆ?zîPûùzUY1šuÂÒØÆ½Û¯iY¬ëô~ùåVû^ŠdZ^­Êõþò|šðŠÒþ‡y9/ä˜gå¦šeÇËÕ"õÃ‡¹ïF¹Êª´.÷õñÆ—½‰÷À.´xÿŸŠ3é]•®ùÌ‡øÖÒ^æõ§4ßÛLžJm{ÅP¡®Ó*¯WYíKZuë»ëÏ¿õ˜'žˆ*t }Ÿ.òºØ‚®žˆæ³@ÐGKØèòž½ì—¬º|ˆ>¶ãVûóivÐòâbÕ'ËÍ>F|”öyßWºñ÷«íß!úõŽ;žÐâÍXeðÂ Þéöúé`¿bÿšÏëÅh·Ð¾à'¸}Y~¹ßþ8ÁxÂ{>æÁñûó“ìK¶<[¤óòë¹'=Üâ¾•OŽÞd“×Gg¿¿{›/ë¬öWg|ø¦^V«E¹,/Ç¨çQºJ•ÎóÍz4§Ü§ôz–$¸ÃYrÌ³rSÍ²ãåj‘úávÇÞKdëÍr”]<Ï`û.´ƒåíNÌóeZïYìI‹ù¾4éÉSŒòâ–Ê}&¤Ç'$_’çiè³ðŸiÈ›§¸7}¼¸Xgc‰ö(4^½¾Äü[«×I¿»|ïòžàÇœïbŸõÔ—‡Úìÿ%¿zÓ‚(üWrÌ¥•Û©×”(=Rà,Ë¸¬´^“õ.…þúÚ&!¬{X«‚WE\|°–ï­gÞ¼©H£úuáíÒk2²Ë1¯Ú³‡ú¯>µB:¡§¹*@\ÿxbœû ”ÿPûAÉnïÚÏRôhéÙ—¥Îvs‚’CÔ¡$ã³YYù[bsõCÍ)p(¥pÊÉõBi^‹ÉçõË’ðèReÑ!ïA-$edÜDl'ÇðÛ;þŽ¸gºŠ¯ü+ÔèÞ¹ývXÝ×ÂÒsÒ$ëÝ³_É=†6v(k)ë	CV»1ù¤ÐlÄ©µÖ¨Q1Îun'¢|i‡8&ÎY0²>úÿcµ ) Á£îÇ¨ã‡{XÔ læNn^7­Ç/Á#†ÎWUQNõSø¢PÂüÐž.ÿÂªNÿ\UšgDW1ÈTiÍ•Gj‰þtÑ_øÓxÃo{|iZ÷‹)Üê¶JT‡!©ß¨[›gœ$Eç€â»œƒaÀW !úŠµ‰ÛQ—³^¾FéË(''å3'A+C¢Kè…e¼17ú[JŸyÍ;è­ÉˆO27Ô¬VÊ©-«ÅÒF‰"çÝÊwNX6à	ý[ìAšåˆ*YÒ/>h' ^`™üÎØ4P’îÐMdÜÞ4@øÛ›Æ¹
+-°„ÈQËÄ,Mâªí*þŒÆ¸ý¡-,Aªgh£ð·[xµçØ?}Ç`¯H£úuáíÒk2yêª={8¡ÿêS+¤zš«$OŒr˜òj?_1øß·Ÿ¥(èÑÒ³/Kíæäs'Ø¡&ã³YYú[ê
+ßo¹"ÁsJÜLIÊÉõBi^ŒÉçõË’ðè‘Ò3‡‘16T±ÑBRFÆMÄqv| Ç½Ãàï|¦«¸ñÊ¿Bî]ÛoÇÕýx-Œ!='MÒå–Sr!¤ÊÚEÊzÂÕÆnL>)4r{Ö‹¿ ­6íâendstreamendobj96 1 obj12163 endobj108 1 obj<< /Filter [ /FlateDecode ] /Length 116 1 R >> stream
+H‰ìWmoÚHýù|Y‰•ÚHB[­?…°A‘š´*mõ|‹{Œ§;žñŽgè¯_cñ˜$5—Æªš7ûœ¹÷œ{¡6Þœœ6Z×B7š“˜Ð·³/zšä×ZJ‘iã¯ïéº1(*òë}æk&QÎMDkÅFFÓtv[v!õ	§?—Ý”=ïÿ7o³KÙÃš!½”\ª’Ý4ù³ÑfßÅØÆ)Hœ?týÕ{ÂM~¹ób‹ çOØˆ«oB¿ÄWM	–O,p`bàŸá@Ï„‹]ÑÔpâ?ÇÖ9ÿàXðÏÚØs )„¿ÝXü{üÖ)ûÏ«œj@Lš2"zÜ(ŒVµ…Ì±´Ù¾2ïâÀ¿·Ì‘à_•yªƒ>½gdöyˆE	òNJ¾¡jMõ—ðš·Î~=RóÀÒ¼{UûxÏ}TŸûAÎÍ±?÷[>¡x|SèôÞž·ÿÀq€SwÖA9³ù¶‹úÄ…þÀó¹ƒåèáÚ"ÊÆ¸êuÐôÏï®ËÞÅõÝ¥”¼§(ýYfßûBÆ5UßÓ`Æ“£Ô×=iDÝÔ“e2ª˜“Å`£Q¶ú4lx'­á÷ÁUþ!wCËÿXýZ(UI.Ç§dN*0öÆŽ^X€}³ã¨J£|:P$‰˜ƒÊ|ìiÈ„*¢%Ô Í€q¢‘Îæ—Xavöß~~wHºsî¾µAÂ ÞáhÚ jƒZcPHº³6¨zƒªê¤IUöö§¿g'QïOµ=!™Pµ=Õö´bOHzóXíi@Lš2"zÜTñò;!ÕAŸÞ32»
+õÄ9ŽV°!DÅªÞ!9–Z!‡WÈ{­€M!HŽå8B‹‰.[I*ì<8ÔŠÆòÉB5Çkï…9pCï4:Þi»Ñéf_Ûì¿—ýœ}÷²äDlzËÛns*›YÎûûKéqTÌÈÁnÀiÑì´‘É±Úð}ÂýYš4–Ò„3D>O˜ó}›TSH,\Š˜6AÀ4+µ¬‚±%œøXè,AÛdM5QâBø™"Ë²ÍdDÇÜ¿°þ¬[‹„Ý‡}‹‰€†L°R=U^‘%p`—<®Íî§¡4Ê§<‰ŽR¬ëªÔpPà£òT/ïï›3óñš"¢-ëK'2-w'äšFÔH{ŠÙ_à“)»‡¨Åév;P$‰˜ƒKŽÚ&"ªˆ–[nžð¾&aã“ÅK¼ƒƒÊ3Žj…Ú[ßD1ÅTc±ª¢Î‹|þ9ƒ3 ô²~G½³ý‚ŽDË3 tPÆX Ÿî8Ón¨W1ÏÖ¼uöëñOR$…gpJyî;¶|Ân±õâúî3›Pþ™“é–³\	°!ãšªo‚é"$G?¨¯{Òˆ »©''88YÖ‘ûBAjÝv£‹dº0oìúVŸ†ï¤5ü>¸Ê?âZQþÇŠýœ)";µ¢±¼/C_}p·ŸsÛ5³wÚnœ¶=D½ oSZÞv›ÃßÌÒsÅŒì6±À€¡¢ÓFB$ÇjÃ÷	÷oà5¦É™ ¤ŒiÅ4ž0;=æû&66¦¦‰ü‹˜6AÀ4+µ©‚™%œøXè,AÛdM5QâBø™"Ë²ÍdDÇðzEð`ÝZ$”è>ì[L4dÙÂ…¤¹
+ÀwJˆbÒ”Ñã g¤qm(òéO"‚£ëº*5ø¨¼ÕË;ÇûfÇ¸‡‡ÁjÈKuÐ§÷ŒÌ>ñxƒ„y'Y÷Yš”~dãHg4ê´<šW¦”sùà¥ÂË”I½lf±±ôî™äT{ŠžTDŒ‘0}lÄÛý­/¹DâDÏH]$ûRê€T¤: ½²€ÔgY%…Î7)ŒåÙ¶Yjßµq¢ Øñ¬Ÿ,6:â$D–x~ú™QÐÚ3ìó€‚ƒÄ¾y‰5‘×¨0îÃlå.6dgYžŸö¥¹#ƒ>ƒÑ
+êujÙªDHYˆm2[å/' â å"ßiE&ÔÏ¶põññ!¬	ÖÜ,†cËA–“qGX–•ŠÛ`Ž×®o¡l%/®»l,½±¢TxóÎö²)M½{&9Õž¢'c$L¬œlqÛmÎk3å­Ô^õNfpœZ:]$á+˜•"üÌqý›ìg¸.‚$õxÂì4šï›8óLÐ¶šB
+$’)bvØÓ¬ÔÄ
+V—ðl»ABg	ze#ÑDëádŠD,KÈ6“ÃQª„Ã#X·	%ºûV6~hÈ+ÕSåYßi•ê³|KÎ7)Œœ	ùèO„”gf†X¼kã P ìXîOóü"K¼€vïH°–ÙŠdXgp³0	1HÖ'ƒDYØ6™Ô¨0ïÃléWN³ÃçñØÿž$Ù&À2¡á´‚{=¯K)òiòBâ!«¸m^[²Â2Z6Ë*¦åÂÞia¸”q"Óò½ç°ÛèÍèœí7·h&N!&Ci”O/xLrÌ6™PE4¬ñÒ¬˜ÂÞ×$îy'I"æã(Ä¾òæL&¬tT‹¶†&-k§ãÑ5QLG1ÕXÚª¨ï"ŸÎ!&HV«Pz\‘@ï¬@?;–S?[JôÓ×5Ëp€çŽ1$ÒÝ{Ž¡Û¶ëY†Èšö˜eX ï1ËhyŸY†ú®³ì†ªqslÍ[g¿÷ERôùÝXôç¾cË'XÇ@Çxq}÷™M(ÿÌÉô®LaUŸeàj?d\SõM0B„äèõuOd7õä'‹Á:r_(H­Ûnt‘L–æ]ßêÓ°á´†ßWùG\ÊÿX¹÷ˆISFD›*^þìo(òéO"‚£#öÍ£ò ˆ©úôž‘Ù3 .HüÓ†¼Ó*ò)S
+Õ©$ðtÒ¾ZùéÏLIÑ ‘¶×+#˜B|Ê"^Åðg@èe[:è“:KüzçÀª»-BÅoU‡ùR3P$‰˜4%Àšë†	äÃ]ÉAþþ¡®ÎAuªsPÆå"u:R-`ÝÇöÍApÀß'a^ç :Õ9u	ƒ@ç}Ûéþã W¼´^<Ø'.öèÂß9o#Áÿ×æQ6ŽÀU¤s†…Ä¯Í‚ƒ‹ë»aDùpwŠƒÈ²cØŒkª¾	¦SpD~P_÷¤AvSO–©¨bNƒ>ÙêÓ°á´†ßWù‡Ü%"ÿcå›ËW£F†SáW½4Áb¢Qê¬êGEcy_†¾ú&ä®´–7ÝæˆäHRz¥è¿&ëƒ²ÑZ1'¿ãJÆ§öÿº8˜ÌÁÚ´„á¿ÇÕ	²©f·ÌÏ«Ž3¨6zŸpÿF‚	¡É™ ¤ŒhÅ4ž0;"÷}ÛhSHÄ¬Š˜6AÀ4+5Õ‚õ&œ”Î«ªé,AÛdM5QàšIø™"Ë²Ë$¡D÷aÑ3Ðe«’Ò€¿D‚µü;»ù8BE|Mø­d)’Y>±˜#ÄÃïà@ÏÄJÌGhmÛ¬^øvµMI˜øSÖù÷u6:EÄ6—T3íG_‡É9ÌoÆAÉîH>8ÉÌÖm§ÙK'2-Ÿ@•[X-–s_±Z&Ê -Á¥Q>½àID°°8uiÈ„*¢å«
+Ox_zƒMàâún¨‰f>Ž£˜{%wÆ5Uß²…ôf9úA}Ý“FÙM=9ÁÁÉb°±Â­>ÞIkø}p•È)çüI¸ží·_™ÿØ/›Æa(
+¿
+v€Êßh+(›,ú #7vkÜ8Šiáé'IC!M\'¡?§Á[$”ó¹÷ž{ŽHC ¤á6IéÚF Ñ›åÜŒƒa#IwÐ¯¨ûƒ¦ÿI÷û¤Eœ…wy±÷yÑîØÇOPñhSÖƒS>_U>ãT›Lv©þ|€¢¿[fŸÖì‚ñ®÷¤}[úÃ.1`\griÉIš!Å³äÊµ&¬Öt…Á²¡ÒBãJ“+M®4™(\ir¥É•&Wš¾\š®1`\i,MO$QŠ“ð^$»øø‚Çâr?Å$
+¸‡1ÕÒ¬3Í?Dg²AÕm”¦ì'ÙÿHA*KnU'^|_1ÛÄ®4ÐuÜd™¿~fª1£@­¢ë^ËuÓ´÷Í¦Ö> ²Ï´Ò¨µ HŸ·4 G!¥m®öâ?Í6Ø“B‚˜P×¥B¨»Æ¯‚Ùül†NsŽ›± ÞßÛ£ÅŸdD<®_og ëQà´Ú¡œFRqm{Ð+4^ßãL‡‡
+”K/ÓÈˆÅD'h‰dÄ#|èmëÃ* TÎ†@ëB[:Õ÷ýD±ß|èTüüjõûJ“Pçß‡4KëˆLºi}÷~Œ™H5,JæzŒ„O‚Ë$äOØ8Î/¯1@–z-û¸…û=N¯Æ#t=ßtaK]S:DMNObŸxlä{\Ù©²ä2NñÚCæÅêDÕuÛÒè'*).Ãˆ"dœ®ëKžY`îO;fZÞ*a"æ%‚Ä.b}-baŒ‚KX.aõ"a©Â–^ÍªOY=)ï¯þkÉ5H) žQÕ]Ïu`é«*Û%?£ÓH*3Ë~Ó‚Õ›áœ­çÍÃÉH&±ÇîDÍü` Hªzendstreamendobj116 1 obj3542 endobj120 1 obj<< /Filter [ /FlateDecode ] /Length 127 0 R >> stream
+H‰ìWkoÔXýýüe$ˆ¹ïÇÎ§ šÕ£	;ËjµB¦ÛI<Û±³n7¿U·ÊtHb: Ì@­DÝåû¨Ç9§ÊÅƒO'Ë¶[Ô{óãf¹èëöañhöøY3š®­ú³â/³Ÿ‹Í¢júæýz¨W¸4­JÞ¾üû+X «t§u_]ÿ°x| «Û£óíø¯­NjÜ[¯Yñ¡Z®ÓU<þ¥¶g§éÙãý¾¯.yw»Îý}tÓºí ë§ÝÉi·j†z"Î‰å7‹ñ¢{×æv“ýƒnÝÏë}uzÜÌó(DÓ^†R_¯ÖËa*”e3üZ5íuëî8ŠÑçG—
+¢¦ÂX4‡‡ëÕupºóZÜš×UßÇ'õ¬.òûb<ÿ5S‘ˆ<@G/¹.§\¿nÁ]».?s]ß—¬ëÏ\Ÿ¤p.®«ï«—åÕ ¾ó6¶:­çëeÕ¿^gÉV–‘2Ý¢•åâú-ZY.]ø­,×wme/ëþè.ÚØ·âÏûÙ@»ÃÃU=<Y®û¾^ì/O«<ªO­t×êßß:ä5|Aö¿öŽËõ{³îß¯—u;Ï²€tÂÍ%<ì«ùP-_uÍêºµw\ÆÍ‰;Añ [÷ó:;-Ø}¬ž„TƒõûjU?ïëÿ­ÁÑ³©Jaóˆå’×Û!µë“×@…¸zbÖÈdÄ»èñv,«¡æÇošåt0mwçÒ–ã;µÒ§Ý²ë_V°èÓ}Õâ“›¼¿*œ›xÝV„_Àý«yµÌ$Œ«5891-V…àÏUß6–<CÚ‰ù/ªõjÕT-¾äHýïhxÉï•ìjê¬†Å³úCSáS1™<Ùvy'‚¼><\ÕSµË”ù!ê¶Ü *äÏÕYLNõ{™õ‹Ï&ùÅÔø`/R£§;N¹'§Ýª¦fÉLÙœÙ\u[*cÈ8îæÉÕ$nZu_U)¹¾MwZ÷ÕÐMÍx×ÃðŽC8÷÷;gó£Ç· úuTÊ‚é»´²Ì¤sÅH›ú`[·Ã›¾jW‡õ]0eÛƒçëvþ[Žü¤n†ÀP½Ï¥oN¼º÷;ú±šŠD"“8.ú¼–I/~ éÏFRéQdÉWaéÉ,ýéX’÷Q–~¼ðÝ4¾…)ãyÓgÉù¸ëÔ´j†)&fü^‘W¾OÝºŸ×ùÄrõ‹EÓ^÷Þ³	†¦Ÿ7ó<bI^oÒÖ}5tS/
+×ÃðŽC8÷w'Š¿¬û£» ÷·âÏû+,¹Ñ‘¤åÛöë/§TÌýå2<|a£Û9gSiØ“â§<RpvYË>Ýß?]öýc³Ž§ü—6ÿÙÝíŽëæèx’Gù1ú{©µ/¦"ØÿåÝ?»nqÔW¹tEôùRËk–CÝÿ£m†É·²îýõ|xÒ­Û,zÒ]G£;Ži+‚eîñ³ú°øyöÓþ/R¼ûk»8øýÅó´M-ï^uí¯Ñ Aíí‘ùI}Ô´Ì^òéÑÁÙÉûn9{ð¢.ÞTíÑÃ™(öáïíÇÙš?¢xô‘éó¶šáW2½=ƒƒ/€écaŠ—Å¿ÿ#ŠòÛl/H#Kk….‚²¡ô"'l"´ú2ë2éÐæJBD›Ž¥ñVÒvé\1ÇíŽ²Úð¡VÑÒPš@ÆXJ©uq6£¬³hv¢TÁÉt•*#ìE£.£·. a›AW](w/e4Ñ£9–ÎÃµÊ”&F²YÓ¡|ñèªs¥3ÎOq»T¥É
+[àæ´R”>8ÕÉRù Ñ(Bµç˜¢t»ð¥ÞPV´ôi¿p¥ÒlrŠvÛÒkÍë„±ãv+}J4.¶¸l„286ºÙfÁÚïJi’ûh!ðõÖ¸tÄ¤dd£–TRL©<?@D«Èl;Ào‘ÖŠÒ)Ë91^àB¡N ™´_ˆ?9`i­‡ î7Š£Lñ¯´káÒ’n¨R°M'Ä”-§ÒB]jß¨Òp¬·c))®’‘Ü’ZF¥Ôi¿UPsc>ƒ%C‰ŒNN€“Âl`éU‚ ä0h?¢=/æCb‹(…v\H\Â€A4{6º`-­TžOõìX½š¬ÂIË°,¨DA I„¥hƒ’\Ð$lâ7GÀ|À±´Ö‘PÏM¤°€6ÂŒ Ë
+hLwˆ=ežx¿WJ3\0Lx8Ì¤ûDÚð~&)›l#Û„ç×keÑÝÛ¸²Iy’þFÚ–«§³Ã¤_ÂBH¸€ÐQ¤Jry
+¿‚&Ò5Â"rÖj»€„4“5qt4ê´n7‚°H“‚>	5z¥	A`V^l*`çìYÎþ¹ÑA cýG³ÅÆú+ÏÞØtb#Ød)í…û£–j*mTìjp){#R¶òŒxÃ
+
+•öAñ]V‘ÜÔXØœ)®Ì åß9‡ù·6¤Æ40hÑÚkêIÄ_k$m7¹× U’€Þ2Óà§§šH'ÔØAœäü[1j(ˆ…1dÆ]Ê³¬x­¸èàÉ™à¨ÄQA­dH8…¡èIÁ@‚M´ÔSù$
+D”t?Ð”e	:ˆ—Ô¬$ŽÕÚÆD>l–~Ól”aÔ”= Ìšh¼K@(Fp©æœnr¤kOø 	îÓ¹XÉHM »]’*”àà5ÇDñdÔ!2{PY$©(yR`…Xk²	ÉIõØ¡ë2f’
+ ûMLû‰-2™°„)  IâHÎ?Ôš[(@Uà,À ˆ‰”€I-èþ-OðuÝ	ÁZ-t|€‹Ž“ãØ"ð™ˆ–ÐF-1U+*Ê¿Høƒú9OðÁþãý¨Ã>g/¸*.i4†;8þ$¨c¥ æ¹1ƒQrOÑÁ¶AŒÄŽ2Ê4Îvì3ZJîëÁOF¨‹b#7Uœ ÈSV@*)Á¨qZP$é8†* Ù(G¥PGùCjÓTòhBpò
+ %Ó€4œúh  TK" hÍgBÉcqeG}Ê…’*ÌÆ^*½0cþÄfðœT¨V ýØ¿A )-Þlf©'‚§
+@”†ÃGôf ¤y"%Ž½¤>0´r›žò¯ QBqNŒÕ,ôÀ?›¢Bq'OAS Ž¹»4 <×bä)ŒeVRUÅ¦'`¥Œf¢¡ÆaGe0ôFiœÐcQi;Î!žÇ¿H–âpô!èp>«2'ô&cFô†÷¸y"|#QÊ€£0ûŒð5ÂrªUÜ«P$V½“£Æ‰±PØ›è  ³S¼6Œqn§egÔhL¢GŒÁœ‡,7`aåèí8.CÚ‚vìM Ø©Í`¨€w4Ôá{‘s<ƒ|Yj BÑøò]BQ«MÓH›Ð†ï0JÈñÅÆY5œ N¬iÐK3Eè@–ZÂ¼*á}„ß d´š uäéÍ",G%ÝKfÊ=Ž%žê­Pø‘BcóSÖZè Š4º„dsTWñ°Œ½d«@yÓ,Œüj7j` Ï{°Â´hIÆ(þÏ|µµÆy$Ñ_ ÿð½$ˆã¾_’§Q¼ÙMÈbgYÃ²y,ËZ<’c‚þ}NuUu=#;ÁËb”H5=Õ]§nçè@§ûº&£CH,ŒÙÊ
+tßò¸†mˆ²à³˜òVÖµñ<„,œ,Ä&DÙ–qO{+ö0Ipu6–ÞƒA¶½Q·ýÁØ‚+Í[¬òÝépÊVèQI^Óè¨'˜Ôøœ…™jJ_cÀ30gQÊŠÚÊ²d¤Ãñ÷¡Ã”°¡E÷2°èDã×fK2}ß‘b¡|g¸¬mˆÈ9IŒ7aìq›™rùFôäýAõøDXž€XäéåóÍÃþÅív{wõð¸|ÓÙ3"÷Ô^çËóWû‡Û»›åìâb³Ý~Ú½¼ß_ÑÙóåœü?úŠYûí—•Oèì¡ÅßÀ!Žeº­dÕ]¦F	.PÕ¥N‘åjs6DÔ
+ŒÁM®Tæ=Èbéàb¹$áHµ'û²-KØëî±ÉéFH+–”}KZ(Ì-% UÎ…¤Üå /Ã›xýŸ‚×,7Š¥²r±©€ÿªDÊ²ÅDÀPìò&X<ó-nn¢"Q%#vuå
+n1ªº2F6±À¢€=W+ª=se“5E„äp ºYó–Êž5Õ™vAŒ,1°Ã°›»ƒª/ÄÈI/c6@ïNec•$µáÆ_ÇLªmšÓçÉ×E+J¯j#±—©¬ó>¶+È†Ó)Pp¤ä~?T#ÄÑ—×êµ¡…’ ±	¢&ƒ(š%«D´QËßw‰
+éUÊÉÀ‹“È‰Ð)"f<öa4A¢j«@3…7YÇ¼‘˜Qmb‚¨G8H	fQª±ëS<OvN­UÞYeŠa©ký´»I’ÀÔäay.ŠQi²È©üÓ.ølÛŒåÙ³WMÃ‰Ü†T¼èæ ¬…ns:
+uÌ^æ´‹ƒö˜”ÍèAûPã>¥/À.DaåWÀÂFúð²ƒÆùlvŠsfzNòÖ4y‹„`—Èf¤ât2#í…gM*@˜ _OýçI]ÎÎ—×ÿ:ùtâY6:0ldnÉœ—ŸkCoa¸)L(a4®Ó†ÌÂ,¹iP^ƒ±´Nõ4$ûÝw:D—‰QØ×ÁJ•­„5žê©MW«4=6’IFš©Û“ù±«ukâÆ”ª”~`6@1$™¥m¢aÍN˜r–µ‰7$½ÐçÀ/H!SŽ±ˆTÀu)ñ ‚Ï›Å&e>z—£ö\Èh¤ÄANaM€%2f‘$suKdCT›-ü‚õkûÐ@Ñ‹X5ÒJG2…ˆ¡$u¡"ì˜IÂ« ÆL¸Íy^‡¶3Jr”‰
+«èìUš“rSñ’8ÑGˆNIÛ^WRšO’x¨r“ºí6,uSšnE—ÜïFô¨ÍrR#8†ðJïcí¹ñ*bZ–Ù¦*ó„0>4¶ÜêëÕLT‚‡9%†@°ßöªAÕª3O2¨]RJ¬·yïŽŒ+d†”º&}„‰LÓ@¢ª+s^Ô¨m=:ZÅ"úÎä/AK´ÈRU…Iw%Ö¸¤K]=€FŒ¶Óê,&t›\–Drã”œa.£Ë1§J¸¬5î3…ýîÄ.›²2hiÐ?YpŠªZn»3Ø¦`ƒ6ŠN1ð:KŠyeT¼k®Gñkab3\›Ü®•¨fÄå½Â->A5(3óõbT´å¥«£#¢•Ï£è·mµÞhÕ}[2¡s·ús‡\Ê«z›´<™	¨Qç_1EQ‡§kc»_¨<+ë
+P§ØêõàúfÚžLïìÇz4ÃÙaØÛƒ%n>WKŽ¨kÝ’ˆ%ïÄŒ!':ªdl„]S“7|ê‘*µöRmn,9õ³¶ÓÆ¼Áø¼Qþ‘ƒæ#BRavÉˆÙ›”´Ñcƒ‘ŒÌÜ1€Mj%†›zç"M%ÊS‘Æ#_GZlU‰†(F?VuÎ€ÈUc5VÕ}`|ÂqŽñ£Öàçà“Nî¤+ÉJãþôwdœ3ˆQgd!3ˆžc¨ÔêE·"è Æ*Û
+ôPÇ*(0*¨<Ž5+w%iTR_kjƒÔÌc)²,$•“òPw'F/œ'm£Q¤…ù;©'cY­ó)ªÔ˜-ç
+4 wHLm‚„$'þ”`Á¬-m	iy
+AJÀéåóÍÃþÅí–dïÕÃãòLg¤#ÈÄùòüÕþáöîf9»¸Øl·Ÿv/ï÷Wtô|ù¿ÇÏÓd=¨ÐA´`º,!+B‘Ìà˜‰|õ–µ0¿Š”PŽ©§Ë¦H1xˆœœT–­³Zn1qbð[ÌêÀ¢J« ‹œ[9[·2kQ±ÍYR²±”î ©¾V0™è1GC–*¢uQEÁp¾9¡˜Ž"ôÒïšnªWA…F>Ëª×œ$¯¹$ÛH\†–“È`Åà¢ö¦°àîª¦UÃÒðHrW3KmVöŠÞOV«ø …_ªï «òŸª—1nÿè·ÓÍÖ\þåîí«ÇÝ›ûò÷ÅõÍíXÎ.>½yóáúœæ6~^ÿ†‰BÿN/é§ƒÓK³üBÿE£¢ä²ÆƒçÛÂ#†Žah?6ÃßðëñùoKX~^þý³¼mö×/ñ?`d0Ë+‹øl¢.u]B´…ï}ûŒÒ˜ÇŸ[þ¢/TÓ) ›|uSŒúÅnJX!¹›î+§ö™Þ(Êû»Æ©þúák#}ñs5p±Jþ«÷W¯/>\ß½ýÇÕþý/8ûgÿì‘_?^Ë¡ÍO?=yìç«ýöý¯÷×ïî®WåÔ7¯kÎ¥›’)4ÓaIÅCŽìŽ> ö!{]˜®)†0ÍšTW£`é2é“:Ÿö–ÛÍ~WFy…@ÿ a{—ÉoBk¦TãjÔŒö7¯NèV~±øRn7ÿ›ÜnÞí¯¦Ôb\ê<jÖû\hÿ/'ÐÙ}ýtW·ž>êè¯ìç¯ìæ¯ìå¯ìäÿ·>æô
+œRéð|d“,=¡¡;rÊÁeˆW–ea÷ô‰¨'+ü
+'Úfóhˆ ˜b‡FÐÕ¨yô fóYPµl}˜£>€3ÚÍ)5:9E¾pó|¿ØzbÛKÇÁÑpx|“z `3˜ÄdÑú´“æÕ&‰Ïî|goÝ
+šdMîÔÁÔÈø4Å±ˆ(R#c	(r£ª«³àAÕ©Q¯Ã¨`,»¡'Çã´;ÍÄÓæëÙÔ™:?´ŸëñoGŽ7Ì8#ñWÇ&€#†,78’QJRÌˆ|SEø`Ct^«Â±êS£"éë8tðAž½£¾@‘s"°²]&¯€Èó¶[“ß:NŽ V.`@Á–©§M›ÛÐˆë	P4 .š\©ì/{”Ðn6“â«¦tVÛ$€O”ÔP ¥	 52 I5ïê,|yäyö:Œú´›½ÏL¡‡×Œ‚HÆÔØ!å×®ÎŽ¸V^1Li|¦PŽ‚)·¡¦P%‡˜VP
+öWm°S1#¶Xtpz_¤¨“%(š2l
+(ŸNRY¦Ùa7éÕ¦ZU_T,Å!ðIÎÚùn5*–òÌÕÙÏÊëqì‚eqÂ2»¶…h~,R>a™¡EC ˜$Bk7›Ñx&ûf±\c~Q(>¬Œ'!æç£Ø=9»Ùg·éõŒ§Z9Ô"ã©sèhŒËÕØáä‡®ÎŽVNÃg8ÑÔn†3–	–$K°ÄbJìÌåê;–bFÜ1…(XèTÄ·²¬E8ÎÛ•M¡4>¸ùhphJ_g§Ã¨`4»9¡f*ÿ;ãÕ¶[×qC¿@ÿp^Ø@«Ì…sKŸ$¹AÓ&h'¨ ”c5vaY†­4ðßwqHÎÌÞçˆÖ27‡\3$§×‘Ø¸L	À0£Sc]LgV‹ÓS”ÎLò:[6:U#q[Œ:ª{F1*«ø£ìÛ`Taˆ—²#Ê}•ˆ«‚Š´¦&ŒžMÚ™‚%ßÒÎé- cTa$oŒL¯…%t› Œæ²3Y-NOPFñÃŒbž£*”xÎF#o]Fë¥£Äž-Fò‰JSF“÷½`Ý¥/±jB%t­b P/[,ikKØÙœTüô:A‹@(0²/$”L¯à	ËbØF` qªÑ.¶3¯Åë)Ê©Š¦Î)´SlB¬*§FËPŠ{5?2|ÖPýàUaâCÕDÊjóöL©ô%I1ã4ÖZ6–Ä»có«Ã	ÙÑBè€‘zV>¦Ë0‰ZÜžnà T]lgB‹×Óä…ÐP*-„ªvâõ‚»Acº'¡ùä¡fWz/C9¢¡
+óæÉóU#åÞÐsØ3	AÖW…ÔÀ’­nmÑjô~ëu‚8pæé#´L¯à*æ·8x•hÛ™×âõ”åU…“ôPRxß]=5¦wòšÊÉK­Íeqê[¤A¬ÂÔà9Ø”Ê$ BmM¦Š2—¸€FlèÒq1WÖV¦Ó	Z Æë,ÕÈ‹Éê´xÌ0Uøã|Vu±Y-NOPZUC­2¬X‰ðïXä–Q¡ô·´6i{Ýi,YY(HØbŒÕÚÇ,t_Ö¬
+tä
++×J;[è€Ävz  ß4ól¯Âêp
+ª²÷q€ƒV	v±i-^OV}­aaUÖ%ÏªÆClRÚGÚ–RR±ñšœÌ]:Ù¬*AD4JÕYydÒ§˜ÞqkJ9Ç­×Ôl›Uécæ©êD!KÚF` ‘ªÑ.¶3¯Åë)ÊjÊí«ò{ãN0‰žöÄö~Þö©x¿ƒ¡Åší¤¥7VÞK’¦\›0‚aC[»¾Köo§·Óƒç2Ûá¹ÄãvuYúC›³lîg*‹ÇÓ´•K®ì9¦—"¨Z
+ë˜rm»ŒzþBï§±J¾ß¢p ÝaÖ¾·¢"C
+Ò|¬˜4:¢ÞÚB±×ÚòÖéêù¶3(Œük¡0½‚)ìd´À@ãT‚]LGR‹Ï“ô…Rœ³~í¤U”TËnYIC+yÏht]w¤z‰¡GƒRƒ!«³U“®Vèë–QqÒ^ì´J’Á?mÁ“w2
+¦ÓÔ ŒS…‘‰$‡¯ Ê»¼‹ÀÀÁiÊ[Ó™Õâô”e•·%ãsÎý¦zŠçÔ¤µ¦²§5ÕLâ4´Aªž#•xgª&—5'J"§4VÙÚbŠýñ,N'ÖO·=L0äžíö†ÃÌå*727p*.¶3¥Åë>yåSu”Î}Ó§MuTÅŸ|òhÛñ‰%­ˆK*1FFÐ9Út‚SÒE¨…ªIyÙFá-…¼µ…nOö[¯¨ØÚ p¦YæÃ+¨Š)¦m­íb;óZ¼žr ÄÚ
+UêºI5UR¼ðNby©Ý‹Aš¼¦•ZÆýÖ–¥¡¢O‹pQRÅ££ZÑŸm-#ï5Ýrq¹€z¼É[…‘LZèÃi®È®¤íùVkÚÙÎ¤¯§0«þpõþÂ)Sþ°ì¢!íù£HÚ¾ nÚàÏ`ˆ}ì3KÕ§®È:‡rmÁÈªcc9Ù¶^P#0Ý¥0’VÚÃkæmGÅðˆÀ@¡pD»ØÎ¼¯§0…O~þâêÃãó7ÇÇ7ïn?|:|	èéÕ³Ã/?¼y÷ëáé‹×·ïï®ßÞ½{õÝíãë¯Ÿ?;ü‰MþñY“>½¿S£«o¾9köííãñõWÿy¼û ¦Áß‹/øå/.®ßß«‹|xúìðò_O¯^=ürwà#ÝËÇgÝËÐËï.ž <!^‰œüxrµÿ£<¿é?“»öîÊcñqãçâ‰ûüO þ?¾ÒŸÓ¯)l¿þªžýÒÎö´OÖÉÓþçzÞP˜-öN– ]Uñ
+˜ZÖ3}èÚ~.ÚöcÙ@Ùýmèë&Ö9Rž}úŽï<8¬LN±f‰}Ba%Ëöº©7:Ý´|RÉ…Ro©k&HÎ*Û¯^z1(ÞntU«Ô/ÚnN"ðPM¾G‘õ×MÜ­d&±ª“ƒ)(‚ðõÉA¼Kä tÕ”ÄÁ	‡Ÿ/?ƒ—Ð—Ç}}}u<þvÿýÃã-Û.¯ZNtº†¦Ø¼^OBAÕ©.ÈÆH<b5JAIï~ÐiÕ¦ßäºa ¡~)éÄ·PDg`¸Uš_Gà"IrTjèÃRÛÊÎ¨É®k
+4´~ùGKªÊKË©¨ij^’îkûä?Ï+ïpÄîÑúãEÓZYÿõäêkï~þë»W/>ÝÿòðV¿¾ûõÍ;EžÞ|xøøñð7nAÏ¸Îð÷åï¿õ?³â¼UØíÅò7¥¿ãÿôûß~ú·;¼bß÷€Ý„_o´ÉU@,5¼îc>QTU×HŠ£°ÞÊ:&láéµ¥¡_šïnQ‰Íé6ˆ•ÃËî–0©w
+}üâVCiqu{k€Q¡jÛ«ºƒczmA\áêRªÅcá'a¡³„åøÞ%C›1:?ö7Lp’ª-È^%˜$¼`g’é‡ RSŸ÷ÑˆÍ1.Äžeûç/á-žœþ‡Šã
+ñë´1vØ,½mÈ+»5.5×Š+ƒòD²oîG&ÚkôºÛ&ã¥PR0ziSÌ
+††6ucúTš*ËÁC	<6•œA¨^2 hïƒaÍ€E­f«}’³-íp–‚ãyfŒ2ºtX$ŠÞlïUød’~ÐÇš¢”kŸt›Ä#ÒÉ’äŠM÷”â’´G¦2IÄTãÜäÙdéÕ]£:€c.
+kóa°¥(`vÑ”ìÔ²?\Ó®M?s¢f8ix£$aá–Z4­>šLúœ&o¿êp}XDZDÿ•–Î:½GJÉ¾GI7Óhš [r‡²KŸooàxþbìÆÐB‚Sýœƒ×Gû"¡a¾ÙÜ¼ Víì‘¤ª‘p­Í¶-.[ÂZ
+^àHÞlíÎàÊÒÀ?
+òË¿Ñ7–$;^Øô~…¡‹F.È¬¹ÅVm_áÎRªQýÁÒ%³Oáp–ƒãyj”34½ÖšN2.5éY/ÎPÅ‚ôÁyEâè¼±ïåŠv¶‘ÂÎëþüãÙ¨,ZL{yz©…¯áF£§K‡bËˆ§^Ø¸µÊõ#7ÑœWïßî§–ÊqÑiI9ÕZ ùRk©Œ’N1)ßT(hM·ÔßGâ¶®%	±§ªÔ%\ó&…7¡¨Ö#°XŠæÙZ8œMþxž#‹ì5ãÝÏ‰Ü[¶šWôYg¶£etlm`È ;½…VsœÙÊç†q3*'ªžÀå¨;"JÞÞb¶ŽËp©f[‚dá¤	ØBµ‰Œ0ÔA‰Aë‘:_·‰Ö‘	…äŒÛi­Ú„˜~ÆVR°7«³Ï3;)w¨0ÝÄÛ˜­ÅæCgR²È^8÷`G²à¦P»„@j]WXË£\êk_óvÿêŠ °ßFÏ&fº_ZAwÒ¬lð•«Y§†úrÉ÷l—Þô{QßGï{}žèÊ@}Œ¹$p
+eØöcðp–¿ãyZooÛ¤U¥¾!
+µÛýŸíj[¹ô(¢O0ï°o„äFº»úxDPÄ€ˆÄ?A”$^ˆ†¼½«j­ê=f6aÈžšîþª««Ö¡m¶(.FÒq–àBÄÃ/Ñ>«‚yª§ª¥(‘&U$ˆBK0¹®âDxÁÜrK™œµdn†Ý`+B­1/ÖïkSaòzæžÎï¿OÊM´ž._w÷©êžƒa;s<~Z¨HõeõÞ_5ùÍk+Nö‚Ís%>ª$}kS<„Ú5r?(­Í¼ð(”D˜1«Àhdj‡òqw?»«¹àü¯¹µ.[{…>¶›dìªýôz½Õ¥ÞÄŠ†÷šC±¹Çx¼¼ìûë<åâ˜CUØ.¾S3„b Â>Ù7mB+õÄ:`ÄáÁðªÀüKÜKž/ŸÀŠŸ¤!&«‚UoÇìÆüÚ­	m!]uÀ¼‚Õ+Îv†-‹wJìI†ð9Skçê‘3åi>)ÁûëÊdÉžÆï~M	.ÒiÇÓ/¡)'×‚4\Ép(G_Á/j–7ñKèx†å`.à9=æl\¯$Ô!ð˜ôBñÑ/ÔáÆ c`O#Ã×§fFÛ”¥ùEx÷®ðª„Å¸j€‚_uªàŸÜÿýuYT¯Š|N—Øjû˜úÖHèy‹l†‰(t[¢-=ç¼â§Ða%ëXÃöÎ‚ÉõÚ![*xjcz¡ß‚ž½¸9ë@ÁI±àçUÍÁ ¡Ð±ïº˜ébÆÎcp#È…óË~R‚÷×•É’92LgÃÖªd5YÊ»I
+*p[|°;0kª0¿Æ¸ñÓöúP±L@Æ þdqJZ£óýOŠè‰Ñó­»¡ïˆ×û­B(ÿc|È2’½Gd×µ[¨*>t«5¢ÉPÂn,Á&¬—"©Ô]jÓÊèbÖj’ø>-àûëºæL¯ÄGœÜÎåˆ2÷Ê¡Z6sªÄ
+ûfnÚ"o‘}ãFmî°<ÊññiS+S2"xª„B¿åš?”t{Tï‚ÎÞóÁ–g‰öäTOŸ(ŒÊV»ð3mJó¦pw2lêúÕZBÒVkD´¤WT"h°—å{]ÕXG×"ÝDPF9¸„5¬â[ß«nª!òMÏ»g$á£ÊjÊ‡Ô-w+]—v¹õ^”Võ9J-mrEËŒ«Wœ"æ)	öœQbWð¶*ç1Òyü´ï/ë’õ²{®qâôó!¾‹]€ãí…#$ãª3Ž’ºøéÁ’2:7»i)5JºQtUÈµ'_L«’ÖÅ¯ »Å„0¿{$¿V’Øð²¯[*aIDGV×¯Üløòòï¯kâÅúã‡óøìóÇ—ú¿_?ûâ×µüõ—ßý‡¿ûÛ¿¾ÕßñÍßÿñ½"ŸýêÛ¯¾ûæßŸ(/ðçË>ü'þ+ß}À˜TÜ¯øˆòà•ò¨—} a,ÿ
+á@¿ý¿/ÄßƒÿÄªýñÛÇŸÿR_ûÉ¿±rvSgº¯¥ÀE6å	¾²d70„3êŠ’+%Ö]J ;ÔÉ Pgh!Ì–ª:‰_ŸµÊ+„á`zÙuÔcmëÐ±×Q°¯ÐõÐ
+@„Ã'µ‘zÖÝV¥YA0‡)í[~jM{&Pá“Ô>`¥ Ó‡å~ÓÛã›0M7•Ê­É™×®Ílÿ¥4”í,O_é÷Ÿ]¨imk-ÄŠÑ™y;À Æ,÷/Wçñ¬×/ºfHo™ŠÀ]è´xjãøð€–ê¿ßù†\¶œ‚E;E‘t¿À›Lh¡ríª3Wß\ÍµÛµa-®Š&¸X	”,Œç%¸Epö!‘²åŠñFÊU¸Ò‹P†º}Ó)ùþ¶4øew¿­¥ÂESÛî¾5]Ä ˆ/+µéS÷Ã£Þœ-9k[°ãð•ÖôÇd€‘‹zØèÎiâá™kÕJâ÷„"à<	?jt:eßës°Ò¡ðÌÉ^‡#kµ|dÔÈÄÓ®l®‹‚—Þ7	›] Êcýöîf\»uëÈ°?
+ú+¨g¿g~*2\æÌëÃ*uæRA¡]Ýù\fùk_Œ^Ä·ZÓÒª'ÁÜï€…Xx%½„:‚}êòø÷Æ™,!ikËê•§Í…Ê²¼*ú*å¿Q5zQaÉ?UU¿e÷ú3x]Ö>÷[q&¦§À ¬lEL
+1éÛH•äêdAý°O4Ê—šÁÃîYtko@FU¥9¨ÊPø~ÉM×{-D ØkÜï½Vç©/Š+…Ë`À®?ËéwÿêG½»8æ®1Fö^oõ$%«Ï%P“7Q²¥ª¦ßD°Læß|W^Jð‡`{Ü•¼°\Ÿ«ÖX[ƒð¨‰>à8Ôîþ³"´Åhš^@it
+*½÷RN§†~ôž²kaQÕUÔ¨wRjvô¸èßœž×=žr=1¢³J/c>×TÐÄª¾r‡gBžfI îïø€Óa W}¿—¨5‚aµr
+evkv@3
+¡–Ÿº+çaEª+é<qì}]c£!©xseª–®??ci»!½¨WïMû(]K…Ju©z¼¡á·Ãòã™¶]¯4NÉT%´}iÙ*?Ä–)©ÆùlŒ§z×÷Ò½”|üE¥?[Ó›”C„œ¯ø.©É…ÎÊòå¡Ž¨B\…5müþ›òOêøtºS?´¤Ì[ãW¯#pìÜýv¯í}UÜ¦I@¨”'¤è¥†ÁÊîG§TÊ'<€+S&Ðì˜‚Ž9Îˆì>c}ä’'$cÜ
+l“~‚èÊ ?¥U>j¡5Óˆü<¦²º€«Ù§¦Ò•-”¦ ƒ¥PWÈ¯É`=[hœ&ûÑ\sÝZmg²[K×¡‚tùÓ3x8+¨ Z÷F¬ñÊJ©øÚ6UBÄr†¥,$Îÿd¿ë˜ìV(5_	WzJ¿Áê	AØ¾/ Ýn·ž%ÝjTê M¥~8Q?ÄÎÌíu$­`{¯%ÝßéL9	•q@“u¬lv bÁ¸iT_þ±r0d¬S»©­v÷Éµ³åþ}›er„ýCJÊ•öÌú;ž†|rR;÷Ÿ/yÊÕ¯£µÉQÀìîUËÐÖ¢—r+9RPŽž¦–û1Ö§»õÛ‡À*Û‹­æúÿmnJõÂÊ`ÅØ¿¨O5)í¡ÍÒs8±&þBqŸàT|=lw×«“ü©¦zubM9'¦§œ«Òº«e&¨•¥œ&y±¶›† r*@ýY–Øcv]¾ u™)z§Wî‡O£7]o~}\’ÝáBß´ûœÔ“*Åcºü¸r¬,aÄ
+~|’]Í}*¾4dÝð¥F9[žÝa¶½ËI;Îƒ%%t´¼þxú©úDßB˜|Ïê;?ÅDnËâo2]—HçÂz’»Óü˜wgY0’hº¦ #¼Ÿû$2(ðò {ÛT†§óp§¨ä©Vãý4ÓJÊ$ÑH9<%•r×» .{#´‡)hzÇLï†Æ þó*mÄ¨Ö-aq}8såv{`¢Ží{ë€j¡ŠÕ¶u²)ÿ,cÏ›@·¥
+l5«ž¨ŠSEbæ´é£”ÞáYCëumêv€®Åü÷âZ¢©¬…£Öù†1@†“R¯URÏ\¨3{¼”l‚¹€rktƒ§o£LµzÐ‚ )D‹2!ô´ŽÀ$ÖÔ0ª‡òØtÚÂ‚îÔTÁ'ˆ… Lê°Æì1þFìr8¢¢–2S|gú
+ò ÌuLŒ0_Úm^ ¢KvÔ€rÿ£»jVÅ¼èøî¦@I¤Ñ»jœMè¦.²+&qCëãß>gæœÑw)c|=Wú4ÍœâG±¿A=÷ƒ„£ú­“9µCüˆß ÂíK0‹è1ªÏæš‰ŸK¾^Ì²L¸ wûƒ—™5•ÉCP*Ã×Nz—n÷xÿfQùÐ]$­í‡4ã3Gæ‹¤)i„ÕÖ.j¾ÞÉN‘Aó¢1X©]p•*>G°Äœ#,’	„àˆî3i‡ÞîG1Ç…òÙƒ0”¢õÄÿî¬B\Â«—vò,^$¯ý(è’>Ó‡œ?©¥—ö“¨ðS †‚”´þñË½&út»Žo{
+©å/~œ!©1ûï®ýh0zÒîýÏó½›dNYý–oÅ˜cKž?ˆžûº‡Œ}„é©ˆý¦änàÿpJÍÈÓöªghZ
+aÅ;v¥SáIÜ>]ûƒžœ£‰•º‘@ú£}Æ#ýÖÔn®“[u ³F9† ‚c:ï~ˆëÉð9t:ÃO€¯Cñ‚K-´ÅÓèCâÛï5‚«ÜªÌs´vgÌªeLø“Ú¥ðxá¼@] ¬­‡Bôsj>+1Õµ{ÏþY×g4´Õ¼í[ÃBzšú×<i{æ¯fÑ ~<šEûÙÃ¯:g×ñ³/Ê,Ì`»çŠ(µ]zŽdR?UËž¶”D@?)œ¡ü¢Skãî^j¦Ô)q§7W÷z«S~@ÓuÑÔ­>R:{döÝý
+T¹ó‹BÇPºNÍ{ûÓ¼º£k«|=9õÊ·Zè'„É¼'µgËæñíSù)> iFM<åŸ¤ñrí‹O)(ŽžžÝ±{¼¬þ™;? >•œ>Òd<åÖïŽ·«ÖEâ92à›”AùÛ½Áw»‡à9Cƒ¼®Lš¨ß$ú¶k1Ü–ðÓVÒT…L9ó²êP3é¬*÷ ÄËÄSD½
+»
+é÷œÉåL>˜k.~ø_S½!¼VøÄé–’oÐ(Ñ#VÝfñZ4ûuû£ŒÅr|QV"jøçŸT“pòþ'«? ç±>~}¤¬4W]j•nÉ^Îokõl–¶EõÅ¦:plª/çÿ’­°8÷sVb¬ã»zÖ6]6—GÁûMµú¾/Þ˜ÜžÍ‚ûoµµSe5ñyãùÓæg½ß2z£®©ç;DzoàÚª‚6Ò¦í3îöZéH™ìÉäó€5c½±üÚŠ™Ç]k;Ù9eoù¬«Æfz/]ûž=È¨wé\ÌÇ¯~nç•c7ÏüŸoþðoÿòéó÷~þüá¿ß}úòò'„¾úþë—oüüéÃÇ½|õã¯ï~{ÿÝ¿ßüåoï>ÿú~õG_ò×ÿ»äï_~{ÏEÆß7Å©¼à­:^ œË
+êåÿóZ—(©;GtÀOïÞü¼~‰??}H7UNhp{ùFÿ¬0‰Þ¥tÁ\¶3 ¯ˆŽíâAu­küÅt‡¡à)¬ËÐŽ”.v)Ò{pŽçá»…¢­êÜN“ú¨!tx¯bø	»q¿lQtˆ}Æ@ƒŸl¥äþ±‹N‡Õw¿	áp“ú(©Á†Óàçë¸S™I]>OyÓWÐ	§ö©{Üà"õ …ad^¾&ï´“KÏQ÷BŠXn¿$-ÜîöA/7]“%\n¶¿ÛÓ4¹Ãº‚s½j OçèUÍO³œÇUrt+åœƒdK%tKQcmÊLÿÀàµÀØk& t5`4ÊEŽ32UåžºÓ‘ëÅˆ…‰[2I¨UxÙDž¢V•št4/z½ðrI§œÅó¯<êÊ¦ÝGÆºµ–²Ñîéò·Þi½&ëÌEÝê²S¾?Ö®/á«T¼“íý+âvæ¸ÊtèmÅàXÍî¶mÅJ :+D
+¾ÙwÍ’ˆ <çnŸI'>“g´‹Ñ3ÕÐìÿc\½¦ ~¥h^‘<”­ñQËÓ6>`!ç¤}<ƒÑsíSW‡æÌ IŠÈí§°V›nQA"½{X»-YµrL{¨gÐŽ ÚLæ	Êd´sgbÍ"PêÞ•¹öTÞ©ñ½‚;tÖpÂ¢xô"‚ ¿{ƒVîÚœö‘~Ð½·÷Dj„&Ê÷V»ÅœžUâGOíŠO‚"26{ž¾jž,8&;sÌà¶*ãvÓïYðG«9ýŽ%Üpi\Ú«àfú‘ðhH€ù©Ú•>@³Æë÷ç\ñ«°ƒ8@AÉìhõz÷¦@.±¹7‘ŠÍ…¥,$îÃ‰ Á0GÓR£lÄï¾3öH¬ÕóþÀr‰´z=¢/•&)þhKÁ^5}Œ<¾JŽbPL0		¦y8C²Ÿ¡ïpò*ùv%Qá.½„V³÷KrW@ÒÍïsn«æÚi*h$t‹Òk?”ÔDJ•Ý‡à,AI_Å2ØØ=®Ñ&Q=s¤mB%HäL Ý^¤œL`î«Ž[½vÎõS–KOß’4‰(8?<Ù'}#¢à‰õ"‰ÏÇ÷üÇZä9@ÓR0µô
+¹õVûM&è inŒ1`ùÌÕ‡ëÞÒÆ=?}²š=÷ïr$¦(ˆ}Eî~Ê58I~`^ÞøÞº‚Á9fseÚ^ºI’`
+™ÎœsT(ˆdSLØ‰ôËÌþ±™mÔßrmÕœÌÛÀMƒ°Ðt7ÑÕBì!ÏN/'ÁÇŠ®“Øo`	B¬`4…;ž4º¦ÑŒäåAÛ~<\'¨­ëùPßSkAï[kõ¦þNFC0Wº|èûÉ@2ýôxap‰>]	PS¼
+BÜ4{>°îÃÛ|A÷P¥©M÷òÂ}àÕÖ9AÓõ«_wß`ÍX³`Kü÷ÛZÍf'Òyl§ú;­f	[’yc•v÷-Ð.k˜R­rOýy‚'´ðNú÷ÂvŠJ ñ ˜Ý¾¼•Ã÷‹|g²·u+©bÖ¢_GÙé'ƒÔô^é-ùˆhµ¢ýKVÃ—öœJÕuüÔÊÎn|{!…)"øGUU ×ò	KVoþ(¼†–+Á>%ºuzzK±Õ”ç¸æQÀ|Sõ³vm¦Jïe6í®cjü*¥’¯‰*xûXWÒŒŒkf{nø@/Â=‚Þ&•Œà8]0ódÞû¼d¸žÔg­)2‰É—Êràó5ß^ÐmW
+o<‘Ä¤¼lƒùIÄ†²ìo£=Ç?$%Š÷à£Üó|·RÈ!ûÞêú¥‘‘Ðò¦vmëª=·'õrl>¼ ²§'tÞn„DÂÜeãqêpV½éãVõ›­¶/YQí/²;zW?·‡;Œ+¸©‹sï|QkJÁŠäõò¯dcGSP^A™‰1"ÓØ_AÇ3ˆw„¯ˆ\D{i©:ªºÛÊcú¸»›p$µÙ¦ˆY;Ò§Pô7¨/‰fè \wWQÒÞúGI2®O)Åƒ¦V¬¥çDt.Þl²H»‘SSñK¿É›µûÙ?ûÔýÕÉ1«…î ­ßFË±Í`÷ùæ£ôsJ…«áóu(€J$­î*#¬¬®¥˜Á”¾E4M[ÅxÜÔˆ¥çñÑ8Y?„IÃÕÒƒ“¨€¸AiÏ´s?°	RÞÕ³ÜÃÖVYO¯÷«««)Ñ íÉ`•¡‡mt˜~Y²1º%\+IpÞfÏ®ÍQ­3¥C8¬}¤kpøØgÜíei^å?MTÊ-`º¨:‡¤¬¿y‰ÔöàcWô­‘5PÀF.ª¿s]-9‚å6ìs‡9A`KòoÝ—˜m0@v9@nÊ"ýªFW³žmY–Dƒn’öü…Ð^C-Y3J¤õdÀNìÔñ)ÙuD´ðå¤ìÌ§*‰ãc9gïn'(šRÿµoîÆ[­(×»ê'½t)AÐÚ¡ìéM”rT˜j†h·œ\;¥a©/´`7	RüpsÕöîµ³ÄÀ¶&Áá8ê7hdªFU­í‡ÊÆùÂŽ/¥ªû»@/úHÛG×ÙóÞÁ€nƒ C+úÛQ&°÷­ocÔ°ÿXwmP'Y-Öz°„P˜ž–ŽÁÖ¢‚¥¦ð%ˆÚªFH='\*'‡(É.ïÅÉO~çÃì9ª¡ &‹ Kzfo÷r(-5Eðà,ÌÔÜEk™6¹Àî÷b9Å‚ƒ,Î+‹¦"Úø}M¶ë²t>jwüÛú›HÀÙœ³§s4¢ì`íÚ§XO§f­“ÁÆü­µü¼È":ýmpöm¯@ïÒ?åaó£Þ€:Þ~ÿ›7h~ÉÛ^#XÙ!ò¬Xë•VÍ»H£ºüµÇ ‚•RØ×e\|»O•Ú`ÌË¤	foT ÎÊ6vÌåvÍ¡»i}˜”)
+U÷©OÙqaÏUÝõv3€²Á¿>.&”yÌ¥6¸Û³œ»²êsZPFýe¾ÌwÙ*V&ÅÞ}
+Ûû2ÀxB('aÍÏ‘ÏŽ*çBLWÁ
+õÃ/ÑŠû'1àî$”^»çXeKb ¼Ý?-‚6;{œ)ÑTï
+ð6$õ½ù)HÝâ˜3ž…8£xýB)I(Õ 8ûÐ’Œ*_	—ò1hãY¨×{w‰‰uËÃÖŒ+’K[·‰õ”	"ÑtUP5×/àÙÊnâ9É\™n/…‹‰-ð¨¨[Y Ç¨99|¶@« "k sùµ,µÂbw½l/2GéSdP£æÀµ';×ßŠ,—QàY%esù¬bƒ„¼ZwëOI ¶ÒRYÁóètvË­ö¶Åîo=êÍªƒÌl½³ÌÔ"S9‘èw4k}T¥dcF‘@ÊäÌNÑk¸j
+àÍ^úÎ¸—ÅO(ªõ.Ð9äîî8Ñ`±7r¢qcà±_3ÕœV™GUcbÜJý{ÀvÍDÎñ(5é ®È™Ï)–ÁT²N³þåð„ë@è
+l7|»‡Õ#ê¾ûac R4`‰€cÞºH&T	â†i‚ŠJ=â¥€åšÞƒýžuUÕžàW‚»/ZÇeßfÅ¦ôUü¥†ÒbE9Ì|Øy(qïS	»w.Ÿ¦zULÙ­{2»u*8—ï¤Qð³ÞP”ã¹ªé]{IO€Òï%`Ðè@F¦‰¬~…»"ˆI[7 •ºQ`\‘^4Ü4„Y§W»á²ÇËgeTÌÀÎ¹÷ò7ŠàgêµrX^‘Ú·ObÔ3ïòèþ€”2uªÚÈNŽ÷ögÇŽôáÇ¿þýG»¿ÈÿäŸ¿þÇ°Yyƒè¿„[o„f‚t“;‡“ÀNm¶®k{Ù8CÚ‘CW<Áx´ÀÑ'ã•¬o=ëa¾ùƒ±ã{3ÅØÎ9" çE±£ ‡-jN?sh¦wãaVõ lµàIã-žÞY¤ü"è#[«­¤B:¶ÕÏÛ Ÿ4gîÕ$™‘]ŒœØ(ºJ<h5)ðž<©M&ß©–óœ½(Í‡4fþf¤¸pœ:Š{ñ¢(»C0Ö »º,U€'1:þ¤il"Ï(ðÚ«Mlø-`PŠQÝœ°Ý%¼ÌÒúÉ-õ˜Verj,Õñ“>2kÏwg¤£”j:N8€P.l¥;!t£/ ³CóÛ†®à£ØÑÓ_êæ\¬ÉÁƒþüô°—¡_W«¨PÈ\Ÿ$=¿€šç4mm~ë}ðÛÛs”ÖxTKžüÅ¦Õ4G>ù¬W%¥3ŠyˆéVQBV˜å K}¤>ì´nzÚdÉš]Í5M—ÕcQÀr__÷ß ´žî4[=XÁ`çhÂ%ÆîEG®W€I2Ìß™G‘j$!×ûŒœËK§›s58)ø¡½7íiK·êsüzËU¥àbÿ[ÓT™Ò¹®:	Â %Ü·¾^”W±’QÌyy'>ÀÔ°ºþêN6ÆF%Ìw6Á˜zhÌ‡Îú‰÷~É·S’X3aº	[GeÒZ2apZ`ƒ¶z1ûx`åÐª,D¡X’†ú}ö
+ËGz²t5l“mEZßÉÓÒT	®Ã¾ [¦!ZRË­©O#W`yH|xgYšì.À\UØJèæÃvƒ:šâ”)Þ±êpßí+=Ç”Õ§«óKZ
+@c†–Sgæ9¾5B Bzç·R„þIœa%Túj××Býé‘íúóÛÀiMlg³¯·ôéÒ,[áí_oÞÑ[Ø<ÆÖ’õžº_M¨jmr 9ƒE±&Kø(}–\?tºÚ¥½úI¾¯¬‚ó§Ÿïþ$2í. ¥mšÊÉ`Íåi6HCL…_&VL›zç$š£6^ô×sÜO™&`Iš­ÆßÅîøÍc’(uúX´ºñxü–.w¶²oæSKgT«}žVÉ”R ¼äÁÓÂéòcP*,+3 ÂÇÇ(›f|bÓÓÝºÔ[Ž/çõc™¨½—À¸aÎìöoýñ;jÏÒžÀØ¥Àö^3ÙOômó}‹ùŠ²ºß¢ŒúmÓ™Pà®*›Yú(“z¾gf²JÕ™‰€²¤–&æš¼™#7Ö‹ ¹*Z	“ª FýöAV¦ãÅ?U§»|NGŒÌôÕ<ý¸ªo` ÿâúÆªÂ¼ò¡ö•Z·"›½+iK>Ä=@ïž¥çöÚG#B«ŸµÞúÝªqQ°ø‘z?rófE')S-Þí;µÏN¯×#Îà”Îœ€›üÈ¥“Ú /ÁqÛµµKE<£},»Ë3jùúÂÂµJ¢.¢0z'w%?žÍ/uÒðàñ×ñCN¨ý3 ì®oms{èRáƒà¤žCüÓõ€þævÎ¦²N ©þóõª&I›O}ðë÷²©)ñmZÝ²§j?{šü|ÖÏ’Ú;Ówrø©íÍËÞN-ps8Î[›oƒ9¯º© $ÖÈé$ÍÞT–ýQ}7É÷8“ëûzG?1^ ‘§„²¦§½wý)ÀÞFac«ú¿˜#½ÜÀ…^.–“&Ìå´xŸ-ÿ—G±°5Â^G²v˜tÖ{ü¥ÊJEÿ7˜½ª§Ž²òÛUí©LLQIÏ¤J[ñ6è«3.ø}ÛO“$\œªíñ²ÞJÁ'uZ‹’4‰R¥œA0øM(Ûhs}k´‹xMº"€B	9„Ò«ú3ÝÀj„Ü”?}Lþ²mšƒ=5‚nÖV±ÐÝ ìz'–@h1/p=‡À»ÃJVq×U
+Osº6MCr1ß/ ‹ÌóÚ³;xNµÀYâ5R‹ë|Öfòu|ìI_ZççHü‡ñxxúÉ‹Ý?•AI½Žw+ýs5Ø5†.z˜•¾«ã´`½Y¼å&WqEù[ï\>§¾´¨É†'iH¡çC-½å=øéy‡Û
+ÖT¬ê \óœÉÐ’wûùÆæíÿ©®’#InhÁú0(‚Àã=NìWýd€¼W&`ÏÆ>v"»Èb@CÏÑ ¬Ú`t/÷|?ÕÃYn¢GIƒ›ê¢6f)3	×?ÿ¿­ÞÑV©ØÊêþò¤ez¾ó±ž«³%<ž‰ 5]=[#LSœ¦œ`;zrÑ¢~k7m;Fº i‚Mum*_„¸Ì¹~¦P%\7jip½$¼«)p ’ÀM‚×JÖ%óÏ"Ç¦Šõ—ihcÜªÿ@mý¬2<ù¦Vg‚1‚¿û¶™à`~ÊóS'ånŽü*ö´vuÒó9~S~eQzÇŸÖKš²b^–Š¦^àõ@W«žo¬WŠS‚ã&ù‡€æ3öèË6Þz³%Åy—5_·ÎO[PF3QåÝß5ê×V½iH„pÞL`‘=¯jøk ‹m7íºõ\qUCî«óß­'ñS€ 0£ËÁæ\T,$˜ŽàFë €­`_^Å^;>ËhDN²| Cïê
+oú ÛAFªêÙ¬ªQò–maþc„§ÌìsS£ÔÎè¬ìiN	BN_×ú##	T|Vöb¾©¿DžÍV‰¤(²å»²|½ìæ‰…·Žò5Ú÷0†›ôÙµ¾e256Ý8Œ	°‘>»Ð¶„ËFq×Ñ¢þœÛ]ØÉúáÌˆ9o}O;Él»¦5c°¦€ìtœó$WÕõ4I¼¯ØëÆýƒì?ÛzâR½|šI†…OR»bØÔ?«¦˜1î•xZùéÉ,©B;õ
+`»^¶àŒ01“lj÷I¸BàµŸÜ¯° “‰Sñ¤'WNz¨ÙŸ‹ÛÞÅ¸—aµ¸)`¡Õ¥‹ÖŸŠšéåPˆô{7“Z€¸ˆèÊù):•ÈøÚ€0«BÐa®ÖÏ¼S½g¸bIzÝomŸ*ç‚à-Ëpï+´XàÝGõG‡Aæu­íD¯ AÞ³°Ôôr˜T‚Z:«Èž_DõnÓêæÓ~r¶vp¿b©ˆ ¡ÒòÑÈ~Ñz£§"Ì°Ÿ[ä¸¾ŒÔ²õ¶P€¸Ð:€çDN2â[îÓäÇŽK“¶óz{éA	G[ý-ß©H5®½¸‹º–Ÿ8N”à!]×Ê€¨w%n¹ «]% o+î@ý`Ï·ÈgÌªø\ŒVõƒ»·"´WvêI~Ì`i_ ¦'u÷“½k³Œš±ßí³”hIýÍR'ù®•»ž¥áù2hÜþÜ_^•Ñõ[çGG§Î­±´|#Gþãþ'¯ÃShÛÜ½ÚtUx@X«†¾]:û9×CÑ’9 éíäœýúíGàtùìKSü­õÞŽ,+¨ØøáÞ­e5šþ£\ÚÆoöÊéa
+ïÊà$º0o»Þ_FU–âS€!£0Fª?Ö÷ÙUÀ¸ìþ
+ü¹â[_y—ÇNÏòÐ‹ìV±DªÜ|Ô~lahÊnúO‰Ü£HªÀ~Ã?†G«|ÿúçWcTð/D/ÿ]ìþÕ¾:þt0þüý÷¯Æ|óþûý_ü¼ŒÇŽÆ}ý+¸QÞæQÐùI/œâ“òc“}ŠN(	Î~vëQø[Å¤Íd§åÜi!÷|tæ"àÑóö Î5Ô>&“FeíÕgk©¨p§õ¼©	ÞähìÚ´ EB¼jÔPÇg
+^iI°!HÄfRU¨x7Á3Ç[Ç¢¯…÷(ñÑP†#NA ˆVHðãˆ	·rÏhZ¯gûÐ³÷x@éU¢Ö÷Ý•@GÓ"`ú<jÊv–@{ÜCÄLõLMv)}ê,®S»*hPq[­?eéB³·Z«„àzï'ijýU³ÁÛUý ”™Wendstreamendobj122 1 obj<< /Private 123 1 R /LastModified (D:20051017164319-04'00')>> endobj123 1 obj<< /CreatorVersion 10 /ContainerVersion 9 /RoundtripVersion 10 /AIMetaData 6 1 R /AIPrivateData1 38 1 R /AIPrivateData2 59 1 R /AIPrivateData3 64 1 R /AIPrivateData4 77 1 R /AIPrivateData5 89 1 R /AIPrivateData6 95 1 R /AIPrivateData7 108 1 R /AIPrivateData8 120 1 R /AIPrivateData9 128 0 R /AIPrivateData10 130 0 R /AIPrivateData11 132 0 R /AIPrivateData12 134 0 R /AIPrivateData13 136 0 R /NumBlock 13 >> endobj127 0 obj18366 endobj128 0 obj<< /Filter [ /FlateDecode ] /Length 129 0 R >> stream
+H‰dWÛ±e«ŒÀ9LÞ…žÀ÷ÅùçàµXSöÏ©}ºXB/Z­Ÿøü³4ì·†Î?ÿ^bñó±	¦­#Œ ¹­?ÿùWÁs¹X+·ð¬ºo¾W#ÓŸÔí–ßö4ž×ö ¸,
+›¹ã}¿ö$œÓîX…ùžåTþA[ºþüó¯‚eðs•µxT–ç‰¶O»ï÷ïþÈvUc®—€2 ˆºc{eûTÖ÷þÛ#:-Á
+øoÍ,Ì“1ù/Q§f¾ïcwæž›gý”¨h´×±	ÊP& ðs@O-	N£2G[­@áèÒïúhWGììƒ3èÓ°%ní@e~þO•ÉRgôõË_®lÁ9†vUõó }ëº­=ð4 s¶Ó¶jò*è?QÐb9Ž¹i4¦•WöÛ)<9=„	¼äfµñœR­;€}e_û€ýæÔÝlçÑ¹ƒ žjLbcÇ|÷çîïE¢}½¹¨vi£æNOÿ*áŸõºu—¯úÛk²Ýpä9YÃ)h‹2 8RŠ«:ðTò¨(U‰%ã}ƒïaý5Þê½ÕÅ‹*PÉdü§G¬#¥ÏJ]¡e³ŠØP_í `Ó¤`#ž]:éÖÚlÔ})ƒZ6÷30­žÆ©¥¿³Ñ èª=˜R	¨ë3.ôà¶v¾„(A3fÐò½ÂÓ#Òä<|ò(˜ŒÎÊç@× kçpüÂž:ÚÀ°*ëáž—CÑJV ±àëÏƒ/\ÑBV¯	b½®æÏã=‚ª`M.“G]ç`¢Æ±	
+É}V
+:•µ	cà£éüüL‚œcùÛúæ`)ÅýMã¸j¶SM}ÿèƒ&ÝCºkx]¸“pÆjpEkêÈoèje5÷¨%¤½* .>m„µ7_1à¹ô˜<x›ñbKÅ”JßBt?àÌzDÂ³p„ H¶}Ò³@Œ.6€Îz¼€w½ÝÝŠ²7Jµ@ÄÏ“Å€Ê–]hŒª5@ÝUÁ¤hM/ÖŽxôÓ‚Û£Xì€sw´‘ö?à„d˜ó30»ZÃJ5 ªÁ
+P\X•p¥#pf ¿l!Ø±³ÀÈt³Öêú }ñ.ÑN–2*¼+Mý?0õó_µ’ù1:Nf\;ûr[A<dÿ>¦º5vöàòT²ÕsOA¢)0È`zšÖ	oÎ£¶vë³iQCA1~ß[ó=©˜r0ú› Çž<så~>¨8pÔF{
+•Ó1Í’!
+&Ê`L{e(à™NW——Ž˜c<ÿ³ø"ÒC¨,eª“µ‹>~>JT‚"ÖÁú p–4¼dÀ¾YÑZŒ&`_ B´Á¼,•l¸-L@tGŸúúËªqœ£œ6kjß5Lµ3XÚð€Tœø&Bž=¾y÷—³LS„^Í7Z1©»tHyº9î€¡57;ð"ÐóMÕÝõÇ¸ÏÅsl?AïVÌÙ`õ9~ìW>}œt,¹ð¨G«ø-ì”HŠ2 glÎ3WìGqæþžR„i%º˜mÊkŸ+x¶_%DÒbúäM0ä˜è<iÛh à˜½žÍÙØ“;öß÷Ý˜øž;ÀéƒwÍÅ€	¾’^¥=‡†`iàlD_Ã:¬\mÕyFugpü½‡ÌZøvÚ ðú+a¾ï[÷Ò¦Gµ1Ö€6*Ùz]‡¼ï%ú{¨Ù¾JŸ6ïMò€ì_)aö˜ô‚éyã³hP}(Amo»UÂ‰-Tl-ë¯õP!6Y ÓÞzàÈn–b‹‹‚ä¥ƒ¹±Ù3¿ëçîò­Ù·Ïá-ì¹L32¨žœö÷ÁI‰§ºK
+ÅDÑê~1}¼Žúø•¨P1¡Ý¨Aã4kƒCz®Ž °ÍIfÄ{ë³ÜŽû"x•#I¸e¸@Šp°Y‚	`«HL>+a&ùäê¶ÀŸÙÕŠ³ÕqÚO¯7tÀ§.7ýÓH9˜½Ky4ö ®0j»kÔ©Fö#$‰»ÐQœ¬"ÛƒÎb¶ÞG öv1Œþ#+{"rˆ3 ˜QEAr]ð°„·Þ:n8‹¡QÍY¢[ÎÛoÑ¹¶·nƒñm¤ÀÉÍâÅ§µ¤W„ìc*–VÚä`¶BXûl¬Åž3®s'³%X.üÕp±7ì1š@ØZö!À3Z	Ë©ÜâóÆ;už­²Ž§"tÛÂ7˜·EàùºÖÀw{*ð%@¼)m÷xd6ÿÚ%·äEPÅ8øþ=JéÆðS¡H5_À¯ß­0W	y€T’~J­í ÎÖ 5‡V}}îê¸».¿Çt´ç@-ˆ',*ÉãÔÕþ©p`sU¦ éb}_×pò£™ÞQj÷·ˆž¶òÉñ†{;ý—<
+÷´û·ö€0´	Jñ %Ûí#=F>gÔ÷˜WÅ áû‘W'x7ŒBðØWsûi*– •QÈM
+ÀÏ»8–ÌfÁÑë¡ã€î>;«þ2c±U›¬aOõÇa€óJ!CUÛU›—U ]Úá¸ïÔ¼ê‰t—+Ã´¥Ë7*vºó•?K2[üÍ¡GôN+X´Û7k´š§'ûák‰1ÿ¦ÀZ#*áÄå* P1%ž8(hÌü¦x†ñªQóú(®¼ŠÃ xm´Ž»î‚+§>%)yàfû+Z³°äs~‡µÍ³“,¢Q"ØFÓïqâñ‚VkB…9ƒÕ?ÿÔv‚_qrÏbªèj{*asÓÀ„z¦“¾Ž¿Ö ´gîýh$†EÒëktbg%cõü½ž2¨Ûô6yžGã+¦x½ŒQoÏ›’à:³ô¾Ÿóê#Ùé9©—ìÀdG€&s°|€Ñ³à°R<,er£ÂJÈG¡Ù8p)ÀÉ~·/Ø»Í99Sêý™uÿ¸h	ð5ê ær>ê–þÀ<z§ø¼ŠŸ¾e¼» zA$£n#âHõ"¨{çQƒ4¥¶ƒÃfËŠÁ®0éÂC)xÎÕ=°×•‡Agõ°sQ¹`v´„üMq10@¶å­Ð’³Áo‚xÔ\‚6Òì»ìª8LÕšJ‡7ssªdô5±©¶µ&ÏÊiÝ‹GÓÞâ[aÀCÁ5Á;V›À}0ÄÜjœºq„l88Aý-X€_ŽÚJ
+,
+æah¡ÿÒ]5»zEð	òß)‘P23=¿°‚ˆRXd‡¬‹!–°‰,oüöTwWÍ’ Ëº¾å9çÌôt×Ï¬v¿ßÂtûçÕ‚%Ë`«këùôp¾²ÈHûVköCÁO7žµ§‡ È)öMùŒ&‰ õ3aùÇ‹äey¼YSÏ÷r˜/{)Q‡—1¢vKÂK{ŸôuÆÁ07¤™EcœœþùEÁµcÿ%##dÉ?J±ó¨×BhXy|ÿæ‹â¿ÇŸï?oe;¿¦"OX·cxâH°dû;A¦Qj ™:¿’Ö´òèFhË›3ª$Ì‡¿Ñ(FÉçqàŒ@iÉ  uÅ}Œr™B3Ò(øÊ²Ÿ¢T²r5¯9õkÁ¼G+¥kqL`ñ¡èG 
++X:»žÇ€smH>ÁYV‚VæÐ»+Îïkå?JUÛƒyu³±éÉËÓÓxÂ %+É«®ÛèT–ž`Ì¢¼9Ähžáff¸~)F#ÁÓ¢µ}±0 ×°scÜ¿ž/Ù»)nàmEž$	\@oÏ\ZSêqúÈ‡y$êäMa0eSÀœ+û$4-_ Fûz2Æ,>¦ú­^H}Ð¡ó|ÁÊVÏL€'%Obz¬É7²âÀ¶†ÿZÜÀ5j‘?†ŠZG¥ù_ëæRð³¾ÖJ:Èâ”‘4Q†ÑVÚ‘XûNd
+¹-÷EË6K˜›OilÀm“`ÛM€Ø2j¥Ñ	O£S»\CSÂí£j’´Ú˜Ü¿’\Å–8þ¹³ÎõÔK‡½•Ã[!÷û÷9¨ Y²šŽÖyóN¯ûàSÙ*£’ø0	Ù}Þ6Ýß´ðä¸’>Îící“~æLKlÐ1Ù¬p,FJ[gqþ‚T^Hk&ÝŽ e»ÂHü}¾‚Žó÷oþðñÓ·ï^?½ûÏ‡7??~èË?}õøæ»Oß}ø×ãËï~xóãÛ?þûí‡üõÍ§þüíWßú’¿üß%ûüãÛ\ô{üuÂG;€Ù+ÒÁÃå†®8ócü÷
+?€ÿEÕõ³ü4…žR}ûAôq1Â®r…e$Ø?q+’¾÷¹{¡?t_Ë¹H÷²ÊæµÐ½…m_|þIÕÞß»ÐR\´&ó°¹ç!YÔ5tÙÎ°“M„¾èŒ0ˆ¼¬µ3•6WôMoNë/œî péwiVÀÅæpÖŽ"Œ÷ð™ç>?ŠÉé´z¸VUµzÔk»ìš`1™ïµÞÉkç¤ù¨ª œ}L
+ðJíâD5(µ;iÝÍ-ižåšö9h?ëûÞÂÉÍCÎ8	=U÷-Iª—ŒB_\
+ö® X%õ{/Y…éI&Ÿ—ÍAKŸ^¡õA)êk’f1zÇ@‹¼×YÊŸó^d9‚[^£y,Ò˜€üCY—úëNÀ+jôðs‹î0RÒ¦z®¢ªœ!a”Öî°±Ù*õJ=¼—F°LY½Ò6z×zú'Ï!";À‹á')¦@Áy+rÌµ^•)ûxwÍž—\C!Ù ¨Žõ´ÿm¶uÕVºðÙ,¡¯ƒÒ0Ó­¹€õ@èÎžr¿ÕýµYÂ1Ø	R®<µµ.°æX{Ôòª€YNÂse€©¦\ér?ç$8±³îóþ…ÅyàÄciQXƒœ·f¹²Ôð›N‡íV ~Ë2ÚÚSPäžk›«ÌQgè6«2 à™qÓaÞÆ(zØZòVB]ÂËD!;ì’£Y)üëPíQ‡*fÎs‚/ç>N†œ©(}µë+@ðó¬ë¢°rœµ®[°‘›?×-ußŠÑ/TZˆ’v0î4äZk°-tx÷“fµ?~UÂ^3ûøÿ»"†æ-ôÒÃcN<ž  bÐÒ“c¿«áfßKiàZNfWoSÖQ38$‚ê2w5Ææqãt&ùÂ£µO±lË:ÂßÚŠ]mIlab¨“›‚>gëº¿kIß ‚3¤¿È‘ƒRÛOÒ1t¤ü´j’Äl1WzÝyR©”zÌ«–Žaœsƒj¼š™@/h$
+êØ¤úíSUkš}€¶7 Êî×ªš™Ž•N·Qµd r°æQÞ¨‡>ÙB§åì»(VUeî¡üyÚ–¦º+ÍÌ¯oõ#Ÿ%ÆüægmÔo´ùVUK¶eu+ÔÎ\‹ùÈAþÍûwm•eíí¬« {n6h?ÁqæÿvM?vye}0¬8\e@š¥ˆÁ¢0K—,“+1‰²»v—A²XN5ùª*›˜Ù’†W9‹Èv´0Õ¨”Ûµ†8±Û¡ˆï-Q‚ˆê‡Ûí-ëiL=D.9¸°0/Z<JH+úIv§©J½²u —fÛò`«i’¥uMˆëâîlâ';lGs›vÛÙp Î“.Ä%ßî}E˜Ç\i8ŽÒ©k€Ê\¸!äœ›85³`X^Ê]\g®%¹Œü äT/°ÌZÁâD¤Ó•‘NgKjÇ§¦u$ºèúˆÌ¼ÎI3Ž. çå³Ÿ«XõÐuçàèù€sf¬®žFpY%ötbh¢t’FƒE&Í.Ä^KKiç¯Ù	®1Ø§–’é4gÖK4tÖ9Óžúuöˆ®	å\dÀAÕ…nHrŒ9öÌÇë×9Ä¸#ÁÇe¸Pi)#‡"è)-©í—2&DmðÃ;
+Lï4y0ÔÄt?‚óQ—ƒ}¸7^þž*)Å!Éü N&·™!7AÖÀÙØéá…y’vÖ·W˜ÜÐ0[ñÍ'fÍ4HÎÃ•¼.ál«°c·sp‚ð]- í—£¨#cä–qÆÒäûöX]*YXÈ¾Ý8‰h@émn1	ÞçÏ9ÂJjÌHµ‘>=n˜ljgÙ\ÛžzÆ*m¯‹ÔmãvÝ°‡@
+êâ÷«'bmðùö4ƒh¾s7°=Ç¬¼ÁZ(1 œ6M×Úõ<†ãèZ©|KCÊ]ô8ª¶zÕã•yØš¤sƒAiv‘Iz­û'rÜ$Ça+UkõrIà0í/”cP‘Ðp®ïs2ä 8çÏyŸ/ËnÆYRc`?7àDÝiÎù‰“oÌMh%WYtçõµk'°òÈ‡–v½`æ°¸–¦îù2 AJ·QÞì·ïv¬Ó¹Ôs”Ûv/êNØ·±Ñw-ãJ1.ƒíß®ÎÄ¸ÇwÍ“}VçyJ)œ<¶hFª÷ÔàPÖ)Ì|¾3´y'(J¥ Ú*¥R;³Dp^‚…"Õ÷rÖRÉkzÈT±\èD8%lrx E·_ùx»9¾]'Õ•:9õ¤4ì¾hsO|¥ÞâImêe/7R”;gœ¥î[Þ3	^#‚Nçð:|Òõø œNp¶¢™8é{¼"Š_Ši-®¿‰?÷ä	ª]!i…Â†Ü`W†8NÐ£ŠX_éPÞ‘ôáìB¹÷´¤4"ˆèp’*pé
+îÿø<ÊR‹åýA½XB\¶ÚÔ y[þØPSÁ´Ç¯*Øÿ*aEõü4®|¡„¥?ô…­¥:9ÒjOb=•ÐsÒnMÂœÈD'½“Æ{‘ÉÂe½r±¦]p~gßìëÈ Õi¨ú}DeoÞEÝAð®ÀäB4cKïƒlÓ(2AxÛyÑE%»T¶§î™AÌ­:“•g”¥…ûws•7‰«L†]Nß{jT6Òìj„Òåhqg ú•ðÀÁyé9	ì|c´‘åªã­ñÊ.¢ÃséÉü†•á‹Ò Î´Ó(­¡äÙZs)S¡¥"ËEEì	}Wï­³ãºšèÒÍsï8<<áN;&ç¿ÿËzµíØUÑ/ð?œ$EÐ·ªîOfˆ‰Q"Š¥(Bf<2Ž`@–òßgUÕª>˜Ëå½{wW×ºZ#‰&†°%‰¢ˆ3©¦]ÁŒrG²Ïë‰s"ÇA9Èw£Æ˜±©2Ò76McS‚™Gû¯®‡lñS(ÕšlÃˆæÇ‡C{9Æ 3Ö˜h÷Ã¹þ]èßûúÃÇ¯ß|òêöÍ«îŸ¿~{ù+J?º|øôÍëW÷//Ÿ~ûüÇ»¿»»ñ¯ço¾ýì“G—¿Ø#ÿøÃG¾|ûã]<ôþÈA#rLpfý¥Ý¿T ‡.×E£@£Ëï	‘²i|×™E42Æuö”km3	fè¹Ã9JÐLÊY‹®(¥†ˆ6”@ž=¹“°%ø>ÒKã½CAœc/ŽÊèîkm¸ê™Ô™vÅLv	¤`¨{õ4j(I¤0¾Ò¯Ø4¿W,•©Í°dæß¡Vè¡·E¥HóÜy $ƒ•
+\.±¢EG3
+uSñ”æ-`‘ÄŠZ®óaÏÜiJ5%·SqÜÚ—ŒHF¨·tü%‚«‘AŸ›-œqß¶ƒV3ÌM˜¯–Öü
+L{ÊJÇ/\»Rær|ba“—¹ÒÀ'm>:=KšcÙóÔ‚»QTØZ¶}¶ÚÌç(‘E`Ô’#”Þü¹Oðõ  ¥¿u7Iš!˜fME˜,¤÷vd6—Ÿ‰óÃÉÌ6¹)¸Ü/éyƒ ˜´Œ-%»ÏÓ ³g+œ¶Ò	¢ß ’ýš›gXƒ±ù—ó×4 šmhc’1•Xn©ÍÝ3„$–WZ/1xÁ†øÚ;Ñ|šxÈê&Íºiò£·¨ÕÁÑ"J¾Odj®L—J”uS0KR¬	À8\Ì‰3“µ¶žAî‘’{¥w[c±…59Šk[QZ';¢E€kfd73gÎû jšO»‘*¾]}o©:	Úr­1 sÑ(±i"NÒ<¯Ó #&
+r‘ù¹¾8ÝŽÖ†~®…¬$N"eš÷^rºAJ#TßjÈ,ö­‰™È ú={
+y`ŽðK(‘ŠñdŒq€Øª¬ô ø¼LT¬È‹ãõH^h@É$u´ih!ÁÜ€ÝÏ Ùu÷pL.Û)%!cD†Œ™ìÀxnÏ’4€¥r÷î„ˆmÞ)fn•NRô,#)báFŒÊžõD¿¾„3U"ý~é»¥;ˆqžbôHßF¸þ…VÌ1h#ààLì<Q¼CÏÌ[Œs
+ñrc‚ˆâÖôÆÃæhá¶e’ö¤ÖÎÄí«×\õòvúÓÙÈÄà´¡t¨u„a JMTúTßr‚Øn3†kW+´&a]J"`•Üÿ0/œñ­›°óø†–+ãWé¹ªãhŸ55;Ñ5 ãÊžÜ™÷Iº&ìí G°Ù´Ã–ÄõIB¸ÑSðéôØ¦üeóÙÞÉ!LtV‚ï ¯|¾^iÊ•ƒqê²¸©}P¥ÚSß-ˆÅûf~ýúhïéPÖ>ÅVø~óú¾‹-ŸçmSÑeo0· è¡(ˆ¥gfC¹ìÚp’Ã&‹´æ‰.@¼ãRÌãÍ÷Ç¡&,»×â“µrQ Ü¦‘[Í÷1W;ø~_	£Ú39•ví»ð»1_â§úqŠ-Ñ‹›#!P1áÝMf–Ia+Ý`¼ ëIãP{Ð½åOGØ!>Û¥qMÎªeM%‚ä:¬í8Z9zgÜ„‹KÅ¯ÉÚ4ù£Ôc|@ÂÇÎ„Ç3C¯eýêX¿iÁçœ›?1ç|õÀ®"þ<{ë·óìÅ½<|työoüë>¿½÷ø³Z¾þÛý‹§o¿ÿæ‡ïøÿß½|uÏÊÃOïž¿~„5ãÏ³Ÿü„Ÿ÷ÂïÿäGJ~äïøå(ý|—Ï/ÿùo¹¼°W¾À^ZßŠ¥Zç±n(¢(ÃåZ&ÅØÙ[¼ãæ¬60^tõwìU ¾K‹òn Ž',oÙQ]+üCµá|TGË¢ô°ìÛ!2ìµoÁ.?(EÄ¶¨õ¯·0xn™wïô(·Œ4ñÎ³ñ¥‰“öžKJ¼¯@n~¾àˆ3b_%…ª3QDk¡¡µ-ìCÉŽ' Kò SÅìkFÙ´05|aµ|2ÈÉ[bêI†þc4œ:ÎÕÃWûÇfÿD·á-Ö:d‡—7š¹Ç€ëE¨¡åÕˆ³R P†5Õ(·Æ~ËcÓïáÜƒ	§¥71~¼¡Ý=ª•
+ÛU¯wˆ'gáim{ùýÞib–yÐ<ÖŽ.¢ŒÌ:óÝ¹Ú½Í|w§ ¿¸ôF¸zzž>‚«‡Æ&ÓÈg‡Ún>Y¶æfÄDšÂÛdå1á®¶Ù7úð¹V¥;µQ˜7ˆ“EÜEâª	0†]¢¬]Ò-Í’E$!Û×98ŽÏ}Õ92Ñm ƒ¥Ï#É ÀîõuÐ9ÙZÀæq®fîæjŽMZíA«Ý6x˜·Q\6v).R^ž“›	YSÕhÍ@=ìvÓ˜ÇÐì˜»Â…öPAœ¡µNPvZK­šö|6¬¸šs0ó}Ým¤7Qå`!(Uš›”cEÃ@Ä1r6§%È(Â¬ó[ÓBAwy2O>éu§.3èl3ÞÜéØ¶äuµš\w‰Á `ª12&bDk—0ba`œÌ — 8Ô ß©Øæ>3·bx•ï“¢ÍkÂo9ÉÇ“{O¢Kúä…¡,•ö¤íÍû²j‰œ±·o%®œx|«ŒF3‰1#:lç“J.3Úm± tMÊ¼Î¨’8âûhÒJ‡…y‰@åúni<#f™‡'™B­‰¸€ÝÈ$”‹Bâ`ÀZSZw„¯;,”U»Æ ¢8ƒ"-’UöÛ­Õ$m š8ÀœÙ‚ÑÂwÛu¥›E¿¹-3ù‹í`¾n«°ŒvEkP6Ç}ö°Xö>u}ärYÕJ7‚¸ŒÃüu£åàm3ü=®PlvÙm»¤Ò¨Ÿ¥ná³¦¤^«¡%îÕ„!ðí‘¾‹6[ô	Ës…Æ`±»×ÈP€µÕúâV7ìp´Z3N™¨CïòQM§ Ô^;`qš}˜i†ÅYúŸ¡“­F5ÃÃ/Å1ü¶Ì?)›eWkERål!±ôcŒ"¾»¢8"ç˜Þ6i¨y8Û
+‚ˆ±b7Û55¦‹Ý“´ §öì{í”YÈ$8:ò¥²,_a±JóÑï>EL¹1C2I‘V–XW¢ó\uù¼:¿„w !¾¨ÕR³Ý=ÝÊ'nëˆªÊT‹bi‹Å-=ÛÁðL³˜ó´k	«Ö‰ì6R‹W°ïE\ÑPœ:®S mñcípM\ 4]Ìñ=r«W2†KÔÓªÖ€á“œÎh7Ê¢Á±(jˆªbvLÝù¤Û€š+=ãÍ¡Wgæ„GŽc'Ý,¨'7V“"m]Ý	;ìRœz­\¯lîE*¸^ý¾P(õpA÷k[’¯—îdªÆë¢¤R/ºt%I‚š1Ø[±Ç÷A Ä\ ÇNõi$³\&Ô¼B6·ÕŽ”=#°3£¸²}ŠÝ£éëH:Ÿ—b×0«¦ž3Ô,–‘ûªA¦XÀƒ]©Rc²A­AÝjrÌÝÎRS¨æ9¸‡J·‚úíýÞÛQºØª]¢V"äàXAOÙÊRÓ©GgÃ *…oãâf>º['ŠŒXv(irÞ×e$?»ù“ÿ³_m«qeWðúÎ‹Áé™}¿$Oj9$=ì˜1„ dI£Q"Éƒ™øïSëv.­c,‹˜¼F>ÝÕûìËÚkÕªªz&4‘Âý ’8¬Öéõb+˜=›"àˆT•¢I‚ô€ã]Õ‹ë,+õ½%e¥T+¦”;¾Ö’{Ecæ¼¬^ªÈ´º>mR sî:’ùÙœ6yÀÞ¹¢bO£J ’@'‚õ&*ê‡6 q®4¦Ú,A@5W ;yI“Æ%º¤ñ‹>Ò8ç¦ñÊÔÛ¶¢®sFE*5‘)ì½u!ëUÚâf1ƒÀÐb*ùs´I£ÉU”¹“Ë¦*¶¼¦±ÎS`_t_Z&ëÑÂè$pçM’²ÓüIÍÌ¥ QÐqô'ˆ’Ž-^ˆþ¨I§¦Ú¬R¯aÔT”š~¼0è5c¡‹ÌŒÙÁ0¶‰²¾_0¿?¨{ÇüX‘Ðjjüp»Y¹UPÕ:â«&<ÝŠñdƒŒ>œ©ÇÕ*®qÁ 3K
+¬Ä’_°ŽJüÒØý1©êxÔ;W‚ì
+äÒºÂ©HÍÒØj”gJÃSa\ª¤‘Í•áë(liÅu&¯`ñQi·jÑâ#
+ºÉú¨ÕÀ¯¨È0{ŒL@©>î•È|¯pD¤GyN ®®*e&å'þ®Òwp,j`nGz·ê±Xr
+(ú£°!°9=ë/j01©VópR57ëqÎv…îÌÒ–ºaòrØ #Ä>½»ifŒ|‡À2µ‡qÖì´Í;õ} ¹o‚’$µ¢6š€— Öš/ŽÔMÖ±¾0™,vYTRr €.km¸:.†	zÖÞT«Ë©ZsH0ˆ5+4×Eê@þTvVÉeU€¡I–È³ËBèúATYOA“.±‹´¥ÔÍÚ"qŒ«5êÉ2zª€Éùd Ú˜ÊM×íi,ëHShÔi¾0€h}/ô6Ô®ÆôÛ´Ô†¨Í:VyšÄq’¤#Œ2:7çÇ€ûÂd@Zœú€¼Hþ0œ)ë%ŠÍ1yg/©¬¡6Ëä«
+ùÉŸ6ÏN¾?º»yuvõáöôîÓð‚¾ÿqx~tþáýÅÉÑ«~‚áoî?]_œLƒ^¿§QøÛøáèü÷RØŸ©/™mÊË€Cÿ(eÓ îEr„h¹‰}IRýÒn¦¡v¹zx¦¨A)I†%il›BT:Ó>cÕ|,Z½ÊtH²_¨¢AÍ*.9ÖFy~Ò˜§ yÀz‰<]·Ö|pü³Íî=‚óüíííéÍÅùpywz~uq{?„Ã–”F»a1G\†ýâ¢pgx ”*á§¢ 
+p$$2‚qw¹A¨ìÆ°…&Dr[ÒwÔ·8xKÂ¡‘z+³UG¡Ø½w7›ˆÔ+°‰x\ÝÐW_NdSH†°Ì†vgO^v÷èeAs`bî²¬qY;Ê`7ìvÿó4þÝÛÇMùµôýë‹ÓëNïï®þƒ·‡çÇG¯þ¬Ið÷Ÿ>ÜÝÈOº‘¯ØîG„á%þ.7«iËu·šâ«Åð¹ÂY«±Õbülá>¬ñU2X©œÕ[¯Ä•ªýD'GZƒ“2‘×S†C$ÞÙ»ê…ì©©¤˜¼uvQùDþDègÚ™KÐ&›jâ0ç¢Ò¦Ñ0Äz•²QZFéªy}Ê¼r"ùÛx(¢M+mÅ£ŠF£ƒ²Ó“Ÿíì¨R½°e7éx)üêÑÆ†•ƒÛ0ÕHmÅ£U>ÚÈ±V¢ýdÇ–~„OÅPD‚&/Ä%åI#mÕjCjÀ°PÊG:C|\{9ù!O7‡; ‹Ä1O]w÷èua|‘Ò…3¾ˆÐþÛ>Çm1F­m{¥6D\Òž¨­ÅdÔÖ¢²X5ûVèý, ›"£¶Ð’R[Ð²_¹ Š	GŒÉ$FVå6ZÊ¸bÏÈ-ª¯¤^È€²|ÝÈM& È>ÉÈM7–¨Vã·ÜE·†Ñl>Á·¤7J_Öót¬±•€{àŠÀØGW	–{=R¨.xÕ×"\lÖ,ÞP´IØ§Ð'	WÎ^o1b½°ìDOãj{´^‚/¹
+ZŠ÷*Áàµ¢ÜW€/S0&HµŽáÎ8™°/HÑŒq%ë%fõzCðEªÃvÜà#qØ2=…ë¶ä#ˆÈvt6‚Xd$¼F¢àÂŠ¬5œL·%CÕ †èÐ,(g¼Zñ;¶‰Ž>šå&À7O[s÷¸5rÜìŸú-*½ß8n•ãÐ)ŠëZ2IŠ})©m<¹UQWï’4üT¤·“4ˆ¢ ?rWq —`G‚BôÜfÁÑŠKªMœ«Mªz#ëì<“è”ˆ“Žm•(bŠÃ[š4ŸEø\µjÑ@Q†I`[,‘
+¢8lWCðmI§’Ó8UP’#¦o,…P9Ëi)´"å w—p¥ïzi®ž¬©xº&ŽõšÚ³†+°l*t°õ¾jç¢X{›|f¯†nÎG­"×D°cW^ÂE¥•$\"?[Oé$÷’µšÂ€yBnèiKÕV÷ _ 9¸³2’h |uú?Xä6æ{Rç­èVö´Ôé´*YƒµJ´€g{®¼èÐ¤‹W‡LE2}=iÅÝãVÁ¡á%)îÄÿòúŠ)ßnúðüÅðîG|zvôÊ»“?Ýž¿ùtóþÃµ~ß]\^Ý*òü/§÷g?_Ý^oîï>üûâÎy„¿w¿n>nˆªŽ~Q¾z½q³kÇ6~ù„/Å‡QC~ÒðÃðºáœ&{-µGÔ¡Qi7#‚„îzézóæk÷¾¿ºüùþýÇë÷»¦}ÿíp»§ëÛõ«{¥ô`£”îÍM8…ºZˆ¦9`ø1«pôP¡3ðló™¡Ó”R¯ö%ŸZQŠ™¡L<‹¹iµƒÅ<V†Ñ²7x¯.²°BÍ@´ÁT2[iŽM{šÐi÷ÓŒÓ)g‹Ï²:tœrŠñ„ém,Àx9/÷'"+g‹+x°ølè8%‚ÓA4H¶§ƒµ¡#¹IÌ'DGlðyËµ<Þ,îÈàý"Af3Œ×>[iJ…Ù–&pÚû”Ógù1ÇÚÐiÊ)Â*ƒ¸ÑMXÅÑ?Ô›è|4ô¹CÞ¢>¥¬Ž 6¹%X¸*¦`‹lö”\F»Nst¯(ŒáÁlí\¶ÖämY‰ÀûŸ²X…Ùbˆ7L·%ÐñfyA÷›åiÇ×§¨LË<ˆßñjT÷¸¹ÚÚ¬ Úí9šÀ·<q€Vó]ëL¥@±z†Y´cÏ3Ô¢ÝR+Ë	°óàs[.µ Û,ØKt€‚QBóÃr©Œ¨«w¥˜Df<¢ûÍò°Ó³°LK=ˆàñj\÷¬óÑáq·™ˆôÈd1Z#§AæŠš‰¬†CH] éE*p4ÄŽvÚÙN!;o	*ÍuO!©Zë‚ZÄq¼l“`(sÑ–©i"
+QÌDÈÂñ }å@
+Nˆ*Å=G"68=<@Èó ¨£l£ýgh±¬r3(yNrº&KŸ± Ù–f'AÒJwð•³Þ½UD$ünêý)´/+lêKOËÀY©±Ç™­ÐK®Ø¾x^9BÎf:Åþ ÔGÑo‘ØçÊ<ˆ°^4á2Üž˜Ø\ž]ŒG¶T1iz‰2ÁäõÊ÷K˜“Ã¶•lJ"x™âeœæ›ÙDì…¢ÕÀ]1%Lnj¨&êõRB)Ó©ZDÝ™Kð@³¨ñÍyµ8)Z¿RŸ
+)Ñû;3"ïœ³¡¬%„+‚V†úNÓò;TzJÐ%gi¦Ñw•phê6±£ÖÄéaDg‹­÷œübÃ†É‘ãMZôl(BÒ¤GÏæÄÞã|ùãõ]íÙì~ÄŸrÉ³¢d6¾3{øXµ¯òéžH”ºw|£HˆKy£?ü—÷òÛÑã(¢øä¾$GB›î®ªþW	¹‚@	ˆH!Ë±H˜È2Šòöœê:Õ³»^ÃÅ"¤8qÎÌ×3Ó]õ;§fÌŠ¸€¤®¬^äï]³Ä>ïZ”j¬€XQWtVê£í–ív¡·Ñ.wäÕ<¬0BP6´…]/#.¨¿sô<Öò.2gùrDÅ`ÖEÎh¯±‹K‘ÝÏ¿8,˜êJç)Ñ èeÀ"Ý¤:¥/‘K;QºÔ{¸4˜ÒV±‡Ë K*öÁóœ3Ñùr\bCòk¾x¤ßûôêvºêÃMr‘¨y¸¥UîjÛõ|oÿ £?:(ˆŠÑëÞ±æ¨Ôèí¬ƒ/_ØU3ƒ.‚lµ»ó*¯Ú3Íd-¾â
+Ók8š¶ãP™I‹ŽeÊni»Á!í}æh-+Á”†Gª04 ¢4SökÕ½)æ¨f™úðnÔ—”àY-G‚çQKùÞžŸ|úöÝçß½z÷Ý?ß¼|ûãíg^|öñí“¯Þ½ýîÍ_o/¾úöå÷¯?ûûë7ßüîå»oùùÇ·Ÿú-¿þà-¿ÿñû×qÓÏñÿìý“¿ÌûˆDMÄ@‚š¸›‡Øù"GTF‘¤Àu‡Š,¬<'£8îF›ì8#znŠ¯Nq®1ÞŒa_bYôó 8ƒuþ¬µá[ÿ Ö¶8QT³¯0`»%œðžˆò6¼âuþy£ëxQØ9J 5–ó@Š×gtåÃ»½0‹îÊT|œDçtÐDìûyìÝã-ŽQ_[ß¢mž<ÿTBŸþOKèø³n/>¾}ýÇ§øþ|ýÃGÿ:9õöÛþ›»Ü3Òñ?¿Â_þé‡›Þ~sûÓŸËí_ôË>àAÏu §ýç™îólïù€ó<×w>à:Ïõœ§ç¹~ól·ù€×<×ižé3Ïv™g{ÌÿÃaæ5¨>h~ý±•í8LÏˆÉ«­¨ªª=;Å€a…²ÍjŸ“÷ŽÊI'j;?«Ýaé§‰v5Rž{‰ùžè¸S]íˆ£S´VÏÖ7ÍMü#¢}Œ‰Z]ueìúÅÛy«$P•õÛ-êâ’Âú ‰`)Kè~­ÕMeµ#[OEQ ¨U†½/*6=¨ª,ô¶,î¯š¼¬DÌŠâ¸óÁƒSÃ½³FQ	îºEù©
+ë·/Ža«TM»¥
+Jlƒ‚:Ji9Àt¥h-^ ù š‹V,Àß£NöfyQsbÛí·#„g¸ÄVUXc|ÀÈÇWŸ÷	¸Ï~’{ÒSŒZç‡µÝ¦[½è³;Ï¤Ôv4	­®y± Ës­2¸«²"D&éWK×{ü^sCPgÓß*ˆŠ…‰Ô%ÒSCí‚ó0;S–\@h+†÷ë	zN»)æû¹•ËÚþo¿%+áWŒjÞ&yxm.zX“• ìj¡•52Ò•¾fŠ³_fß`ÿ—å_¢•BDKñ!@~Î=ÆÏ\z¥Ú2ð?LbêG¸$~`JyöA_µiWk‹âÔ]|ð¿Õgö?d£³/ìkâk{‡"¶Hì¿kØŠ'B@2‚=(ÝÈ0›EéÈkFq3o‹†-à%¶wªcWØAše9´$“Zx2à·ê½¡`Ë“wŠj‹¦è¦rÄÆþéýÀrô¾¤—d'º¦±!5Ö#ê~<ZwgŠdO“ýø¹Í¢’=LKÀ„ô–ìé‡nÝ‰•ÚRíDÏŽ[k¨¢§˜23îóˆm"BÅ›ÉAÏ zªÕœsÔÏ<Þ¿$;=ÔôÎ¡®•¬ôñB`Œ‡X¤é>€‚`s(£^óÞàFu„H”¢Þ[ éfÄY£?”ÒÃz±6þ†»‚tL;<jÈ¹]Ø´-=±ÏðD‡ü!JÁ·]ŠfwÕ$iSÃ"h•ÃL·Rãü}ÅÆÉß÷\C*gMœ–:=«_ŠYkŽnÖ³­QI¥5zM±µC 4ÎLùÀ¦Îd¨4i·'ò$:I ê£PÈ]t0¾³ã	t½*ä(v§Ò¬¤=9©$’Ÿ­ 6æ–™@°²ËJ±“­å¸`Ñ—.Þ_€´3Ðž Ü”YX#7ÅE‹¬ÎßvÿÜ¨3–ÙC”}ßOMçQ¼£Ÿ±ÌåÁì3F;ÑKG¸9j=bà¢ç\À‚4ˆBzwòÅ<P§åX¶†0û¨—ö+~;=½¾“”SÏˆš"5ùÃ–rQm µèu—-*1¾8lh*(³u¢»_=*“·b>š‡@1í¢[Ä_ˆ…G•$P«üVŽ)Ž„HŸÊ±«›Ûÿ}kµƒœ‹Q.gÒZšIu”VX‹ú*zæ7~«Ÿ¶W{ˆ°ÅºÈX…7]»ýû~Áqø#ZèvÖ£†°3Š5	·H(d£ú„:/~0@+×ÂÐAËÂ]³sÑ§‚ –!J;·Ûû†·–u’Ùœ³%Àd Õ¨ÈÆ{!êH)ÎYgŠ6/µD€ŽÞé‚£tãª-¼é}†<I çù!îE ŒJüÐýþI ]ì²-%ëlD0tçq¶<¶Pc ÃúEóÎmß1S[Ó¨µq²¡l4‡Z{Ýíœ¹Êr¨€¨¶BI¡¹øþØ4ËºÔ¶}²ŠOùû>;{`·6C˜„1¯FS¬¡!ÎÛù=fTú}«’`¥'…ˆuEm2‰ª	!Ö L
+!ÔÂîg¹¦*,e•Úw±µƒ‘û×¬q¼Œ;óJAˆž|> y¥ m–`ÐI ¾©;™§’ã§îBÔÝ?Næ“ÿÀž–1/„„Ûaÿ×Òúà÷Ýû·]ZéeØù}SáQ‹äã{ø·×‹Òßs…(1T&TŒ^‡ëÉà±C¤Ù5® Ü.`u¨ i¥ª=YÕªÒ€Ó\ÔèÞq¯!NÆ>æÊ{mì±éØl‹M‰il ¡W4ðè‘¶@Õ÷TŠcNb±[BÜ“ÑQ»f
+g4÷E%‚åûy’?Fwøƒ*ùƒã­»©ýû õb©—ž{µ,RøýØ‰œ,
+Ú&Pá`õ hG´ûÊ+­bž"VœÊ»Õ ÎZì,Ðƒ Ö¯)#‹D^F1uæådm
+p0©1„KeŽ±“âˆ!"g+)Y[NHÎÂ{ák-ÚG1Ž¨“bÓë6ù‚A‹¯:L8›œÙ¬e_ ƒaÌ‰ l@Ý»pÃ­pÄ=³‰øß‚5œ7\\’!ãkÌŒÓëŽ3›GÇmÂÎ‹×„v ÜBÕé¡.œÝîå 2H©Ñb÷éWÒ‘	/(Ä•äâê©µA„·’äj·N²Ïq~^ÂnÐ‚å0¨­Å“ªSúY@KÜîé1y7[DŸU¡ŒÂ¸,×†ý™ô;oÑø~‹À±/|2³+T0|>CäXÕåÞ“!Ø>¶K5=dÂ|›b“B˜Î¢ß°ìPË1BæÇ(¼³ºŸµÊñd©æÈ%R¬)©ußjv!( ìªÕLâ,a_Sâß§È#9|PxxD2¨¹+iæ’Í’DÊj{Í¼§]O+C’#2,¶¹×‘#¤ïÞ<—…í³ø{Fªtm´½a“?è‹}Pî«óŒ,5cÂÂH±(PG‚X å3ÃA³].I¶#+ÜJ/!@æzz|÷?}¨úÝš•…I*%8ÎJƒDø’€—8¶I~ŒËY+Ö
+ä)©$.Ó™ñ¥ÔË ¡6g1)dí»?&:{Øâÿ±BzKæT~F®q¦¹~F¾¾/<¾e$~N®l¾m›ÄfI{¨v?ÃÇØ²}€ðWIšªV¨·Æ×¿àbˆÕç@5¼Ö¢Y@ºcÝ0_Ô@zê×^YEáÜÙ•@…(„[¾E
+ŸÓvÖ‹‡÷ÐXÏ§Aù[=s³­û±V’@KÄô)õ²,$ÀI“€}ìÚlþhì[>ëÎ«%ì¤í¸à&½}1{¬ßóöúèEééµâ­=€ÕVEp¿†ÏºJPÝ#Å™àPXž¿ŸÓŒ9:g_Q1Zi4x¡Ì@…²"Í¢ŒðjÓçÞK ŒÍúÁ¡[±bžQHú/?¯Ž>ÂØðQüà†ÏØ‡N"øãÓÜj<Ô[ ‰êŽð¹4SÉnz&«ÕþåR6:f§!<'?j€ÁCeßèÛuçéáõ	ÉLÎ•e"D"Â5rÿq({D|§¾¬¼úNhþycÌ>âR9s÷ûè…¶ãL½=6Ÿê[	•ÈÃÍÌöw¿’>‡£Ç_6<)„€ä„²ÌÉÞu£ú—_ ÃñeŸkvè$6´èƒ“%<Ì¥¼èƒÞ¬¸<Ç„K•bâ>¢ÑÎöÒ3>+•´~ÈO²ËÎcù>³Ó\3l5|,?6¾Kö¾Á¦	µ
+õŒ‚ú»Ÿ¾°”{Cå¨°O g<A<ó[á ¸3OÊ#i D´âgyš;¹˜Å±Ìù˜ÃnŽr=Ò¼†n}—»…ºj#ˆbíñh¢ìŒßUš9Ø=ùtÛ°ß³&Û‹•0TY\"‚m°÷²¹åGÞLÛ¼v\ãÊÐ]áš„Î®xIÕáå7˜¹düÆ‘ß ¤¨¾bÐö]‘2è]ÁZRšZbâÖ›ËUˆ:YêŸSäÔøòøíŠ•
+Är²ê©ƒ¡ÏêÂÐÄJ—B“NúhËiõXBþ²®¶IS:“B"§ti'×Õ¿ãU†çrþÎùƒbÇLÅ¼ÄS›é®ÓóìêþîWá²!«×­ó¤¬ ãöù t ÝöAhäcP*OWÜø(Œ¬_@h*#|þÙBÅ7g¥ª//ðÍ»ëPc?`8.Š¤ªà-Š~
+ 5WÜ„Š®,½•ÏE‹Û³ò±ùQj¯µHé¡ÓÅ;£±îÍ+ì•ÜÁÞ'@D€‡k}xsÐwcÍ×Z[N–ÅÖÞÁ0Ø÷?\ÌZÁpF“ãm·²-Ü 	…›ÃáI1i¡A¯W4Æ&­š)Cµ"±ÆÏÌ­È{m¬"Í¶ µwå®LZ¶â š>¹kºƒ¹7'Q `Å¿»/C±Y¡ZÓ‡vø ŒJÒg¯C,ˆŒûÏ¯ù?rðÇ…¨ù3Ï}ù™Pñ—üÁ‘¥€!=å_#<Y|ìÎv21)MŸuó‡úÖò^©ZÖvî×þ¶S‚4Ž¶îÇ4ïœ¶2ñgü/TÉ²+Äâ—áØý±7¡ûV+PÉS/Zf3Dw°ú7t­ &¤J´u†6âeÍçHŠE„ñ³.ÿBý I5ðkVo{ÅàNBÉ«âÍjàW ºÙÍA€9ÓÂ  õhA#›gy›™@0ç
+@yZ¾@#äÏç5.œÉŸ­—K•·Qãg	áw­Æÿ@]$}dË*úH¬4xùõÝQ¢ºWlH¾=*Ý²‚<œ‹ßÿÝûØˆÿWª‚>$V	ß®(øéûnçö[ÛOx-0"Y&§¬èZ`i?àsË‹Nm`ûÅ™xg…¶¢Që"÷ : Çç•,aü,2Igd¬Ê¾ûß¾\{4€æ#•ðV¢}8²±°´ÅÊ!×TÆ)ÍlbŒMµ
+·ß–¡oM á¥XÒj Þs¹³Ô'ü!  ‚ @ÇØ ‚Ó€p#æ/>Ôr- e­zjI'(/ÕUG€¬ÞA<¶½·L¿è}9ì§Ñ=:¥åÌ.¡œ¢Ú ‡åÓ·Q%mNò×Ã3YVÛ'i *¸âP‚XaëÚØsA,
+Ï¬-üîôý×  XêÒ/Öì7´ÃM*U?ÀãÔWs–¥‚5ï>Ë¾dæ[¨
+Pþ¿ü‚oO.<€y^‹ŸýŒ`@?-]ÅtÀ0#Uˆ›˜ÐŽ&‹¡`Ðâuçéìú•láàõá-ðR{l+å¨ÄoÜfÐšq Î 7núGz±ï¦kVˆâ¼äú}Ò˜´½ÑóÂåêƒAšBóÉ­iñ1dqó1ù
+‚BÞyÛœ"6Ê•%4^Kâ÷²ÚKpz×dü¬Hu±ûÉ‡ =™z[ÓŠò ½…4çšcÉº¯t¬AcñÚ-¯hƒÉÉ¾gíuÇJ
+ü"åa˜™½ÍÌé’œ	•cvÞ‡r±ó„Å¶Uÿ)ôo€ü†qâ~Ž³¨ñƒW£•Èÿ•–ÕÇ›Yhh	h‡eÿ+¨,@9ùqP— ŒŽÅ¸HÁ89>öLú#G8Svûgø×Œ2Ã‚°µLaSÉµ¡èaš&Â;Fµ¿Ó;ÚÒê‰ª/…Š¬žöÐÊÿßlò¸w-ý€´]´:ýTxTÂªùŒÓ­Æ³Æ[­mô½§0vÁè_tì ´vßÀÅ¤À‡™ŒÐYƒ 
+, i"ÜcaµÍÖ%<@8gê\²ò!h¥Å8_­‚†íÒ è|ü+8ÌÓÚÝbîÌ¯hsÈào5p7ñ‘d¿?°³‡<>±“Wäf6v!h}	ûäìûéÜ8p¹­\1f¢4ZäÜØìeÉ¹,#]ßRºåAåÜh%W62hpŠªS£¤w°ä² .‘h£^cÁ ½f…ãÛÃÐÛÕž×j‹ƒq]wTUA(Ö7	¹ÏdŸO¼öJŽkŸÚÎP³»Â+Í¡@bÆFið9Ø[Ë)6ýI~å¯^Í!_ÊÈ!<qF­áK™¯\Å¡u*þl~;1Ž5ç#Eä¾’÷ÜMâèªû¯†`‚ì×õ±ÙÙ"!Øf
+6ãÂðz‹òš»B(âÌ’BË•>Ðî°	°Ê÷gyÂ´µÿ`³{rêÒ{i;wÕád›\_gú~.<p‘Å‚_ˆ^&‚(‘.{1*½}!3¾
+Û×\~Ž²á’úQ¾¼ÁS­¯W¶c}m-qÛÍÝê¡bºxÏ7uþP 8sçÆŸ9Zð`¯ù#ùCwÛ@ÊL×š“«@|=Ÿ…Éaçéwam`O<"§Æ`ñÝnÆ£_”¡åáùZ¶Ò?ñ’S%³Ñî"^‰;ÓÁXŽäL\\ßPîGºÂÏ‡0ótÎRËÝ	0‡zŠ®­
+×þ¨3ªu¶ºÌ¨û˜óÏj!#HÜGÅ¾ÁAQ@Y_æCKh}!Û©^×·z)ÆTóC£ðb„äÿRÞÿ6~…ÎøÁœ‡‹š9Û,¿ÒsÇøÃÔàŒÁ
+¬9Iˆåx&œ†&«¡Cíõ´ð„±>91n–‡wí£›Y#™¦rtSâMCšÓD#«1öýw¼ÞÎª«æv¤¨ìÙ¡-V÷‘×7Ÿÿ±].Y’ã8¼JŸ` ÁCÍý·ã Ü©¨©^&RRH$h0ÇðdÏ·xù(
+N™ôÆ»Ý:k?÷7öWä{îÄÌ!vä‚ÖïñÈ{â#Îì2Ž†Lq¯Å©Aü¨âÎÁWh95²c<â\P—²´Ê C^;ˆü–Òß«èÍ>i_óf‰LXÿ—9ï<yÙâý„uÅ_ÅÒÌ?.HˆO#cÝlÔbïhw6å9Ep”ÔŸòÜÿ3ŸùÏÖbBÃ¨‘3álŒ÷YV­|;hÙüØ3BFÝ£)w­S¶=ú\'¹­îË>ëatÍò²ž½G4Òæ§Bcª8Ï{Àýã–÷bJºkÆï­"Æ
+°|ÇÏà¸4S…™	@­ñ¼Ïö²ÛYR„ÙÜÌEÐiÍÙˆßµFõý"ÐþÐBÿ=Y#h•~]tÇ9‚FˆÚÂTÿE\H›Qs
+Ú¹/î`"l.•eþ@åõLËdÃšÆ¬‹Ü‡°L0HÙ'%ÁœÝba_ñP°ÇxË—›q×=ØæÄ°©Qleß=+°w¿{ÍéV§[×zt†‘NñBNÇþïì”&é³•FÎ–µb R} G¬~öžø½¸‚KQ3Ù€Jé­òá¼D=Á²^ ÿøÌêœk-ÙÎâD}-Ì”“(\¦ÇÁŒ×š›Ês(?sÚãÐŽBÆª=ª¢<kÉ†ÊNû2ÑGÎÐÖ ñ'GîÜx H§ÕÆ¢Ó{çàY¥7g]ýDÃìV{sâæ(»sC b¦ËH6ˆ!&J`hs'†F0¹ïB£~	U›’ ×•mÿˆÑæii)xBT§z„fT
+˜Ã=ûZíñN=tÙáµ6‡,
+!É«F-å±*&f„Æ0= Ô„à™»w%Â¿9B
+MlàG¡+E¢ÐÆ“…Äv4hÃ-ÿec ³l²ÿ›rQXÍ@5EÐó9ÛÄ 1îFùyv´kûÜ\úÙÓ6 vc‚ç{ÌÍ¼nû¢yÚèöjaê¨¡Û·hîÃ¼6JÄ6³‹ÕÙèç¼ûÃ;iÓÌ¥-¢EOzE¿CE›äù±ïµ]{)YÊ-#nY´ƒFröµù²ó@`ÁLâØiÑ¡tØý˜YÖj÷de¨êX“›_ïjŸÇëZ/Eƒ‚’ŒöÌ.“êË>rO|nãÄ¼ÚqÈ ,‘BP¬á’/¥šU™Mt‹®™!BcžNmr8ö{@ÛA
+¯´™/Ð&ÁÔÎÒ€gl—FzÀò 6•ÄnóÜùhÀm»i–Æùdˆ¦å=å=>Ãø~.9dÕñýF-Ý.â)líQ¨WæÌá!»éÑ‰€zoÒ°Ûá…Ï#<QA52#}Ã« µ]ÏìVt iÑ¾ÑúBþ@3âb€w| Bº•€ Dˆê°M,Æ	ýüý”»!c†Ž`&‡ò ”ÃÆ?ÂZ§Üì5_q•Í»zav·òÛ:­ˆ#Q²,^mÓwzê€<êÌýgó<¶Ní77™IóM‹Ásý!¤Ù!næ$C·FŠŽô=•ç'“Ùû}fdÉiJ­Wï™œœk)—Ñˆ q–‚¼ßŸGý 3‡‹{PD‡† Šù}òS2—Íýj8›’ ¯îÍbŸß¥£üsÐZ«„¼PãÓ‘&Ýî˜øåOwÐ´á:ýË'³ØžÍd mk¥wûB‡Ë:±‚ÂG(Œ{ü›ƒgß¾û‰pÌeÌü­ÕÙ,O°ÖÐâyl–+¶9^ó&¿5ê°"aæ'}:OÅîíR«îž %€[0Éa¹”pwE¾ñÓÉža[3<„©Së—ó~LLäÙßö‘˜¼¼TÙ E›¢—»à‰l±> MaåH˜“¹‹ÐÃíŸEÈ¿ýø³°_äÏî˜Áé‡×ògÊ2A\ôCÕþX}è­ Ô­¾	 lm=þŒVZ†²5¡F‹èŒó¢Ål*F`6jø¬ØÒ¥s¬³SÎ²WtÎ9·ñ¹^•¾³cJ7|‘@§ó­¼ú‹s>‚ hAÞ¦ùdñ´ó`£ájoàV'pô.‰Ü5>“@íh]Ï4±þ ‚…Ý^qFM°‘0†3$J'VÎ]¶äþ´jµ’ ‰*"Q-];å@“µþÐ'·:l|)ì*xfFÍß{*ë›¶¿‡»z¥C4Ó9:ë^'0	ýaéV±þë¤5Ê)Ì”r\|t[¬\iõ «RXÎ›fJa<,çùCN8Î*œ¶ýîFWì£ò¦Õ¡„]TåtŽ/DIŠfÎbÙ.åž[Î}vÕ€#Å”sy˜ë~æMŸ=e2ã¨ÇãÛ¿¼¿ylfyqç–SYà,®ù „lAÓ{¶œwž¦âÿ1D ‚·| jøîG œH@Ýë“¬~Gš\ê^_ŸøãêaUüúÒýÐÎŸ,Ÿ’=ld7]»é4‡
+oÜëÛí÷ì®…×æO‘*]MŸó9IœÉÃ+}Z-šg*&ÎÞµ%"`&Ÿ*"tú÷ sNå¨F¹µ:Ð9“\5d@ÖŽšïËIöÄíñ¾nm5æóß$ÖúÉS¾8fp`×"NÔOi9¡b7àJèçèHQ&2cVÑ»ì H•1GÍÛ¯Ô&ûN%ØË'{îâ{ê<àõmŸþØƒðvÈž>tÌïÌ½KSèñ½¹%ÛçïÙåÖÆ˜@yZi¤püï~«ì•N4ö»¶«'žÑX‰øí©kzÀ®A·aoä<²ßHŠVÝ±´(mžs~ö3{P”ö4™Ž2fòÙßêû—½€²SåËJ‘wÎzLœ)ú´çdÑ¾øÕ­«<C×Ò5³˜ƒVTœ¿ÅmæyÏe»ŽÿT‚@Í­þ/€?Ï?#Y,üÀMøIi<9å?èéG[Òÿ6êK½’½:À½‚¢ðƒõw–sUªˆûWm+mr®-Ž™Ž¾û÷®ÍŽô€£ h¦fq÷WTªòöø‡\¸&Òs>°È¬‘zž~x­Î4¡°G{a××a‚˜	§†úJUÕ¬\+QîÏ {iÕ‰à‹þpÆcôhÔiY?jÊj{„´&k‘CAê²'´ï"lv­×–fì¡ûÇOÿ®F){Y)Ôë™Ç%Ý¥tq>ýA¨Yõù{0¿¹T=¤T€ŸõI¥9Þ>De¥œ g
+1Ö`‡Ëeª „y-üC¶Í8®ÜLŒYV‹æþóÕ™QË^_à•vó+}:'õÞþùÏpç±ÜŸ¿¬19Á-ê¤UVÍ"°óàq:Ë}>õÆâò£âYÎY¿ÖXoËK³Ú—\g2Tç:©´ŠiŒÐ8S÷oöêx	_uNh4þÁÐµ!È9€( €9BDƒHý\M¿nƒµ½ôÛPVò#`_|y”÷=h9AVís¾ç,¥D#Ç>*fª;ÁÅŸÁTÕúi£(>§þgÉbïþnÇã9­ŸçZt4úzP\Œÿ1_m»qGôöæE iDR_ªoÉ/ Å‚)Š†@-	™†H
+2iŸS]Õ=Ó³K$@ü
+ôr«{zª«Î9¥Œ’gþÌÁª×Á6ÿ‡ŠT¢	Ñô]½bh£<ó§7:}Õ’e¢LƒoœRŠº¢ØJ‡²’Š)ê¿pjõd ¤"Å<“Õ*¤®Çx©þµëÕ©2?§ÒÀÜ&šA–—^»Å6³“ÒL?TÔ¬jˆ‡Cqu¸©N?Õ¸Õ÷‡¿lÍë¨å
+¥v8É†Ôº/6±cUÈ±´XÓ¦¯2{ ’S#ªlgúqSª¢˜;×¡µ\¨dÅ«Yª^¤¯÷*€	ùÐç™^QÕ®„>“‚vTjKš-JÃ)µYC0ª1­CY½CSçÏ,}'0õXÈr‹µ¥Øìê(ÔïÐ¶ƒÔÃÔ|‘i&B{Y)‡ÒÌ@Ôžµ\Añ¦tA­‡WÂd§£/;4d*¸ÑPã ¾Wß&“àV®G˜ï yjw  H(¦––ìr\€-¥VÆ"/` ŒJ8^áÈƒ>©àUZFÑV°ÍvÏVÇ‹r!ãü
+ß¯™ˆûYðA(Z¯,âj"83–`¿BraŒÚ°Ú†T‚€Èuê}ˆÇF9¢‹t»ÙïÜÁwøäÃó£¯w§WÛ»«Û›ó¯Ó_NÏßÝ}½ºù4¼ûõüËåñçË›‹7çw¿¾<=œþÂ!4ä_.%èoøÝ¼ßp5ÈïÙ¾àãb§ƒÃéì§ÍÁÑÅíÇË‰×Mu‡ßk$JêìÍæ	dŒBdäŽ)×?ÒéIýé°þ7ýgóÄ<þãÈîÿ/ô§¯v}o7F¿ÈË¯±­lÏ¶´~YSfú±âF»ÄràË3RIÂuynY×¦9¾ÃÚ2VÄ)Ø:1b/­Š16øf£Ï£¼ïUê¶%‰mdÛ‚>Š?‡¿..ö¬mÊc¢ø~i¨•…"ÍÂYž@\®RV§†Ìþµ²‹VË—b/aŸº–AŠ²Ñ~Áëç’TvlæDªÈ«»lCÛnú¯ö§Üç˜qì¢¤¶Ûûë··wç»¨gÙÜ'R6©~­p2Â²òÊ’.èh£ã"ÀæçÚ—lO­ö2b–1ÉX½&IûÕØ”uL¸¾Þ§TŸMnÉÉ-‘ˆ%ÕdÏÊaÔÐ:\³n€DZ§2a dº¬€’õâ”v3ðxz—<Ø•Ý÷›¢Í²üëÉÑKk>|sñîáúãígý~|ùéêF‘ƒ×çŸ/Ÿ¾¸¼ÆÇ!7~Ï¾mîñï»{(Õ©ô»&Ðz`±ÊÄž¹‹D0ñÕ®´sOšéþøÐ·‰¦×ÓÏ¿˜é‚ŸòVSg©f%‘ŠH+th îVJ+ä\Áu³ù9º¢::Yl7:‚u²{bÉCtD_ %¯A+ lÐaœ¶ÇÚ=¯µNÀ£a¦ç/oî¦¾Ãi{{ýåöþæbú5dº¾½¸\õÚ7Un
+ðvI§,ùÊn¡°‘JÅÈ*¡Ñ <ƒÒ.¶.r=ÒWtµÕ¾¯¦Åjß#c¤Öv+l«5#ÇÈXGƒÊýÑ‹ÅÄnžÒIfÉ˜[a'z™»‘´û2ö½6…ÝíÅâ*årò¸{9”RÇòê¾euî‘Ô#KÇÜžÕ{Ÿtçä‹ÃêÙòÞ´ç”û±¶:«mÌE*ç#m¶e"`îÅ¶™yŠh—çª4“<Ä’÷mƒôÈ*©nÌ¢‰×£â/Žü×XŠ~Q&rÓˆI¢þXEÒ¢‹·Ì`èš
+)„dóìÅMdÇXßoyÞt-jdÂ<¤˜ÇPbçcVëIj~µžú2FÕFpJæ#‘(bÛz·/ÖíÙÔí}¼ë'¥äÒŠwJn_F]PkñŽž4¥ÅD=eƒøÌÆ¸
+‹LÏ–f_ög´ì ÔÃf iEPg¨SwÜ‹²j®nº wþ©‚~“Dûè³œ•õxþ¼¾$™%µÏš>x­)ÍÃf“URJ¢Ømk©ùªæF›ùz?6óÉ¼š[Â8eL4£N)qI¢ö™+2ÓH×ïTØV¯…óÏäïÞÿï[Ü×¹ç^¤ê—¬Y¡À®ÞVþƒ“¯ff€57˜z,6MA@¸Zµàxþ
+¬XÚù^â]M^ƒN@Ù`†ÍK»¯µ“€?É/’â­u@C’ÙŒÁCâ4€èƒh\XN687à9„bÑØLbGPÊJy‹È°Ü€YM`èH!2q†¦5(—‹f·uÎ[Äâr½s~Ú~‚åª›+o,cqÚzáŒÛîvÄêØ´'Ó^XÀ¨ã™…¯ÎŠ¥k‘¬w8jô:teŸêã"ÏNÀä“_¸žÃ¶›68ŠÜáâbm	«Päm\o¸"…8{µQE¬Þ«Pòp«) 
+ëX€µ°<>e<ì˜:šÐóGjC¼•á¶B¤¤Ÿ‹ÔÏ­ùa9©gŠ9´5#U|?“&nà‰¶f‰¦¬bcHáLF'ð1¹Å^Mßr©5Vh‘V{°SCCk_h$ØBÝM€2·’ôÁ.ÀV¾Õé± uS_\\QÀíf„¹TÈ±0#Æg»æ=°rÏ«® Kd;UpaµånO¤ß·¥ßÿø‡g¥7ÆòÄD;à*¾'+%”,"Å i%[­Øldwb!:Îõ]M°+=žµ] &#°‚Æ[maFvÓ!['›^X£U›SRhiLôPN U:†¦¦z “æpyî1/Öîs¥¬bÛ8¿q]|”õl"i¬§l…XÂ,+p»i¢³;ë[xfƒÔö®þŸx 3â÷ív§€rûÙ€›qpÃßÁÀøˆætv´±Ó«ÉMß*•×ï1yßë†%Ìf¸w›÷›2Ng?á¯'|¼ßß\¼{¸þxûY¿_~ººQäàÍùÞãôüã!y„ß³o›{ü3Ó81j‘ê™€ '÷Š8T"þ_ÉÃÏÎ±ÈòáßÙ¾¼Â¿ú6Ñôzúù3]ðÞ6ï)7‘k¦Ë N‹f%å›Y€AƒŠð:ÔdI¢Çò –9ÇœTðz•\vbÊœ-©OFÐk8DñI<d†T7(2·>­ó–‰¢Gµd1ðz¾Œê
+#˜œcyÌ£Ú ‰u¹Ô]ÁŒÉI/7Õ;äñaðÿ¡ˆ­ø"ê|ØRS:SóÅ2Ã4FºÊ
+ò,Ëu¨¬pù|t‚ö™!ßÞv†A'ÌVŽXƒ%4ZÁ“Í ³þzéðùXhæ6õÍ)hàvLSX5Xd[y‰µ
+æz±À,{
+YA­j~l:œ¡2^„×’`÷U<MÉ=z~Ü±wÉ®bá•Œ}PÉp• ÀÑŠ­œ3HNÞz¨â±2¨YàQf">PbyÐð4Ð1yµÇÕj%Mì‰§æj—¡K°j‡Wý±€õQmƒjµÑ¬'h¸*Yã±zŽ¹ZÂûï (Â½endstreamendobj129 0 obj22171 endobj130 0 obj<< /Filter [ /FlateDecode ] /Length 131 0 R >> stream
+H‰ÌWÙnÇý‚ûó"€’qïÕ<]R1à„†…È h’²p*ÿ>§ºzKÙ¹2Í;‡5ÕU§kÚéÕ:OK4Î¬>Ù¸ü)Î ñf9Ý1ªVo‚4YïYÔ¦•Tð]”±¸ÆÍ 3¿?ÁÏ‰bzM*™öº#ò, 
+1þèCtËånÂì3 ‚-.´O$°w6‹†5Zr›÷;(‚âÀˆf­¿,JE_uªÄ´³ìšÅ³’M¶í7iuîL“Ï‚Æ¯Ö§$`ôÉeP¯´Û¾3ƒž½78Òk=[4Ž÷7ÉÖ«èl>•5c dtZþ7Ë8xJRÆ (@ˆ9›a·g³µÊ¯ˆYJ`H”2»*‰J­B÷­R™A[RÐ¦è3ƒÊ®Áz;œ$
+FøY˜D©[•s©cÙ~V¯«RIDÓZBWiHgÿÕ”¹êj½*Ä0Ã‚%Ù :c³,½þÝÆ<Ýð7ÈjÄêöý¥Õ€;eìF6­
+!¸<eY‹Ø‰VÐbÊNHrXXÉfÅ+üY•lŸ`Jv#ªWm‘+ÿÍ¢´zÒq€ovE6¾YoQùHTX$Y6 Ž~æ 
+VwCÒ³¤[=D·XL®k¹ƒ
+ßl`«qßÃõdÝ shÄU;¿ÁZ¸Wð´„–JÎldÃšôö}B”9:x„“ŽÑ A@²ÞàöüA¶eÁ Ô r|Á t(©Ñ²0È²YBÇ8§›Çýê›8+†Üò*<“5€•éýMÉ•kÜ*ðö¨à%_‹äå\1<ò¥zVP)µ¤@ç3 mÐ¶ùUôVxÒ:ƒ•U@R¶Þì¨7Ã“_£‚vßUòr7Ýx@BµŸB˜fÌ ÷Séš=²!J†æ„ƒ(•BÖ
+F€Å\³/Kq”[Að¬Þ—:ÚÈ¢SÐ\*xº{»ûn—–£ãåü|{±ÿJ«7½»zýtûãýMy>¹þéý]AŽ^]|¸~XÎ.î¯îŽwjÙãçüçÝÇüO-ßìàWnô½ ·Ñón1ðf)þ“`(sËùÞÒ‹ÊÿÎŸðð7|ù7 Ÿ·|½üó_j¹â3þ±ÇBJì­E¶Q/·µuëìšA˜òmÊà§ €„J–ê8"hP “Ã‰ƒ€'‹ÃrVŽ#¥èxcÅ˜|ñæ#~à–"öNsº*t\”ËìáÙÃÈpŽì¾Td‹Gø1ã°¨:Â}‹n>.·;v™†çËü²æOÊÌ‚¹´Ð¬±aõô¢ á»¨\›®”8l¥§çÓësy¹›Ù»?]ã¡ï¬€ùûbÿðøòýåãûû»‹‡§åÏ€ŽNŽ—/^?>¼¿ûi9zýÑwrs}wõêâñÝW/—?²Èß?)òíÓ‡ë"´?;{Vìë‹ÇËwßÞŸ\¿½(²ÁþÓËþƒ\(ºdaÝï*WZ.”³K[]fƒnpˆ;ëX©bUš¿Ê%¡[ºt±ˆ=kSœ¥1«×a§ë@1¢jh8('§Í2©EKÑ¾Œ¦Íˆ
+ÝäAº;7è=`â—®wÿû\ïþ-êÕt»¨vojåS|ÓC)“2ökyüÛËÖsÙþ¹þ™™þyþ™Yþÿ–ã=§)x¾cÌaõŽ¥_)BÃÆ]KfäM	Žƒr£JëBeEe»BK6¥¥§<— æu{rì¸ÒP‚r“ÜØdåíçW°F‚’iÅD­SÜ(íàhÀ wc­Ý­gà+m½]û˜¹€ )$ò¦x*Ñ‰0’CÇ%“
+‰62ðXF^lâÊ‚Ó1ø€aG·é¸ÀŽW$2Ë¤Ìä	m2 ‚Â"¢ÚJAî²ãuÔ³Ò†Mç7´[Ú5.º_4–ã#óEH¡Ê wÌ©a†ƒØÏ¸@’qñ¶ŒXí ËÄ[nÃ5Å²à4;fJÖ´A¼ÂJbÒŠfÂ_±XPA¡³Eody5šf­8ZÐáÁÚ®uðëƒJ#e¹Õå²¨+œÆ 1¡¾uÌòhRh†…Fl­Ñ¨,çê¼¹Ð¼U}©0Ž£˜e›R")Ô8,çW°Í¡*¿?Èâ¬³ÎŽÇ7t°´«|:t¿0hø•çóóZdæxÂ;@%'záÏc±¡£²K™˜%±¥InumäÚ–YaœÆ¬MJ1Ò›j*•ó+(bÇ²D³¬Ë‹›™µàhA‡k»ÖîÖ3ƒùWNßÌ`*K—ÄÆ …¹²èàZ( ÙØ–3áY¦/"ågÐÅ5ð×}´Â|žì=]+x‰šj*(b]"fY‡G7kÀÑ‚Öv­ƒ_‡Ì,æ^‚Ûwµ/K‹^=³Ùi4¤¥ar…FB2ÊÌ Wø¢a»àÂÂ4¾PXì0Ž3âCSjfçX±œ_A!‘Œñh–uà3Ö¾\•àh@‡c»ÖÁ­C*‰¹ý"H™9‡5¦’ÈpŸi$†˜¤¹Du¶a{T`™MŒÊ‚[ÉË¸Ð0dO DmT,(j‰RÙ®´DŸªrzÅ„A¿b’µ³(-²ƒÒÏïð`j×:øtàþL ü²¹;\q>§w'Ð+'ÍKy¸-â«s‡Ë`âR^¥,ì’Ñ ƒðÁèÚUçE-$6­ðÆRªqX,¨ °èÐ3Lše9…½2³Ö-èð`m×:øuÈA¥1qó(CŽéóaÊƒ‚×CvÐ²P’”JcÒÉ°´U—Ä0ôJW¢³X>‰ïçr7ÃeÊ˜´‚š„ég™,¨ Ðˆò¤¤TvY´²&ÍZp´ Ãƒµ]ëà×!L£Î;jã²ì-y7—²–
+‡(õÚæ÷a€øí…¨3rcøªdì«3ª’'P0È€gYuÅÓÖ¤u Å€ÚU
+Š…œÎ£`WŠN¡}2³Ì
+º±ƒlwkÐzÀÀ§WÏýï³zîß>^?›çw»œùçü	øuµËÑñrþÃîhuÿãõÂG,YËŽ³$<9µ{áPÙPå’24æ/ôò4
+¾/¿1ªöÙ½PŸþ§ŸÿÃ—åÓÞnÓçäË8>Úúf;{¿uö ¶õò_¾AŒëè¤Þ’­]
+Ïõ›³,W^OÁ×’Œ¨"•)c¸õ’ÙÕ+”~¦<úˆÍ=™ZOF…ÕÞµ„‡ÂïëÅûbÈ †ÀY†qv5	=— *¥ÕêÅ˜|Ê¼Ã RÛ	˜¬¢åtÇp,Ë š<ðœ4pçØ™ïxÿóE—`1‹ˆ¢œ¯ƒÕY«VSkïP¤òÕZåÀ—¥Î6k•—<*-t°–G6®òbmj5–0Žx*æb8rTêqôÒ…º¨¨ìÂ0GÑKöørZºZ°&ÊØ‡°sÅ\¼—dý‚0o£riØyò$bÙl}S€®fC*4pÊw‰µF‡ÐÔ¢»—…!"}¤T4Y‹°ïÚ`­ <nç´ÌAx+Ûw¬)zuªìÜÅY©´žrw†fó?¶«nÕÒâˆ>Áy‡sÐ\ýß]—:ä"Áˆ8™BÐQ‚ÁÑäBÄ·ÏªZ«¾½÷92ÈÌYöé¯»ºjýØ6éÒÑÎPQqïäRQùßÌv­¢3F\­×Ue°;ˆ”NÝ«½Xy¡N¸h{š¹iÏ‚W½PÅµ%üþ4†lßÐ‹×Ú³k%\]üã¶3Ù£›|gÃ›|!ó6kk„8JQ´X;>/z9ê›eÖFÅÑ°ö°Kñh½*‡áýÚÁÕx0ŸåÝ²c¼¿}.g¾Â(»	†vÁáqÛ¥^p•£„EºÀ•]ãªÍsù|Žpµ€aÅÕºn™œâsÌ6™©6ÚFfßÆQjË¶v5ŒgU2YKwÀÈŒ¹e:ÅX_C I†}!Øªš p*ÆD-r×žCâ:Ú¢°ÀÐ·[ß·}8¼¿©­G§<ë¼Ôµ`t®m÷œ2áhªè%.&f[ó$´†v("0`cí.?ªF0î¤d1Ï5Å|q€+ÜN5Xí—‡ÅPt=ü+’-ÍÌÎ–±7× jtgiÿ¤Ç¬4ô@„\aÓ®Î€*ÉLmë¦.²*¬û¿bìÐq"i(I)ææ<ËÆ0¾“qƒ†Y:vXR'ù¡þîÞt‹máû(U”¯ºáºïÒq_ôäU¾~ KŒŒá`…ß›‡›ž1Ô³Ý£e¦P1â `BtAª„BsÆh<íQlõ	VÍmßi(Ž®p@oÏ$º­÷B•öÈ¼‘îàRêkB´Ÿ­Øi{,Þ« „0>ã¸#Ep²ƒ¹Á®|G˜ÏºŠ.€ÿ1È=X[çMO	@ñÈ~QÐl0Èžé)ÑŒ½ëÍ
+æ€RJöpÿA·íä1kŠ?8˜à9[1Ì¯a–¾r@ï<‹Ác±ò  Q¼6¢=j!nUp¯U•¯u ·Ôì#AéÏ¥ÿw+Q ÂùƒÉxy¬ÉVø¥·ªZkÔ( ¾"0¶x8§±
+
+¶¹T€™N™vFíƒ&¨ØÜz¸u‚,»p“Ä©::ƒ|P]Úî‚‹k Û¼®‘ÔÕ4Hb	Ž3®‘€AÕÁ
+ú4ûÜJˆ¬{[‰ô«'x‹÷q€z‡öûÝýQ|U9VÓ[Þ
+/¬Ùgôº”¨ð‹`Yà‚·JocÄƒå ×[ke`\–\7®ðv ¤2!u©Ç|2 ðq$·«Éð¯B¹ÎŽ¾}ûp+—O0ïÃJ/!ýù·nŸUiéÜÌ­Pxˆ+@¯‹oã<êºÂ j–°YwJYKóx­ÔýÞ«Œ?2‘IË%~Ó™ˆ²ÚnÿÀ‡ž7îŽ€yï«¨5¨jÀÔ#X¨¨”F{ÖÅíg…ð;},j< 5‘Ä˜—d¼(‹êåR¡<ÐÞ4ÅLN Tµ¦!YKÉášŒáä³ª¦®Ïq)\©„A½‡çÂƒk}˜åÁv¤$÷Ñn<ùûPŒ²eû«¨ÙO¾dv+fÎ]Z}“.ÅªoàsTéØ»÷hßê˜“ØÃå³&ø}fŸ?ÇGÍlã@ÕC$¤W…p®z±FÄG×Åz+Ó1Q?4^õò ­y‚ÑgXÓŒ,g8en°çµ¶²­Pþ:+áÚ¼éÆMàºJW·¦ƒ¯–m…<22·¬à ¢Èq~ú# ¯‡Û«ü’ˆ]öÎvyGeúz¼¸ê,{†–•ï}]ü|•’å"lc_¯2Ù*®‰bâšíƒYè>D:AÕñÉ*9Ù‘VLpÌ¸.Ä0\˜$£,‘Ö4{>kÑÁþûu½«rj€‘bšbFÞŒÂ¥dçûB%|hû&¾‘ LÊœs_6d-*¸Ç ZDC0J§ÙÖR¡Kvw:Â©òe›¸pOÕi›¼ßo¾€?Íï¿zªÏŸý÷	£VÐµ<‡åäå?”ŠÄ»ø_ƒ˜;Ú÷_?ÉYõhd2÷Q2•¤‰VùšÖÃD/ÜôÔŸˆ±Î><%\³]æÒVù×b²^¡gøÁŠ‚²ywÅ¡ÕâØò Öü§â¾Ý‡I_ˆþøÆÍª¨£ˆþ—¦NÕèIäu`xFÌéÝZ¿cám*Óî#ØCi¯r7mºÑc³ŽÇ$˜]Î³Þ-½»Ô@eã^àCØÉh¡Šº
+¸´h‰¨hó†òÞ)3ÇŠºwß¾ßq7ÙœpEóå€†­ƒ¦µGpC™] ><=Âóbã~9Àí1v&Ág'uò^ÒFÂ“Þ(ã‹1m¼TN§(R'ÀÈ/àÃÁn0F°Úƒ‹›Ý³UTa|(<…í+/»|¿ç¼ÿþŒýWëZ{\py«M¢Æ—Ö‰ ãp#øöéÆoÍ¦!k=iÒkë<À1·®®‚·~=+Ñ»§Å—À8ã±	^µ‹·ßWOöüÉ§Ïïÿöð¯ß}öÇZþõ‡¿ýò×ßüôƒ~þü»ÿ£O¾üî?ÿôý×Ÿzã¿÷¿<ýŒ?åù/Oa¼q;;Ö<×e`	ïgWX42~D—çê(þ¼ÿ?ü	ÿø _žÇóŸŸÿñÏòü­ïþ×ù“îí°>&ºk,Ó‘ƒf0‹{eôßY’9y%T¹{Ð*]1±×)í«®MÒ£Ú$h a…¶±U2•äk#fºÕ üCå¢$aI¸NßÇ	W´E8Êdƒ®r/£Sfµm€ñyÀS¦ä\	›ÊÕºP® xèÈ†ã8Ú ?œ.«U[«×ac×Fäel`%]¡õ“'@èåhÃ@ŽÓó.çô¿ðÄ;£è”ù£Ê¶Tª¹/»I/VÓ·g†€{ 7MWáÓ¯ÐÚ¤ïyÞ›œ®í4•Ë›!ÀYV~ß§4VÊtºS´ÜIÓ¨ÃP †v®°šÚÀk=Þ¦ÎzÜS˜L}ÚJì:º¬ºD€0üþ¢«/â lÐGJýÁq.vÆ3Œëû3,ÑrKÔRC­{ÓÖ»÷Y'‚Æ†Ì×¤lTcsÓãzSõ%X‰F°ÓüàþsœCl#·]Ç?lˆp)ýÒ;&[Wæzé)·Ó¹ÕëÔXÛ»­æœÓ¥â»íë|¨hµ«<b ˆK^ƒ¾Q©ÆbÛUæUAˆ{;ÉÀ²/ÀãÇé@ Ãô·¼=Á^i†ÕüXD 1Cu…ýœZéwÉ¨B^fÓZd­Ý·ÆjA-Ð93D9ªmŸVßQW‡ÞNÕ¹Áñ¸ÔíV‚YCIàÄŒ&²•¤€}2/¸åa¼óûžÆ5‚Rm€Ó)IšÕb¶Ú½´K`ëŒpz0Ð¶LRvª	\²‚(üä‡Ü ]ÀcÈ
+!=˜2ëéìw‰‘?^K))šÀ"IZgº‹ïµÞ•kÃùG]qV[’îòÙ8UY&"ò@á1%Öc„¼o‚0û—ÃT­Ð›5µènÐÃÚù1(‹”{`ž¾Œ Fåæî‘®ÍuZvD“µ!µÞrc‰	°-èåN*öLeG­‰Öæœ²ÊÒ¸pƒõ†nx’QnÓžP-‹Ìè`ßš¤ÒAÖòñ<'×†ß¡q:=«¢Çr;m¦ÏO\u‰3Lñ²»òä‚Í²Ý’dÂô6šêny„CÑ[?”°a·ÈêÝb]qo=ó÷ƒr@šèÀ¡;arŒ`äž,_Øþ è4ƒ^Ó °uòPwÊ<ZYÀ‹× àAÚ·5rƒr(Eþ€3ßï³’HÿÏ{Ù¶Ú}QüÜïpÞ°v??è«´EPÅ*DB¸6bb)%ßÞµfÍìs¢ˆà)·9wî>û¿ÿ³gÖúàÕJÓÂ)>K®7ijLäÓŒy©ÔW1ObÝŠît³j-*H¬*Û=÷úx„Q>¹!ˆ›t/¯n„xÐPQÃôi(žOÜ2jØ^þœˆìíAsïnó’ÈÚžþÆV1Ë\R0R™Ìt3©V
+æ­§£“ëöòexµ!@Â3-ÓØt˜†#ÖåÃxºP–…‘ËŸžÚÈ\ö–-ÇÍõD»gÝ¬Y‡ÆuõŽi^l^ù•kÛPN£ÆyºÄßé=´§qú°Žh¬!•>>¢òN«O²Ø˜i 
+I\Ñ»8ªÂÂ¸Rq(>ÁLí ô„ýíq2fo¼V^çõ­¹„×nØ ^c[“xa¯V…Ìøèád¿7Q?Üx{ÛÎŠbhlÝ'¡ÊI.ˆîlw‡p¯¥øû§dÌMeØò?áAŠ¡úâøôõ¾õ¨à\d…Õ1H•”#°6òô‘Öý X;§I:TdSÅÌ)CûðN­jWÉˆÚ ±šÂ£è²Ì±¶îy’Ò«¯4Ó,Õ Â¶·0ªÑÆÔÚ%¬ãX%J°ÄòQU:Á
+nÊŒp{ZqïÝÄ»"½åÓý=Y4‰lô¤™úð g8“Ñ§‚Àìs…½0~,o¡nàñ  ¶v‰J± ”Ã±¬ñ>™–BSÊÑoðG åÊ+PCÉÇ>6Ác*¬Ç³˜Š©?P¦÷6Ã””Bñ†ÃË¬aªTè#RÊÂQ°ùZX–‚˜3’õWBÔÃU9]á¬šJÑ /Ñ!Ä«€BXA‘8©?¢à£¬¹Ÿ¿å9…þáEYêŒ’Ã* a8k÷IEµ„%–¦î™Z'û(WÈp9Ö¦¥¶Pãs{*MÁÞCDF¶£2Ü@\&ƒ¬kW!n,-•º<öÙ ÊÁP~_‹é`F½Ê4ÔˆX|f£X†™8AkÝ{ ûÔˆ¡w=H2Õ÷1âVóerŸÏm©²#è£VÎ.ÁÁäí˜0mNËq-€:¼·»*+‘Í%ŽØ ïÂÄª¹>¦¢ŽIèvÍ¡Êàm™Ñõë¢ýùf]k½@˜éïç7;uâHÛ…îùxþÒÁ}&SÞÍ²‚Æ¿±0í­sh“ "©µm®%ä¯0›E­&Òïc-,Ûµƒ‘£sx+©;á®vú±uI.Ð3h$Ç Ï–jõÖ›ÛÐÝç»h0fˆ4`p˜Ji-?À0nœ	ýP)&,¬³øM@±Ö²&¤-u-u®.B÷'ŒmUÓ9ˆâ™z@ªt˜³ÓÃg–Ýo'38"¢_[PÞbŒµåPƒ II‚‚ l«ðÁæK`‚ÝdÕdØƒkÏN
+cî$÷Z‚¯G'z‡_"óxCëgÅJèt:FÑ)bý¤ »ƒwI½N­…æ»ÐGÝ£HÁEpá¦µ m€›±g¡Æ–›*7U
+‹}*'Y½IëœµicíØÚ˜sš´oÈw›s˜U;LÝªë¤-ýÜØ·è­¨©ë¸
+óÖµÞQÇ°-MÓ›c	ëB‚FMçDñè]Æù®Ån •‰9É_jÖQÝ©¦‹7ê"¿ÁBÓ±ÀäUP\è?¹K§md¢«àâsðGÙŽÅ™ã›•£Óõ×
+ÈÒä"¸Kõ ‰ëcHºJ“ÙejÐ‘¾]<Ã©à”yšÿ"•¹O—t„ÓW¢š—`Æ¤BpÞÒ‘´Cˆˆã#° nY·Yx[ÚJ'èZ˜92‘±<a•9Ú£?½6›¾@m@·XŠƒ/õ¥i„VMèá}˜ ³q‡Ú=;a©¦ÍIæZ‰®ð ÜÝ[8ãZGññ+…6eŽˆà¬²4BƒZ“Ä!dŒ„a@óbª ›M2+qxyÕ*“÷û•cf—*ÍÄŒRü>Æ0¸Së0 x…Q÷)ÁlÍÎ®x™"b5q=Ui%¬™ŽOÔgŸÖ(Ö$Xšx&\mõ3‡“"I9yÞºÎ—aÕ4¡D¾oÞjÞéæbª¾µÁÇ‡Ÿ=<yñ=~pB
+J"Öwš*Ü€^:ƒ´c±pb¤
+Îúä…w¯@•˜`<oô›ºl°,v(M·þ›éªöY(m·×KZ@.Š‰pŸÂ$â]6„‡°÷K84´ÑÏ] UÜ¡†$R¦·pwø ³ ÄKÜžý¬&DòmÓW;°óŠs
+ÛG¡ñd¬1æáñ$h‰ùñMó«€m2;¨ˆÀPªâXK++Jöl:ÛVžø{)ï[Œ.vÀl`´£yyÚ¬pe›å9¢Ä’ªÑô\$‡•³åÇÜÿºƒ¥¨¨,CAé•díDË‡_ü>1[öu®ƒ2m0‚¨þ0NÙò®‰á‰¯kj:q±0­›4L0ý§dÅ4Ò,ˆƒpœÍ0¬®¥uÝ )KV=èŠ¤††;!¾oæðiQçŸ¼`¯|ñìý‡¯_?~xý÷·/ß¼ü¡Ï¾|zùâ›ï_¿ýËå³o¾{ùîÕ—{õöÛß¼üðÝÏ¿~zù—üòß.ùÝÇw¯´è§øQ'®eßd'â¶Ø‚+x~DÀÚ}mÃæ=€·H½y±Ö…x‘É¯+=˜;†þ=Ø–ßä44NåàÐ‹.mZ5FF!&TÌjÝ“¾­‡ Œu”z»l†žÃ+‘ë8æÔÁnm…iØålÐc”ìW/#ëiPQƒÔböˆæ†¤Ÿ-  =gÙa+^|<§ÙÁ(œ,hÞCñ›âA¡Õ‹O-%$5?x¸f9ÆÒò˜ãæ¹[c+ÞôÅ}§*ÎÕ¥ÆÑƒ i7[`L›êâ:Ïó¦å*gÛnÃ?XËºÍC/b-*þŒ38-ç}äÁ$O%‰vã:{¶Sºâ:‡*;Õ¨ g­.{¼ÿ«
+`PŒ¸O¦]ùÐxË;{ŠùV5Q&³¦ªØÔ×}&©e`Çà&mÅiëÝ0Áùà‡ Ã-pyW„‰!]Æ`×#xõ!¿5yˆŒqP ñTÁ5"ˆ÷)7‰ 5åÀfÇ^Î(£ŠpwäfMKÊ	|«§ Â®‚¬MˆÆ«Ð0ÑªÚÉïB¯×´ä\· o[!§e‡¢Â{«·Û<—uöùàõI&X2ÖÊ£ìí,Ûä=ßÁq~4é?ô4o
+
+=íL„Ò¨_Ê%ˆªCÕ"Ø“;Cª#ß¼G¯† “³a;­kÙEÝ9JÖÌ²øUdô`+ÈX>Ï«SB¹W˜³$s!ƒþoxö?õ†ßãg_>{zyþ‡‡työŽÿÃÏó¾Ç?¿~øo(.]°Äþ{þ¿üþŠÐ—vùÕåJ—où„ßÆ¤öÏ¬w'éÝÉywSÞÝŒw7áÝÍw÷ÒÝlw'ÙÝÉu÷RÝÿƒéØ•û¦)9Ì&
+${³uÔ~Ë{Ü4¥¿ÖêK§eªßx­!ËU/Vø]G“bâ¼¼î»ØTÞ*„ÐMæÝ¿Þ[r—ÈÍÈ4\kN©¤ùÂ¹(ƒ
+ÜSÊ+Loµ=t§¤€ˆI¼ÑFio{ûMBßñôF–Nd P|ß¼¥³(×2KNÃ¬DEM+ˆÇZ¾)œVöC6$”jƒ4¬¢¨¬´}-z•ÅÛÐ§46ÕþÜf˜¶°­RN{:–íÜ`újþŒ¢¦)ØWÊê³•Wœ€a{ÂcæØ kWÓ*Ç[”K2MA°âZÎÓH	#‹¥@:^ÉÕƒÎ¶l¤U×ù>²ï°¸ÒˆÃ–Aô|ö`®Ú ªþ?`¼(ËûpQ…‚Vé‚¸§Ê]&‰’Ü8½Š ¤Äu¥×}ÿ­Šìj¯Êü‘H< DãOIÍ9%¡p¾·Ž-ZEøÛU˜µVòº»’ôaé¬í†ØhGÈû.­ÅÍöïw©=]¸·/}Mì-V,Ö K‰5Š½t¸Îò”÷¦ëBÑB*CŸÕ«æ¨bÿ£f°ÔlŒÏ€³vë¨ÁÐØ3»ÁïôÏ-”šJÌéÚíK­ãgqÇñÑíâÜ¿ß)0škô÷ëŸ![¥p€ž²¢hù÷„ÀJ7è°Y´œ¡ë´ó4mgL+Æ"¼SÃ¶zm#õ^)Q1mÔåì?~þDRþDïû<”Ûj\Ë§á¨%¥T:c·Ù8ìéùÞùk1-Êk­Œþ˜MØõ´ ,úÝib+	v9Œ2¤ÑëYŒ{EëTXŒ¶F1.«_p-®Û<wVÍ–Útx]£·0ÊïìˆÎïT„Pg„Ç^-dì¦Œ#’vÂuAÃvð©? O-€„ôôiÓ§H²Ã3Â€ðÈÒ/ A(o‰!ì–)|’rZ«‰ŸNXÖÚ']l?&ÝõD©S#Ž„v|hÛLtú£Ÿ ÀæÞ<$‘€Ò•TŠ†«âÉã¤‡ßç}–U…ü­Ùß_i
+É¥sß¢ö(Oã:×ØvðjòÅ¡ì>»û4lp_Ñ¨lê¶o‹ýë§\•´ü©%—QmkkâÖ‘Úkÿ~Œ¡ç/þÏ¤Q ÍÊD°í ÷µØD¬ì2 Ýª\£FXÝœKê«­ßôVln¨ÚÊG9(½¨a‰5ø{¶„M˜£’¶}½§Ìúó4˜½y•ëíàI@WÃ`VG{¢ðOrh²àT“I+º¾ä_×ì–øoMEãÚòúY$/úú³}H¤;»ÿ ÖD«Ã4Íé—Žç‹Œî¼è7¤vJâ­´%¥ÓØR¦<yhuŸ¤‰ÔÇÜ½£Ö|p§ˆ2U,³Äžþ¶eõñ­d:‹¾ë¨MóL)´³ÔçÌX†ôkvî6ŠzûªÕþ¯¨CýçI@H­k,XTº0Q­ Weã[®W
+é?¡Œ&êƒàÞºÎÇÅ´ÑëÌ–Eõô¡‚¯ê|Ûšs¦5„ß^o£Æw`Ò¢><ÇëË©àJÌªÂ S][ÓGzkf¨Ó®äjê
+~>3˜rngt òykV«x»]Y‹Y7Ë=WqÅ’Pœêëûü´™L2_½Tø®bR4‹sßá/Xì›’‚=ÏèÀ%#úâÎOÃÈíð°{fÑBXüƒ$¤#"	ÿI0"ilÿI‡É´·i…$ˆÐ9E”ö3|VÂ%]Þu	²f>Èœã	×ã’/•)§'RîÍŽ9Ä*ºŽóL&úÍ3)iÂ¾?:utAÉ3ô½@R*À¤çRÞ$=.ÁédÄDÔÃÂ–ï8e0ÉGI"}¦I6„´T™oø$¸À)Ðù½{ÆzÏæð AM-,Óè¦!Û¾ìýÜsNáéÔÝêI`ÊsöÞ ºé§ØZöý~=YÃ:×í¹ŠRríÕ®4¥\?¤F¨e/ø~Z«LÀ'eþ ‰¥"Mý€æi‰1{0„t‹ív:+6Ri-õËŠé	—Ôdþ=-1³QµÉÁñ,FýS?¯Î†¦·ö èW:çH9¥wÒA•ù5 Üy%{-Ðu¦ÚJh€zð¼û·P¬„ãCB	“xJ=8v…¯#þô ‚1{[£±Í(Uf·ÊÜwR‘ij•³xBÕ@aÞ¥|Â¸Úµé•t­ìƒâZU²®‹™iö's¿/ÀAazÜºž¤_0ÔVö•_UœÓN¶ L}+˜qZä®7.âg"éüå§N¢¶¤éêÔ¤w»5.Ø–h'Õ!ÑÂü¦úî ¹s¥…ü¹.8‡ðš<—ÝB~EÈ»ý?eí]SD0š£tôæ!…²LË°…À£V Oú°4ö:Y–Ù \Ô´¡€¢„ßG±™ÌÓäûSïÌßRgÄ:æÁ‘W&ÁR†×}¶6PTPRë/« ÉÇäí‚C-”!†® ¨t–•pÓ¤ûÒ“$Ž&]4é¹.*¬'¼×åÀb¶þ[åôž¬râjÊÒ60ûì²þ »HÑçŽî'”ã‰ØÍQk~ì¤BœóM|„@$
+õk¨@Ì=©´¼•œþÎDYÔùÀÿ¥b+š÷°ëæ”0ÜyIktÐªÆ³ûãqHE‰“7ù’Úfd‹°ºjx8-Ò…1|’Ž6³s¯~T$4]é‚OcJÏ¼iÆ¶üHâ]néç–vÌ‚¶ÌD’Ü¡ý}E Œíëï÷Õ$ÕÙ·ŸµdÚÈVÅ:¤Úßb‰©vúÙ5#?J}‹oGwÿŽ ›/ÿ½éø²Ë|S)í‘rø¬Ú
+äÇ‰ÍRjm6¿°Â¢¬öÂ?)ê@Ž=*+¥õÈ´þÖzTÔ{W£j‹NãÝ@Reé–t*¬¹u]yjSeQ\N½vŽÊ™§m:©DiÊ)O;M(ùýl2ÂX¥"tLi‡Þ†¢9»x4Z•1’Æös¹YõOezçØÀúlz<YœaÏ|?/«È÷œ!‡ô’3­b^B½ÿäÔ-†…#ë	ºÆ™ÐYCý;:ÌÌNøóüÙ¿$ìõò-àµaÿšÈvÃÔnx«ßæOÂ–3'o¥!Â{ôþº¥ Â
+ï¹¿¾B>`}ÔøÓ³Äï;éËjad»{ð?{¥TÀ2ô“#0Š@šÅ8œ€	l˜•ÿGÕëîX¤Eñ¼ÓgÑ2M&6Î{A)íx1–ù‡oç®P€Þ½?¿¿E£NHèÝ
+%8ÓšgxcC&8óS±èf"´MC@µï%„ðúý‹ )2lX,RèºŒDÇê§”3®4'xRoŠ«–Ç…èD×;Û—E¶4†ñ÷.Æa:g¾^x±…aˆ6©¸sGq'T§¨“;@­â5i­.µØ}ó: pk÷\cUFÑšó­`F“Fé‡Æ	^zkÀh+£Ç”ÝrÖÓbO'¦úE´ìHM{Ÿ³iÁsá|0•4gë›fµµ“F>Ë[›³ òò`ºB¶È(™}€¥OûÇ1±è#÷ïû#r±Iûþ†j¤J¸ä[œ7<ô‹‡>Û‰,½j•„ÐÕÄÔBI¿ÇˆUy¬ýQÏKž÷Xo¦{1GÏØ…"<›·±çLÿŠë¹´R'¡ÓrÆ³–ÛˆÙ)glËuêcËVwð¹n?OvúYõ‚¹‹f”Ù#™M(_ûÑô|‚"sUF‚t¶¢hÝ®pÕ^jf:Bù^pítÕÙ’†Æ]ua½‚ËÜq(0)þ½ ã93õ{6æ‘¹¢ŠünÏwˆ ëK	ñ€¡hýþa«¯I4tfP¾¯¤Øó²ÈÉS¤è«³ ä#¢îp4˜"o³vTš‚ô«Þ°„¾)ž2¤L[Z2è!X˜kBkrm€¶øü…<äâY'D‰D£Ëµ*-ëPâ¢ûãx¦8£mþQ<q¢(ÚYþŠ^/ÌõD¯¦ÎÕ½†ÉY)¬rweÄBÏÉ¿Ï†¶ãzû'z
+€	nÌaRH: |#)°ó¿H"¤6y”tÂ|?A%^´©ßçáèºæ7Ý>r[¤ ÛYE¹·°óƒÙ¯¶Ýª®+Âƒ¥6§/ùM%K¶T%ë~¡}À˜RÑ¦JE¸"dŒƒ]q8B|BÔ—öúí7ô©ùŒ¼çµó¶÷áêcslÉÇÓ{¯5×\sŽ÷(‡¶3ã}áâgkÆÞ“RA	qz]®1¡Ž´Ç'.h¬G.ÌŒ$~kŒ@À‘ý
+×IÖT&h&lÐZ‰}A"­§{„ææÄù&ÏqÂhø>Ê¥Â}˜PÝ4:;
+3ÀÄ*´ MÓ8ƒˆ™wÞb®+k´ZÆýUÑ<ê¡'»S±YLÚT»öˆiZ D‘@ÕXÇ½d8ˆ!BÍã¢Â:m:?äžÂ[$|ÔæT_€Z¥jƒàrQ|nPqãfQ.„ºv"k½’¶¹09¹›˜0ùnQødŠ‚>™U«`8c_G&òUÒ!hRÚbJˆ3&.ËV'(“aºœ©âh%™AAÀ‰1YäË#SÒÓ´½vj:2!‚ÕX€uŸª“bAœ$Œ0[ˆþOÁ¤Dwâ5Æ’b¶jWuÁÁ^ož‡ÍÉµiùÑÒ½<4Z9 ÅˆAF•}Ô‘(U/ !è Ö¹àáa-a”=¡3Ô`ª³–Vp%>•=)îÔGû(†´‚¶xeAˆP³Ž˜ÇN#›¸
+„19Db”‘´ê{kK¨¡" Vjœ $™ÈîÄN¶W¬€½Wªá ÃsQWg«·?Ýxrpeç`ÿÑÃí'Ï‡‹­m¬ŸÞ8x²ÿðÞ°vcoûñîåû»ï~±}°wíÊúð+zäo|äOÏïÊC¿ÆßÙÍ™€ñüwë9~ÀwgeX[¶nÍÖ6î>º³;Ð{¯ðtŸD‹o}1[…A$P|r¿Ô+›üÑxÖÿ1nüÌVÝ›?°6¯ÿÅUýÌVíÛ¸vxñÉËWÛoÌ?Ï{ç—ë†Ïgd@;QÑˆúz¡ó’èfâ+°}ôþï¹á:ÞèhG¢Fþî˜^±4~ÄELéÉummh±û“:<ã.ffæëæE2{z4hq8$Ö‰&ZY47 ¹‰i"3†½7ÿ’ié3BÂXƒ'Í‰ XØr`Ÿ˜Ás#~Å¨­e‘±„º¢ƒáÄp³œÀÆ–ö)æH·'|¯<=û0±‡J•ýÂsN@‰fÚ•)Åu„]×ÍðšcRƒ)l±ñ“‘9qSëªFø‘ÁYç*¨ø‰ÿj•Ev.nÎ,/Q 8Al†`›+z)"«B±Ü€q92+RØ7†
+¿1{RG0/ÍD¸#€N*bÈHã5&jèÝŠIá ÄYÏ‰:Õ¤Û;ÒëŒIibj,ÚøDŒSô>ÎìøN*æ¢Â§'õU“¼ß‹.•¥7/ £FV«¶ ºxäü#ï·jêÇì-J’¼‘š-y /ì8{D½>‰”pÚ$¢Bhú¾ññtÕèÏQÓ±vBÅáføôÐaì"Ž\ÖêÁ’Fñ*€¨*wO¯#AaE¶Vô6>Aä‡#lo+fAp© Ä¢aRLÒ§®1!`QÈñ¬‡BŽMÆ/OÝ#cˆ“ôþQßÄž•µ±¨'ê™s¦ÜÆªE ¨Rìæ‘º9«,¤ˆ”GÜÄhr¢Ü¤zŒf{rIé.sÅµµq~ÈrÑ^Ñ£*7ùÄæ«›“ùÃu¤*Wèq& #„WUa’ræýIw¶
+¤$uÈnó«äã R%¯äjc¹ƒE[–Uƒà<AåºÛ«„ÁÍ‹=ÅÍeY «:2…Üo\ 
+¬QRi×žÞA‚ZqUF MÊýJ“Ç¨„˜õ@$ÝÂªç«&a#	+™VˆE¤ê¡Û)ˆD¼H°È¸&+Š–Ê Ê“ab›G‚n(ld¡6u„Ã¨W‘"”›nôPˆ5•€©gDqU^7ÄY‹n5¥­èTÁ‚Y)ˆžt<. ÐÖ¥YQiàŒ‹^sÌ›ü*ø©¨ï£íXTªtºùƒÁDÊ§J± B‚ÏcýíY¼•Š”8ŽÑÏ6Ã5ä'SQh*BHB+x©ÙV•	 Kö.°D`V{”ç -µzH57î>è×˜ZÑQ!Ÿ!úÕGAp´·zB’
+=*ƒ ªkÂö`ì¬›ù Â0TMŠ»“…î¤#Á‰ìÕ¤gäLLqL¾YQš—ð-8m$›¹+Í43r©ÚR¤`Zóz ª$bÀ`WÃØ¾‘Q¥QODÝ½Ú§ÿ”ÿsÅÑD´:_>GJŸ…*ü@ûÑîoE•ôdÛ$8ß½¤?S@§·ÔÁ¡|Ò“Ø¬QPÀ?(Ä.ieè÷ÑÀTAö–&ÖNDês«¼VîÌîÌ‰Kò9£ºô¬J)û8ýK¥^4¥OÆ4ä¢)I	•
+Éu¥U”ì¥#<‰«àeÆ=Y>áŒ©çËä’6“Ü…“)ºj–6§¬AVóSèD‹¢ëŽP(ÛWÉˆˆ#8ªg*ÀÇÊkz¨¬‚³Ý[”g3	f•~½JŒñÀ4E–FIäçy<‘”È¤<Ê¤WË·3ûZIÕe†t]îhE««¯Ñ¨Î;«ktAYCuåÄ@Aï·9®§©ãhDfYà»ð”Á4êŸd$"ùDoTOEîÊiÆ3Ôh%êVð!Ö}2‘„^K•rð^™6{ÕUèI^gÑ¦u}®¶îÇ® ÷©VÊ&Ô	g¸®A’Þ‘`J3š!pÑd$‡>ë’L‚¡ëF,9M«1;HZE€º®¥¬B£:¡.\_fæbÆp´ÿUj†"¦ú
+!±poRX4P›°DôU´‹]dÎÄ # 
+÷Â,,;ëÄÔAÐm„,Væé»Y4SBÕ'	æ*]PE6IrB[¨ Ö§Ì}g£3¬9ë³¥+¾R jø£¸Ûmð$îˆç\R+‹ÁuÂd-N:¤e	futÿ<^ Ç‚ùÒþ4-hkêÃ0
+…`óÒKv.J°¤¢ó…++"pÖÝGÆ!ŽöãÄ„¬Kætº‚3E‹:…¼ÖX2Ðö=uƒäÛ¹e ¶LèMÑ!~ÖqdcaxEù&ÔE¸uåA ªóçñ¢J«?yµüt‹7g}X[¶náÛêÆ5ïnÿöáÝÏÜyt_¾¼{oÿ¡FÖnííîÞßÙÛÞ2lììì>}º>sÃþn=›}Ãü°ñ?Îýþw„±•Z‚Û"6ô”§ŽpøO¢[ÏñÃïñå¯=ÒðÇáË¯Üp—–½Î3ìÌï44`Àƒ—ÂÄ|t‡rŠ¯`»’y‚
+Ö¸›,(€„IœFá”v\è¹%0#›é…½æbš/;…IÄ€ûuÙ)xÏ7m…{&Ñ?¼–ÈÆCX˜—<·ÄT™i¯¹˜¦µùúÚ~†¶ø†®•îñÞŒäX….ÊÓU¡+òí«û÷w/ÊWîëÛOvŸÌÐIxæw³/õnÅÈ$_ !’%ÃÖÞ›ž <%ÿ¶!âL =ðÇÍVWyÇ+ÛÛ‡Ò{Ÿm]ûÙÿø\šû,òür?—Þðyï	œZoOàÒX$“NcñN.³ÎrøéæpB	,žÆ‰&°H§ÀÛs8ÎrX$‡ÓLïÇÆñrXng9{÷eåp–À)o÷Ž	œDª'”Àâiœh¦q
+9¼=C_|¿9,½JÇ+ÂrÓ8^N!£æ|ŒýæðêâKIàxi\Z çO:q—³.-ï:ŽÀO%‡EÒ8ôõE_<Û£ÿíO»˜G}ø¥]NîNI`ÁÏ{O`‰i¼KKIãÝxÇ4–•À±ÓXnGMã$v_0™e­ÿÁÜç>,ô9w~e6[9¿ÈÓ®|¼ÚÚêÇ+þèÏ/lî}ûíÞæ/?:X+nþý_ß}÷ïüeí£CV>÷‹ßüí?ßÿðÃ÷ÿýçŸ/¬üŸ÷jŠ";ÃÎÌª¸¡Å‘cíÑªáRåôôýâª[ÀHDw„5Î
+Õ#3ôPÃ°.¯ÆTeÙ«,¬BƒÊ
+’1©}Ø$&UyÛ‡Ý÷äqó’ÊCò’ª˜lòŸsºgzn=¸€sžÿ|ýŸï¿ž¿Ý9{kÏ-õï¯¿þÏ?¾øé‰½°u]kû/øðÅWÏíw'ñRXàð×ÿÛ°íg_þóÅ¿6bø¬wéÏÿËgðÙo5›þì‹•T¨r,vìxíàÅ‡¿šë6cðDøîRÿ»6”;µgo­&«6‚õì=9ýtúdYØªÆÑG·ÏÕ½æ¥/×´÷¼pï~oÃ:òÚ¿w—‹‘`Ü½g×úÂøõÎù».fB˜ï}þû•»ówàuûz‚¯vÁÖœºþù—¿¾_•¹ï˜ùìÓõ†+qðîÞÿFc ÷þƒþÆlóUi¹ÔÛÖ{wñâ¡î>óU7E~rçZ÷¥;F+DÎWÝÜ7ûäþ•ÐÙžNŸÚçóæ^…Ú½ÕM}³ksñ·Ž¿øyÄoE¿j÷æ§g÷ÑÈìÚÍþ@íëß»°´~•:‚F¤ãMô-'ØWÛ:ýd®¿™ñùjÏÎ?_§¾sg~~~áößuV”§ªaxy%`|jê•;‹;¿poéáã§¶ÖújC3ÏfBu ñì:¨vØûwEFÒ©k¿\nÈ:Æ³Û?üÉš•ãÞ]{÷[V}çØg^ì»±>Ê*†Ÿy¾Ô]O{<¶³|5ÚÔø9sÅ¡²kñùÌ©šÂ€zíê'…»¯;{ë:×’ÅÁ¢eÒ­Ç—‰b…]Xê?¼³(˜;÷?˜ïjlŸYŸ9}`OÕNOùò½‰Õ[ç5¯<Süu¡VùñõÖù·ëB3ŸÞÿàò¥ ã!¼Vïž¯/lL¾úó«£U{†×þô›WßÚç%å»TlQ± * >\_»•–å´§ëòû`oBÍ³uŽ…Õƒ¸¢ óNÿö1É”	$V–/û!o¼¯¿ùh=­(è¼ïÍ=»…ó,wÓÜ?÷dš¦w×ž]>/]Ã©~ço]y¼¾ªº@ÿÍµÙÈQ+¦Z»•8ÝX_Sµ³ª¦¾1”˜[›í+Ùà1øæ³Ç7’Ý§7ž<?:³òd¶¯¹tƒÇà¹ßýqýã™dbúîêÓåéHS¹³ Šþ½é×ÿð|miõéêÝéË­GÊÐLNt'gnOž?é>xwƒM'Ïvvž=ÑP_SaäÀ¾Ú[‹[B•íMW¸Ç½ùûý§Í¡‘1˜ÈÆßÒ!Àïnc"K3íÌ$¼9Ô_úæÉ;ÒÂàK*ŠL1Ëñš„®0–Sei‚*°º¢ihŒˆyVQdÊ<«‹²Œ’XÊ+¬*ê"ËºªZbžy¤ÏJ¼®S)§±‚LÀ’Àªª*‚¸‡áQË8°	R4Ž4M¤¬U4NÅ¬DV×‘²rˆy`hJUæD	„ŠÎê¼Bd"«Ê|N%6É¬äòp*«	¢P 0'´6§·çÄ
++ˆ’„œ:Uåd%s[eòh: ƒr:‹2ƒà/p&ÉñÙÈ*‹¤ðÔGgGNb5] ÛHÀH0u™ce™Óò…’ÌJ:'Pž9±¨Qµx/ˆ¥*aò`œ êYÇ‹œè‚Äª˜—‡åuHUÊ×šæ1pˆ°E³ ’¦’d‚0pÔ{ Tu
+ÔXM4Ôæ¶¤3¡x4O™Fz
+‡‚f5µtðŠ¦ÆÆS“æš1Æch,5kFÇ õ&|ó«CdEEÀÛ*Ú¢¨Xy(@,%Ý!Æ©}ÑQS3Š\,yå˜„o™Š£Å5Gä¥ªŽ.×‘—ª<ÿ ö©>ì0ù[P ²kè)U……/[‡ÔÒMT"U°‰Z´}½‰jôÿgfkÒŽnQU’…MÕ%Õ°©Ê¤ÛTmÒ¤ÛLuÒ,Ü\}ú²J=^¢F©±%ª”¸ ÇPÓÓ4ÆbCHÕ­JÅ1$'ä£”(d?æ†OÛž©±ÁT2{øt¦Ì®tÜÌÄÍá@€Š[cÃqÓ¹ÀtŽã®t%'áoxp4Í0M-C©ÁjMONŒ wÓŽ¥Q8=K7»¯!ºØf$“ñá´1>ZÈwS©d‰h<ƒº±#ƒ.Ðf`š^Áøö¤‘Anx… 6ü¾‘tB‰ªÒxÁÆWÖ-È€%ª(ùÊwÈœÍÜ†öDLDETÙÐVð¡i ·cÆåRXÖmÅÈÇžŒ‘vàˆª"ð™É1ÃDí±XÉímT{r
+ò µ,CAj`yx‡™@=ãDî¦ÃˆªP:5n¡¼Âf—‘ÉƒvÅÌh<éŽ!ªÚFŒt4eT€¶OÅÜDU… À¤»®Iãƒ©²˜\ŠöDÓ©d›‚~h¤ãÆ ¸òí˜9œ±oî">2Kl¥ y•
+À5
+#Pþ=™t*«|{ØHäƒˆªRÈ®TrÊŒM@UÖÚ–4&&âDU4çñòøc,z›KÛ	’×L¶¸)•)9h>¹€à	BG¼L>"G¾/Ü¨~³s½„l­"^E’Œ?xÃíÚ–´%«#Q“9$¥ýnçÖ¹FnùZÎn«Á?aûvÎuV²3Ø«PSaâ€·MÛæN"º-Ò°·á£“Ï¬ÝÊ"(î»ÀÊqŽA{œ («‚álB0SÃWxYÑvSgE,‚0’KRli`§¬Ã¼„+«tU «ßÐÉ%ÉçŸE.üO-u ¯âER9.$ø/ë–5šLl üY¢ÅŠP–(À³ †?ù“U£Ï[jNî ¦¦tÆ®dP8by­‡.ëqü¦9Åm5)|2ãCÙÍ»ªÅå8Ñöpö2H²|LÈ²
+ñ®ÞTxêZÇò~¨<RÄ­w¬cÉ7C¦®¤œÌ:ISVR¬?(@bZu~Ì>[JÓ9­åóäš ‚¦ÀS’íRË£½ÀD-)·‘Ž¶•­¥äà”›À¨1È¶F"ûM½OøÓ|ÞL#.ÃÂÝ
+HN|œ®Â¶sÁÓfýÕzƒÎ¨xþÕ’ 3¼EÂÙæ^5‘òƒx	r‚#gr½‰'¸•5Wn¸ÆuG¦ñhQáœ‰|Ù©p…t;çrÎV¸-’‹Iä©§Ä«…2åYÆH!o…Xè\‹2psÓ©‹qðLVª‚…ù—u;«èÏãcIÔ4AÄž“áé¹´ýÉ=º'™æÝ6ˆ°d	õìÔ°ý&Ð‡PwúrÙÕ½F”\°x¦M|Rkª$ó´i¼„q/Ý4tº-¯'3•ŒM0ÁsfêŠI~ ã`n ?xNf&âC1»Œ`ÚSÐ1&ØÍÄßÙà`[jl?²µÇ“x`9NNõ¸‰(€J›i+´ ÇJÝ3M4ñ²7m`§V]î¸JºßŠƒ})Ó€¡à8ÊtÇ¢©ôDñí–åpW˜±)Ú"“ŠLÁ³p1úö«¶7qÿ‚þï½TpÚBB ªî$èûÝUEÐm{·ª›8àkp"'´W>Üo?Ûy'MwCËn·•€ÌŒÏø™yf˜è‘Ívçàã­L&½
+»“½Y`ì€Z¼s½‡¨Ï j<tô€È…irñ>§û; 9€Ô/ð¯o#b~ƒb}â¡TÊ™Ä‹dùŠó®9z ´µgo‰ßöm?åM`–¸3Ü‰®+t«—½0™ù(3[y¹UæÂR{—¼›‡˜sì¯ð­\*¾ß¨ÂTx¿;Í£‘1çG
+±v¹ÂôˆC¶¡¤l£kP_‚­›eK¤TI‰\ãUØú›&kÿ©ó8EÐôêâx‰cµeu3à_f€BüæM.±oššC™kÅ…WmÐ<#>¨ñ}Æïú*¤>Äv"-qÝŒÉÙã‰Í—-ùvHŒ¦ÐäºÇÒKË9õÎ&âBÔÈÇ;{N¹@ŽŽúfIÕ3lú:ÄYîÀÕÖ¾ÍkÞ.¸žbŸ2+oÝ
+!vùˆ©C“z~ÐLK¨ËâJVº®w"ð@2Y]ô¾2*ˆ‘¾‚
+Ú8NTJ[Äv²ö
+t·Ö•»›œ8õLè²‡±+2v<°y–.¥öÀ†žð¸ ¯]9l…”aBŽðB¸ÒìãÈº7:8;ëj‡l…É7ûùûû¡;¢¿¼_à_•Öö­½+œ<ÿ¨º?u™Ýûžø¥Ÿ£Û½ÿ~c±¯)‰Ÿ\,N(¹XœPV4#i6‡ËÝk+ñû¬ýwã™ŠK‡â?¦"âÿøýÙqŠüñ|±xçÐ»Ï…@¨Ž,~a Žô§å!ÑŠÊüšxî½5
+Ÿ#pâ8os>úÌ:øµŽBÏmnûwq×ÐŸ²h×>ÂPb‚	e¹‚XýèÊu°'5Yjñï–Þê‚=­ÕÐTÈYW;áƒÏþ„mØï¿Àœ•6ž9ˆdõ¥ŠHÜ+Nº¨§ˆúá(’™U:¹YE’"‘	é}áø"Gr!.;lñòt%ˆæÇÎ%mAL–-ÊõÑñÐIß`m=uz2œÙaû~*lu3Ø…eyÈÆ´90etPÊêKi/&iÇòD:©‘`fãY=à‘_ÿßÝª™¤!ÉZð©ð/]kë(íNWe_’¢·V+•Ì*¯Eos—õ–Üæ_ªÆŸTî9Ó)eíÄÖ~…-½°Š¼©˜É“êRù5Šÿÿ˜"Ý[à>—÷¿˜ž7ZÑ»›¨èÛÛµ]r»Î‡ÔæyÃû-YÕD^u¥—o¸¾º>3èÏ)§—J™º?Ywé"±ùvlI[À¡Â¢,{ÖŽl»·gU“	¨bÏµáSð˜¦Ïpc€`{wžcÏ}!TÚ)é569ƒ/IOžLýÌCdÇ¶iabªGÒ Á®í«.?{ {!ººF—ºuy%?ªÕðcuð¾¤x–Cg9hÇpâþ0µ¸¾ã*æG+YoÉÞG¼âfÎ:ü¼ô*%Y@æ³ÇÅÈ[M!t18˜ø™ÂÉÞh:3¼Èæu|è£ñ!šP„¼"‡8ØˆÇ$Ï€6;ã14|GÌwš´¤ j ¥3ÕŸ˜ Âí®VowU¸E–Í
+ÏM‘ð¯gƒ9¹,@ o;ÐÏaa07îÙ¯”AB£ÝØ¤ÜÀÐU=JñØ`Ž­8%Ž_5é7ºŠ¦¤™¥2|ñ¦ì{ªOõ¤úÿ …Jßcendstreamendobj131 0 obj18364 endobj132 0 obj<< /Filter [ /FlateDecode ] /Length 133 0 R >> stream
+H‰ìW{sÓHÿùUPvÈ½u[e;$›[ >;°Y(.5¶Æ¶ˆ"¹¤qrÉûÙ¯gFoË‰“u@¬žîV¿û7Ñ˜¢Á2<E$ôP/ˆk#ŒTÔÙóFcôb§5XNNáW‰¡3–3?úžœÑÓóœåÈg?éìúæG!‰/Ñ+Ôy±!D±G=8|éèŠªªê)	PË;™’	‹â6œ½FB½Þï‘˜q]=’ø“Ô²W;­®ùG1	“iŸ­XžŸ 7d2o´»$¼™Éð^­,“ß“¶<•žœEçô÷“[¥~,QB†Záò¬-|*ˆFJ\øá òCÖ.¾èEgþåT+×GŒ0z²Kg1•Z°¢¶V;Ï'ÒLœ%€{yÔ±ªÖÎ4žÐš!âè­Òm¯Ñö±Q[L§°ã&â_–ü
+Ðˆ]B%±¥P.†k“ÊÙ)ý
+¤wT;Ž†T¨NÝåM7¹BÅÃè˜€¡X|AEÇ—ðòoøñHÈ@ïÐç/*ò€z<|Ç|žNÑk´ƒZù§*î~Hè›szÞ‡Ë¾÷£³E´½Âýþœøáõþ?öNÑ;ú5½£*¦¦[ë{Î×vyûæ©«û¸^Ýýu,†vl½ùU¼ë±kÁÃÅºTÑøêÏÓú‡ÓiB‚œ¯¤ºrÖåêùf)ÎË<š&,m×´³ÿŒ´´¿†lq«ÂýäÏ®ÈlÅ £OœÞàAq¶éäÊæZ·:›È8‰‚%£ÙA^ÈäøY…Ó ›Sq1h|o&'Â¼Î‹úA+ü¯{…Ùsw·…|á÷f.¾âk½Øé¼ù,¹	â@Èîtþ£‹0ý0ŒHÂb?bþýñ8
+¡ÓªìtÁúsšqn±Ù‡\êGqHãd¥Qj§íRçØ¨ipÞò1¬ÏåÚâ^usÄÈäônöIø³˜,æÝ^¼Læè*pÅáµ|®¯ò–ü×„Öà0±8:½1"ÉVÔà/Œ¾e,Õ)/QšÝæVxj®–ªXOån,}Ç¾xbÁÐ^ 3úáµvýdKùÊÙ:û‡ã¯CÐñ
+U$nŠq;¦<ÁÐ02X·ä?bþP6=ÅÅ`mÂŒÇ„}'	S\Óâw:WsT¤o}êìŸ,uý(ô–>[3Y¿ìØa¨[ÇÐ?'¬2ðâh†û½-CŠm,è´_¯ù§½}ÇŠªuîVhnë`ÿVØ¾7Ãš¥˜. UÑ5WC½9¤«õ!¡Ì<4ã ÂÝ»íÒ>,n½héõþyßkóš÷Ñ¼?a1ˆŒ6€­=À¦‹gË¹Ì“LQš
+œ;Åÿ~.eåZÜ¶ñÍ‹8ZÎæà¥Á¯¹‡³KQž€5Èº!7ÁêÇå|ý<~“6z	×M[ÓÄSWmôÒ0Ã…­]×ìo3˜£®Gðr²w•“}I+Ãý"ÞxÌN²›ßµÄ™™³ˆ›gB	À6jy„‘‘%\éôüL¸;ê8æ.(ð¸îgOàÏSçèùŸÓ«¾ÿ/½ÅßçÖ'å‰W¼ÿ×Žý?æÀ÷¢+~ñÿöþþb!>óûÊx,76HJq¾5Jyl†zqý8`™0‚4ü`À6zù;ÂÖ½`‡®):\²À¹Ÿ\~¥K§Ó„2Ž²ç½Zß¬i7¶NÀK^S5³rzƒIÅÙF¶è¨3¤H’N##xŒé$”„˜×TH“¤-¤’qKF³ƒ\!8tuû‹Áæî>—Ï¦‹G}¼'m4G“ØƒK´G.¶="ªsÌzç`µ¡ud	$g|€Ü¢óÓ€QD ýG”œ®¸ÒÄÒàUÎö<gº{ó(}œÎiÌÚeìAÂÉ¼Bàø¥üšdFTÈÑ’­‹ÉÖÞƒl0EÅ®…TEs4º¥:²Ïë6<LÃÄkW›q/«íîn‰ª×;hß‹ƒßÇ’8äÙ×l“g_é8<TUwe	Øš)ŠÂ±Ð1¹í…æq¯Ü¼W¢)C}’04š/ºøÐ÷·oÆ;¢•¹ï\Ss¡³\Íæ¨bøÚSMÞ{Yg>DãmÈl;fÕ»Ö¥èìÅ”¢]?a5ˆS=l 75†€†!·x¢
+ä¢kF™v.pŠ£–h¸K¾Š>Mði¦V¦5èÓøtÁçjŠiã\§—0i£¦»
+6t­| »:”>Æ¥¼NbÅd ­˜Ìiu“¶b2§o˜íÁ¨ë‘¼œ,DOöÇÁp%áûd™$>	Q/XÆ¯sl–ò¬Hg‘p’x2p€02JÑ{§çgÂÝQÿàÀ1wAÇu?{ž¾>ø:?½ê:“OÍÿô'„Ÿüý8/ôl‡­.^>çÌí¯Þ_@|C(,Ùî#tø ÃÝÝ>þ–Ëo7Ž9r­ÂÊYÃ ¬žo:åàžGñU»L8§|
+‚Œã ô*c1m_ì ¦Ê†?‰OE8”‚-È¤]ž·â±µhäôî0$™qÙæ	lÐ‡ÂÒí†×g ’eÀ¾”f×È?[ùì*BÍ­äðÖÑ`wã4à4˜€¬dÚ³î{ò&ôº1O8Åä”“÷Q8ˆÛg/_JrB5H@£Â–Á¸fRëóxƒ/mqt|µ³BLV=lý9÷-•`/Dæ°<StyÐLC<4]Ü,Ë†‡•ÿãRû1¹L…°ã@¶¬¹üÒUþ¢b@lªRüã2oýÙœ¡’¤£›:*[+ì‰àšYå‚MQS~°!ã~[gN­QUÝ·] ° “àa.¨ªÍM”7¨46’ó£AFªlv­ŒM1*FTÙåu¸qnqÊfTEtlˆÐñ/(.Öí4*2OÑ à³-U/S#ÃleŒ`QaOU S.taV*cöTD4Ç‚h+¶Ì«kˆk$¶Ôô‹Š–PM˜E_›²ŽlÕuDÚ\--®Iã‘,å®$žúnÈXRšÇN ;WÓreK¢®iñOºÂÚ¼¤dç¹–ÙSLÕ”¹–eiÜ#|ž­Ö®§eTdP²¯”“Œ°+‘g1ë¶!õò‚j¥¾ÊBÅ¹IE€J"Ø´Ex„¤fØ8)úòYžg¦¸º­Í.ªDØÅ4á}Hi<'­j0Û‘?²„ii·¼òë\Ÿ˜i7VòRfw5ÓÌÀyÉ¤£ à³2µ¶i©F¢AÌáæ|ÙleR«ë·+rº,&·H­•&X-ãE…‘çÃ4°Vð	RÊIcÿÂOƒZÍè2ÿjf^Ö4iå J_³åa‘Û„ó	†Ky;ŒI8£ÕÎS:_*©¨
+Ý4dœê‚½1àj¹C^ t]3»Ø'½¬—^o§Æ*5d=Ù›seâèŒhH<Ÿ7èl”ÈëG‹E†ZÖªÈ˜r©á~Tùá˜Ï¼kE+œM½ÎÉ:$Kþñ# ¬þ`âh&|	\+¼ÂzZï¨÷ö«ý·mä_;¯F8—Š	, ‘ù))þI¶b[WÙq-çl Œ¹¶X“\–\ÊVþùv–¤$’¢DÚmb]Á‘"÷›Ùùfggg!.¬Á6:nØ«&Œ„Ÿ/1‹_‘³@<»Ø2ôbVf`®ºOm2Ö¨5(¤Cså_}ûÒä7;×p
+rH«p3;Ø¢þ…‰yÞ0‡sõö7ß…Ü‚¾¬˜	<8Úž6y“^nÖÝÅÛ¾Ê¡6ˆÁÈ¤EìAob!ë ãt~¯ô«F[ ½ö@ßÆWÞv58|×cU¾å!”x5P^õ5¾šc´‹¯ùó4ò¨o˜WÕðxD{”r,½`hÃá]¤*â{‡¡O>ó=6æ<¦þå	1ù“ïñ) ¸Îõ½©ÜÖ7#8¢õÇÖ€šÜÌO‘¯'P˜¸ß>ÐâÎì¸ÔóÐ>fÚžvMèü=ø²G°Ëùò÷`væ|Pä¾9¨òãÒ$ïw‰…KaßÁƒà;Ô
+ÔÃ6l” Žä_>5p•W7 ­á*‡ÚšF<¯ùãÞÞ…uó<¼Ùî¹Ôwºö…,Óé€@MfÜ‘OpK`C8}oˆNàNYEI@4Záƒ.‹£—ÎØÅög†îd»¯þeYNM­gh,a›¦qébg¹˜1MÆøt®EºK'„Lƒí?µ<Nÿ/F%†gÍb{3û¾À_¢ƒ÷p»	Ej9Ô·u¾}þz™—c°ô&t&ÞÔdø8cÙ3F“—ËA£®K–àíG{DLêÄÂ6}ƒÁïSì:Õ%'ª˜ªù±Y3\ys¾9yF‚'Ccµ±;ŸÏz‡ªØx­GØ*Úäg†Ë´ðžÿ±¡zTÑ;€fpÐês@mvaÎÄ0;ÑèfÎ×,,Â°Žÿ÷ˆws`„]Céìæ­‚÷îÃŒÂÖÇ’©»üFò.#mc@¨ƒp†ûŒ;ú.z7Ïåƒ‡-¸³ð-ñƒ¶0¥¤Ç\'ßÍ·¶w®AƒA­­à˜ÏÒ]†	‡ùå>ŒŠÑƒ<ôV•çð®H:Þ1€;¤ëa¼Xà$ƒqqõBg1Ÿ&Õ®ˆžÏÏ†Ö|õ¸M¼ÿžYp‹Z°Ê›¥`’Ü½‹ë{;=ÓÐþ/Ž¿€HŸú®F¶y¼’œ’.s]krC 7Ž	6W&ÑÇ™Ç].yÅhÜdÑ¸6t6Ì_I¨ÕeQ]1F‘óó¬†Ä¸æwÙ¢¤Ô$A]µ|›x?Ïk@t…=rÁ>¹Fp™Ìcˆ6·)]jóîp|P‡–ñói¡aÀÿþnu»—„Ý»G‡{R}—ºþ‘—Ë;žÌÅ¶ç`@kŽ„Ká¤óóÙiØŒ¸&Ö
+´¿ÂŠQ‹»>OÌ¦ Cv¨IÝßµ¤óóä¬âÔ6^ï²z¹µ”â…aÂòþÓræø÷¼Á,¤`-Pmï7\S"óY<¯º"Ù0çþ}–ß9ÿÿ·Iñ½Ò‹ëä·omïÜ»¸ÞZ½´Š¬j´—;ÿZ§šo;Úª¢ÈJ¿v·…°Ë»:ÒxñD"šV›\ä¥K&.åbÓÅS¤ºÔ\•fä"cäbs-Þ<,™]|<ÞñÀt†Ž<ã[ú¬à@;Ä…AË7ƒæ<„È‚0¹`qÐ'Ÿ9>CÇØƒ¢uñè˜xÔôg:¢’Ð9 Þ0G#õˆ pŠ(5&œtÇ¨¥¼Ç¦á¥^YØ»ŠLï½Ög§P»‹Ú>£S¿&‘„iìD]˜üP¶!.n€{?"ƒÅ`ÛÚ|*Ôg¦aÄÈ+†ô˜K¯HšK
+¬™†‹m9&¹L»„°åh8.ñˆ;"ˆŽˆë@]b‘B=–'»!œ­¿ûQ6F=2"fª¿jw°%¢á}´Do›æ.“#ãeØ¾?ðÛÄ¤×±x‡Ë³}ÌSfj|²<ó~¹”žË‘§CC¦‘Ùuvw Ê0ûÀàáX†å@²·0¡“½OÌ}Ì:TëQ›‡`ÄÆ³ªÿÛåý}·GÆ‡OðÀ$|Ö”Ÿín÷íð¤9¡¨U‹^¦žgu†ÛØ?9è¡ÉÙú\5\ï7â2H¤ÓB…}
+»Öu¢"$Mê|öÈN¿Ÿ\ÏLÛll/Þ7‰ËÌvmÍôuh¶-~ªÌïžy=Ú3Fd’&)àRH÷£å°ñ1M/?B'SCgÃ}b\Yþ]_’ìœLû© š§ÜâÂ›‘ñ ðTEaÐÖ2CÇœ¶N¯½\ÜgÛ¸‰•æÔpb¦=l%8÷ñˆW°]ØÞ3Ôæ«Œú³*_PñÐ"!
+®p+-1kIò”¤È¿¢¤B-9ê`n¥Tü«ßJK¹“–z'­F¤u»6Sy´$#²*FÓÐH^>	ÅTB³—x¹Î?!Ê§ÛªIÙ¡ÏÕ“ï¨· ­rõ”ô²-Œ{öùF1ÚÆÚÕ¥K}[ÏÄDU?Àº³›BÁ‘ÖJ=È5uu ¿Ff“àÀÝ¬2Óñà„YœÕ6BzNÚö)ù %î¤€§ ‰âžÈYÚŒ]ÛËŠWúø˜A lüÒgÀ ‚«FC•|­Ÿ\úu„Ù0‹k¸ $è–˜O…áãC]Æ{¡ig±Å[Pº:Ñç‰6)K‹ñ[“Mg]52ì 1§ž1‰ÑÖ¼úVå(ž´õ‰ÃÌpåÍxžûWÎ·¡³·{xLÜŠˆÂ þ_RÔhñ)üeoPÙ ü éÙaÉÒGûÙAïs·ŒBì9`·Â»Â9 a(s?Dñ
+ÍÇ£¶÷›áñ.)eø­¨¿g×À©íÀ·O¡VWšMÎ­&Rð_©+Ýd—ŠÎ0àŽ×â¯a”¿jB‹£k‚ØR%©ÕäƒIAg|Ž0\0×~…/ÿD2ºFut€¾|ÎÝ8®4ë5µ¡4Q£^kÉ-Y•¦Zƒø¶Ú¬)Š*¡¦T“UQFªTƒËŠŠJ­Õ„ò¦ž(H«¨­šÒ/”fhC•kb® Ñ”%¤Š5E•áu«&‰r”˜ëÜ”ÒR\¡ÙPøL‚35„Ðƒ¦\SeI…†
+ßÔj*¡	Zr5Åš,	2J³Ð*ƒìØ Óu	æŽU±íí¶yxLY¬/ËçËåLc)òXŠè:ÌO^£>ÄRõ{p?©lT9n¯òeª¤Šà/úŠ¾ ÃŒAþÂ¿MX,ÈF ¬ÃG€ÌÃ7Ë$
+u±U9ë>ÿw)¥”RJ)¥”RJ)¥”RJ)¥”RJ)¥”RJ)¥”RJ)¥”RJ)¥”RJ)¥”RJ)¥”RÊw–ŸîS<¸‹ÎDn©õðáÃGàÏÃ[¨‚Ö£Gkkëëëkk\¹ &W[[òä)È“Çëk5¹Úú“§Ï_T@^üáÙÓÇë…4µg/~~ùË«W¯~yùó‹çÅ4<\{ü¬òòúó_þúö«Å©©ì/¼só ä†nîûò1 o„(`!@ Ñå¥Øî®®õ±ît;«ÕÚjÇŽëNíÖvwgw´N;ën·cÿTû;7…%Q[w¦ÓÞ/799ßïu¾ó;'åe»æ£ÍË+PiÖ^][Wç÷y*œÅÖ—`"wzs±«ª.ÈðÏë«ÝÏ˜Ù‰ÀÓ‹œžzº©=¼¿«³U¢>·E«Qå`æå«´˜½¼†l÷Œöt63¾J§ÝlÔåp	ééL%îz¾³ÿp|v~.15Ön¦ë½åŽ"äˆYyf‡§±92žX^ßÜ<õæB|¼¯C"kÝN›I¯)ÌB„8WlíŸZÚ|÷½÷¯\x{}16ieê=@„P÷Žå‡xmƒÓ«ç~|ã·n^}ïÕÙÃÛÙz¼´È¨Í)ÔSk*ñÛ†f6.ÝøÕ¯?ùÍ½Û^8•šèkcj+KÌzä0Ë:`ÅîÆ–ÁÄ©+·îþðáî^¿tz>i&¼Î"£foFm°UÔ7õÅ7®üòÁ£¯¾~òøÓ®_XKw°µvÝ;Á•ÞZV+D¦V/ßzðøÏOŸ~óøww>xkñð1à.1ëÔÙDõÒáèòù›ŸüáÛ¿ýãé“/>¾~þäÑƒû=H0ka Aœhž{ëê½/Ÿ<ýû_¿~xÿæÅµø@k°ªÔ’­0r‚EåuÒÁcëWn?xüÍ_¾ýêËû?¿¼žj§ªVCV
+ÔYÍtE—Î^½ûé£?þéÑgÿìÒÆÌpí+ËQPXA´±e`zýâ»¿ýìóßß¿síÂFr4Ìùs4¨ŸßMm^¾vûî½îÜüàüúìx·ÀYW>hiU°¥orñôù÷?üéõk?¹üÎÚü‘ƒ­¤ÏeÃrI³WøÙŽÉù•3gtñâ…s?XM
+O©Õ Ù[ÛÐbÔzK©§Aèè?6·¼²qúÌæ©•Åéñ^¤Ñâ…=osyù¶î±ÉøìÂòÉ7O.ÍNt7“¾r»)‹f2½©Ü ¥¶®žÁ±Éé¹ÅãK©é#ƒa±Ñ[–-EÔ5K±¯	\s{wÿØTb~qa.íëàQŠÆ½õl­Ñl/-Ç«ý´ê™˜ž_HÍÆÆzÛÙ:·Ã²wmòP¤ZƒÉjw”Uxj¹ÖÃ	 &§F#-tmE¶Ú "œÌl§UõLË‘É™ù…ùÄäpÎÚÀÁY RÃ±dÀ,ö2OÓÚ3z4™Z˜Cµ‘rÖžˆj0Ù }sí½c±d*5{l»6Ð÷ª:¬U£Ã ïøŽ¾è±ÙT*;ËïwçhQi*:ÖleÞF1< <)ŽØ‡RÄtÙ»wž\ZÉîò›ö™ž›Ÿè¶„º'okM@=5Ô¾îá‰éÙÙ™©ÑžVº¶<½³ñd"¨§¤ÒO·FF&ã3‰X´¿S€­hÉÖ£¶ˆHvV^Ç¶pbÇŽF»š 	çtKv¨¨\{ÏptâÈØÀþæ lá¬½æ9"*jUßêí”‚ÕÀÓææ!¢\ToßÚéíéjã¼9zÛsDTT{¹·ijµ·ˆ”ÁB¤y¨¨Û÷ž%áà.ÎÚówQQÍö2wµ?¨¯­ªpdÛ½ßImW¥ÇƒWºEè´‘»-¢³ØJJKKKìÖ\·‹ïÕh/[¬³É¨{IÚÖÅT«×úôýò•®´jµF­VçºtíE„½\€îÏ/Î0åK{þ«ÞõßØú‘ðŠ¤ÿ
+ø|]Ë3áøZ‹À|¡ƒÏÃñÕµä
+Ö­Ã‹Ä0
+Ÿƒ'…“ò+º‰‰,Áq¬€ó$Áó¢„ÇDš`iI!YIÄ—0‘"X’dqN$H‰D#‚DH4-á<CP”H£9»ì,a³Ø¡Œ+*íJö8ƒñ¸¿ŽËcé@¶
+íŒŽÅOA<È('ð4G‘Î°„(~‘sÚe"IžÂ$š ©t+"ªÈ,XÒYð$ÉãÄÌpòCðÅâI,KÁÈn;/Îë&m¿óÅ‚¡•µp*±–:±_ÙÄ›`ÈO4K‹[‡GÖVRËs¸¿£#”H¬>±GSëð˜Ø;ë±Ë•/¶£8¾ØÎòøbýÿaÀ]‰g8¡Z_;§5•:“|F–ƒÅý¡™ÓÉX("Å¦W“+É™Xor3–ž´ú\NÌ]F> 
+L/#Ár¢ˆ2%’–ŸËQ(}B )­¬¬XrhD’¤Ñƒ’x™DƒfQIhÉ‰-P4Ep"Iá´@Ð$)ëˆåò4‘„H	,NQAÃKœb	†§ 	Qäž‚HÓxÄÇÉIð]ÚE¢=AS„ê—@[ ²ÇGâÓVÀµÈ‰¬LÕ‘—‰¡(„t$GˆÇ!?©Ã!mÅ&AV‹ÙîtØôëPÚòZP™‚C[In&ûSKÉ¦ôÛŽä\j9ÓY@‡0¯›Ø&AÙ!ô)Vƒ•7Èü_¢Oé	éÿ|›MdáEb>Ÿìu´&¨€HQX4¢ÿ§
+(P @
+(P @
+(P @
+(P @
+(P @
+(øŸÀÿçÈËËû>moã{±žŸ_ #??ÿµû ë…*•Z­V©
+3>^«ùBµF«Óëõ:V£V¢<^—d^¥Ñ0“Ùb±˜MFCÆÇëq!›×ê1‹­Øát:KKìE“Q¯ÛvñïšÍ j£ÒLEW¥§ÚçóV¹ËËv«Ù¨×j‡WÊá9æ§ÖÕZƒÙîtW×ÃÐdc}MU¥\˜ºŒ‡—6š±Š„Xˆ šÑ Ú»<þ ¿¯½3îhmâ©¿·²¬¤<¨‘ƒ•`§UR¢F£Ñju:½Áˆ™mŽro€Ùî:4>~h¸?ÒÙ"P^VlÅtš½<3û\¨²U­éÐ`01ŒÙb…eu¹}|[ÏÈd"µ¸´8Ÿ˜Œ„š˜@u…£ƒvU(mZ6»#Td5c´Èf³—8J®òJ¯ž;ú¢‰ãë?<{îìÛ›«K3“#=!1XSé°µª	ü‹ÝòÿJë>ãx²6Qƒ¿‘Äoè'FñÞË…ËÅ/”DAQ@PD¢ØÄ$ëj–sÚæ¤é¶¬i–~Ùi–&¶'9Y’¥iWO›ôlíÙÿÒýÒýÒý´=Ÿ{.$™ÙéÙéÙæƒ(\ŸÏëó~žÏ—çáÏú‹˜+$ '•§bhm]½¼¡h:Ø¬Tµ¶S†n«Ë?—üé«/]~ëÒÅ×ÖN&¢~W?×¡”ï-ÛSô¢˜éüªXižTÊC[TêÖ6M{Iéô¬©»ÏîžŠ¥^¹pù·®¯ßøàKç_IÏO÷±š¦šJ@.AÂY/‘HË ³ûò¥ Z€2zk4uvuêµôpyƒ±ÔÏ.\ùÝ­{Ÿ<|p÷ãkWÞXKÏù»)e½LZ"âïÜ	x8.²ýµõ¨©Y!’ÊèY#gÂP³¥ßzøˆÍ>0èv{ýÓóÇÏ¼öÖ·>ÙxüÕ£·®]~ýô± ËÌ¨öJKvç`çO _ZVU]š[Z5-’jîª u¸ÝžÑ1ï¸Ï?ŒÌ'Nž½xõÆ½Ï¿úú›??þãÝW/¼œ[
+ù W‘p[µ:×Õ“'SèÄ„ß?95CÓá™ØBòÔ¹_¼»~oó}zçúÛ¯Ÿ^õÒ-ò¼ü`ù%DUM£²]ÇõX¬¶‡XjMóGfcÇWÏ¾ñ›ëw~ñøñ—ŸÝ½ùî›k©Y¯Í¤=X›·¾À/’”ï“+4L—ÅæöŒ‰¥³PÞðAl¡ÈÜBêÌ«¿zïæ?<|xÿö‡Wß<»ó;éTûË%¹ý‰ÓS\ZYÔ”ÉbwŽû§"©›Ô`0˜ššôû'&|ã^¯w|"‰'a‚w®Ýühýú{¿>ÿr2:áèÕ·¨©"
+Ò_LTÖ6µ1ÝV‡g|2KÝ¤tlÔãv»†œŽÁA‡sÄ˜Kœúù…Ko_¹üËók/-LÚ{˜Ö¦Z™”?^OåÃ¾ƒ¬ˆ¥b*°ÛŽ¶ö[Ì½‡zzzzûì®ñðÑÔéµsçÎžYYŒøœ}©B528½¢ë!›Å™mÎ‘Q/„Ÿ“Š© íhwW§ÉÈôŒŽ¢àd:Íö$¾´¼|,6ísY»„ÛMš‡Ï­o³†é4[íƒ‡C,µ»ËÄY%;Ú5m­jU‹RÑÜÜ¬T·ëL–‘ñÉ©IŸÇaíb4ŠÆYyi	Ïãgö§†f;{õBø"©¤¨Ú|°é jl××ÕBÍ­©khjigL½V›Ýfí5éÚ•øîßS¼» |‰Î—
+¯êH*¦f Õû÷íÝ+«ªª¬€ž¡¢RV]3Ðz£‘eÈ6Å3è›÷ƒ*R]#Ü=J%„/’Š©´¬LJ¥¥	´<P¤å²jù\U*(¾@—Jxúµ7{¿Uí«®­Ë“*PyhIq1ÔÜ°ñ5XBð7¢\Î7˜¾ëéÍ	ßoàn	_ý••ùR‹1•‡ò5Sh8_ÈŒ(¯¬’Éª*ÊpfžAÏÔ¡Û“H03OjÊ›¸*âk})îÞþ}G¶>ânuw¡T14×&oVT¨ÓEÏÑ¶mÖ÷lÃ]@}–¦2Bž£)Üù¤m= 'dznÌó9ækúwÆl›È
+ëÒl8&|6Ba¶ëCðÝN¥£IbˆX‰\…bð—B$ÿò­£¥ôƒhRË‘ŒÃOŒ´ŽF´z%šE‹§Ó²,­G4£å$‡Ÿµ¬ÁhÀ>:#eÄO
+8‹Ä1–™Š¦âgœ%H¥F¾q^›„d™óÕ1èÁéµz^k AžŽy0%Åj0r>²PB…±¤–"õzD1 “eqt´–åt¢i!ÊEÂhÔê9Òˆt¤Ö@ñÊ)±¦9phëðÆ.ûIê0'Óýñ™t<±N®"<R‘Zš¡£Fžt2¾C*‹Å<3³rÌH‡±«iÀ±Þùi)˜J*È‘"ôd–¡¡¨Æ&Ã™1f;2¯¤HØ`ñSÑÜ`^2R™g‘hÈlçB®H*š|):Œ®†§”(2
+|—ð‰Ã’ÝºŽðj4ÙÞ.|·Dcñ%þ	¸SÙuÆ¿YQ´Ñ°8$Òã§Ž¡â}¥FŽ¥§GÝás:ÆìýÈ„ßøbÕvŠ7üKH¡K"±ˆÿã9<Ž¬'—É4ð£	Ôçñlíç§â‘Åhž&t¼ß}'à—¹p…àÃQxt1È‰&$šÅ¾n!!‡ã‹Q“(7™ƒ®r†gâKéDjÙúMc÷”)z4mê¦Ò‰eÓ\"¡]^Š©ñ$GˆIDjY#¥¦>ê ›Øý°|bñ¼ç·öæW$3bómÄ.°ùØx‘„BÁ+ÆW•	1¥×>ûžlÛ¶mÛ¶mÛ³ýecãããÇ?2›l!ÿGö÷ï¿ÿÓýûë‘È}™ìË;àç÷rù-êßþöÝwnß^÷xH¥BÚ³?ÛùÿÏÙ_¿ýöÓ÷ß_w:?Ûµ« íÛùÿ¡öÏ œ÷I§endstreamendobj133 0 obj9611 endobj134 0 obj<< /Filter [ /FlateDecode ] /Length 135 0 R >> stream
+H‰ì—HTYÇC1Cq™(&_ÃÅ(|1\\Ã0&Œ]Ãp1£Åp1\Ã0\ÃeÂÅ0ï\grüÕ8Ã˜2e)n.n†e)S¾Y##Š¢(ÌûØìÎºãü¸3÷œû\s¾|ÿ*¹ßó|æ9ç<Çfs§÷SSµµLzz¯DâÕn?/2MLh*+Ù¤$.Øî
+Ç^øæÖØÈˆº¬Lïö žzj4ªJJ42™ØÖ†…a—²i´º²Òÿ¾²  ]*å‰}½±Ë»Œ“w%Aìþž5kµšš¹¼;4”ö —‚éQ«PÀô¨
+¢ŠÝaØ_ØEãËl2iªª”))Â0_oØhØÕ£éõØØ½+WT		ÂcßÊüGT¥¥­11ˆØž±X°y¤':[TÔ¶{7:óõ†£E-/-=êè`rs;¢¢ÐQoþóssX–ÉÊ‚&:á­ÃÿãôtwC“‘¡FËÑ0`cã«wfsGM“–†ÓŒ`óóS“ãã­ì¡Cè·ÿgCCê²2ul,:º-Å¨··¥¸X#“¡#ë§F#6Z·Z]Yé¿ŸÍÏo—JÑAmþ‹}j5“ÝŽÎgëðŸ±XMMLffwh(:Á<h0àb?5ÕUWÇ¤§ëƒ‚ÐiïG(ØáÝ§©¬d““Ñ	l)þ0nÝ»rE^¸H,ÿáþ~UIIkt4z½bsOs3=ìkÓcaág<=ò7Œd™//-5&'§3"½:ñ› ÿY«•‘ËµaaèEm"w74â?ÔÛ‹^Î¦3ÌÞ¤øk
+ôr6	òo).F/gÓ™ 8üÑËÙtÖTU‘â¯JH@/gÓ¹½ºšÿÀäÃÑì¡Cð…—ïÇéiRðß™Íèu‰Ù™îG`S:)æëõÔhD¯Q„VÇÅ©ËÊžÓ`¾^úÆFôbÅcUbbkE…ib‚6v‡T¥¥èU£[ÌääŒ†Ý!æÛoÑËG4ï0I¼O}ÜéèP¬LMíS«±°;ÔŽB`3YY/GG±Á¯iÆbA§!(ù´´gCCØÔÿÑp?:a¬Ž4°y;ËÐÔ„N†¶a¶I~yi	¶Á¬‹Î‡ªÙää×ccØ˜Ý
+†^tDôm¿º²‚ÍØ“Ø¤$tJ4CÝ£ŽlºÞÕ.•¢³"nUb¢ÙdÂFë]óssè¬ˆvô¬ÕŠ–“ž£ã"?9š
+›+Wõ47£#hejêâÂ6T¤©ªB‡FÊð¼ÚDo›ŸÎˆµaa/GG±qú,eJŠ`|˜ÌÌÖ˜JßÀ²Ø,ýQÛîÝT±ð–ââ':ËLn.¥¶¨¤?Z^ZÒQjõ®º:ÇALZ%øÐB›îØ·Lâ­Þÿ>Ðv
+b²³)ÁëQèñ—Q£áY{wh¨S«o”ª´”|øÑWWV„„FP~ŸZÝIpòÓƒÖ*Â°¢!¶°Ð·VÏÈè¬­õÐêNš±XÚ¥RzðaI³V+MBtÅ¤§luß—Ë©6?\+4°¦Öèh­ÞQScš˜ðûã0S…645¤!°6ŸðsøÝê?Nï©å0÷“P„‚Þ&Õê¤Æ~‚^ïÌf"­¾QðM€C›¿2%…øÊ?ÁLH>˜ÉËÃ.T¤RÅÇÀŸ-*Â.TŒ >X]V†]«Åäæ
+Ã_UZŠ]«è´º²Ò!¶°»\Ñ	*aàƒ™ÌLìrE'eA`üáµˆ]®è¤‘ÉãÁ®XD2ML	¿WdW0Ü}3âôó‡»·d»`²/vDEiëë—!äáï0›ŸUï³¡!Ø€­11ŽÅ´WWc-Ä&'ÏmÔÖ
+YæS£±¥¸ØåM‡û$lòßhUI	ÕÒf­Ö>µ6x»Têi3Q]†½3›±àÛÍ¤¥MŽ¬hqaaÐ`€–f“’¸®!7—à|,—?XÄääÀFÿªx9:ÚÝÐÀäå©âãýé¹œ,Uî‚«¿ÃÚ°0@¡©¬ìin†[ÒiF‚­
+ÿêíÕ*la!“‘¡Ž‹ãŸ«LMÅâû;ºU‰‰XüaD/Ý0‹bñ‡ýŽ^>ºá	†Å_™’‚^>ºuÁÁXüáèC/_†©‡¿_Ûçç÷SS(ü[££Ñkƒ_¡ð×Èdèµ‹Á#þˆ~¢Ó¡ð'ò~üü€eQøæ»µõõ(ü™ŒôÚÅàöêjþÊ‚ôÚÅ`uY
+ÿÎÚZôÚÅ`¶¨…ÿp?zíb0“›‹Âqa¡;4½|t3r9
+[à
+þdej*­B^>ºaÇâ?kµŽ Ö˜,þ¶À*‘tDE!ò7›Lºà`tˆ†òùƒT%%èp£ "ÿù¹9u\:D¿ŸšBäz9:º•/â×cc¸üAúÆFtXÀÆ¿¦ÎÚZt(~¢Óa³ÿK]uuè4„÷–ÅÿŒMWx8:!­U(°©ÿK¦‰	UB:Á¬©ªÂFî¬å¥¥öêjmX:•bóv-Œ™¼<x!¢#"nØàìÅ‹}jõÇéilÌ^4c±Àm‰A‡ÆÇêØX&;»£¦æ©Ñ»ª?‚9ÉÊÒ¡ÃäbLÆÈåšÊÊAƒaÖjÅ†GLp(ÁÀ ½¢C¶NHUb",IUZª­¯64ô9÷ ³ÉÔÓÜ¬,(€Ý-m8º¡±áô†6îïg6cc…àP…Æ345µVT°ùùLz:ôd»Têáµ~ÎÊ‚ï¨JJ€³½«'ÇÇ±«ÜÜ‚^ŒN†çöº
+( ’´uôÍ/=hÙ!Çû`³½Á	ßq²eöS»cäGžm[þ{»	ž¿ëíúí>#hø¾Ÿ;7³Â…(ÿsãq'Tþ‘ko\·ódo;öëÿÐÎûí'îÎ Ý7;Oß[ôN5×9íª—pÐv:á{/õyÏ^ÓN
+áûþƒ[8üÃW_qE?zã­/á ½Ä²CŽßþàc8¹ü§Zæ}'”ÿÅÙÎeïI®µŸoøžz³×t€Wø.ò	ç—°üÏpù__w}¡úª#~do;vËý…J;ûÉ»³¤Â}Î<ÝæíBõQßpßužË…ê£ŽsßûÓCâÙœóüìbt*ÿ¿×&i…ƒ¾ó~ì&±æZ§Ýg‡œ¸ãqt¥›¿óžª:ë.ÿk!Òm¶óîòÏ!ç_GÎ¿'Lþ%wù“ÿ£»|ºðÚñ/ÜÅï¡œýæúqOŸ#4ÃŸ—å){Mg¨…ÿ~yŸ·pÐU:áËws14Òß\rÛoÎâ;×»PÏI®á â7_Ë—>¤K"	§ëú’CÑô>L¹v&˜¾\âk¼ä2¹ø‡û}N—Hî‹/ßæG¼ä1¡ô®ï'šzßë_ü2ñ=^qô‘ø‡;üŒ—|G"¾g»¿ñ’Kâ_ø]½Dr‹ü¼Oç½“ú8|¿í•Çÿ?Å#^òÖKø«ëG·ßöø7øÄ‡¬z,ü<ìê½Çø·<~|‰äK…³_&w=ÆÛÎð‰—œpùÍÅO…Ûåe<|å×¡ï‹íç(ü“ŽzŽ·ã/¹éTxçÿ>Ç#½\‹þž»Ië¶p»¼½Mïò‹—L:
+¿àê­pÊK¼í4¿xûö›tQ¸ý¿=< ?oÝ¿µÏ]áv]ðÿ–_¼d›Âí
+ñv8Úúxæ{Ö9oñ¶ß¨æÿé5ÿÍøÃ^ãmå4óo{Ï¿J1~‡‡éMŠùÇ¼ÇÛÚ(æÿÊ!’bþù¶Ôâ÷q‰÷µ·ErþÓ3œòg¸P"9ðË‡ï9ÿ1—Ÿt‹ë÷^]»Ì~äœÿðÿì—_hIÇóT¨ÜR„BA~‚ÁTtºógÿUA[ÏÑÃV¯á¤Ô4&š#&%¦´Å'á p BA„>	}ážî)Ð§A8ðéàžA(¹ßì†ÚÒ”ü’f<<ò]²ÉÌüæ÷™Ùý†Æo”(ÉÎÿÒ\Môa÷GZk“hèÚ“Ï&ê1?BÅ7¯N˜e0õð=±Ï¨üßøôür|úÖÓý/°M*?×õaseV†{aDÊ…__þÙ:î5•ÿ°3>Uu*Ýÿ-•ßÎxw©¨üßÍð·©üº~cÈoïýºÓ0‘ÿWûT]é‘Ozûw!÷?æOù<¿­ëD¾©õO5 /ñ©„h:Õ€”ñù!>Õ€~4Ã'Cl@
+fød2dæˆ¡H6 ±ãÛ&ød‹­™à“H,ö‘wÕ€ N›X‚T¢5g€O5 ¡¼¨$R±ç|ªiêêûóñc'¶zË_ê¨~è%Ÿj€viøi…[®ë:ºôöè7•ó]±›š|ñ©Kô»Í•ÔÐaÐM6:ûW²]ßø9'{ÞÑñÙ'oä­ÍG…`¤—à]?>Xÿ­þ÷~jýÅúZ!'O·ÐˆuâËÿ7ŠÇ'Ë·'²µ¬•¹lÅ“SÎ<–§³÷kùªuÕŠÏ%«µ‰b®V¬”³ÕUÇª„ÍìP£06S«Ëw ‘J%s¹¥{Ó•ZV‡ŽÂ<‡+ÚI›Î®æ«gÏFåTþN±ÖX¢ÃÆƒƒ / á8úËGW¦¬D
+rÒåÖÃË\Iß˜š€qˆbç1ö$’SÜžÇhlŠFÅa,U©”tËÌ¥Y˜\Y¬Tk¥¿^‹33íã~(Þ/.”ò{âÃ«µ!‰ŸÌ2^Sr}oÙL9¾¯¯I[„ßŽrÂËežà.d²7q®ÆV]‰SèhfóÀ;‰À×žp £Ñt!kßáŸ@Â2(¸7çl¸­‡1mI9Ž-{Ì
+îY2`\r8gBqÒaBó|'ßg¾ã ™°±˜³„`ÊS.pìgWæpKŠ)¦òƒ@a0Qoî3á¡Ã=æ–Ž!#´p™äžŽ&ÂäÂ‹2à`ÏötÛV8Š½£ÏY®H¡„ÏiE.é»´¸3…\O!‡åhY^*–òã»Vhs+$FuÜ·ÖÍN\çÁ¸¸P•¾w[4êR}¼GØê…
+ÛŠÇCŽÞ‚ãØOIie¦Žtô†é«¯¾úê«¯¾¾Fý+À ÷=f„endstreamendobj135 0 obj3962 endobj136 0 obj<< /Filter [ /FlateDecode ] /Length 137 0 R >> stream
+H‰ì—ûS×ÇC ½ô’X@	Ð"­´za#^‰÷CBÕdÀz˜ÔNÜ’øA;Iœº®´ã4ã8·žqZ§‰`’6§ù§Ò»+Œ§÷§NïGÃ «=çžó½çÞsï?B @ @ @ @ @ œà•ÿ7j*¼¼õ«4/çƒ²®­­ÔÖR>^Æ¼®žÅ°êëjOëØ×Ö±Ø\_ àó8ìúºSz öõl.¿A(‹…ç”h{^ƒHªP*•
+™¨Ï©YœÊžÃo”4©[ÚÚÚZÔ
+I]ÇÜAMŸß(kFõÆžžnC»F!€˜æ ¬£ìÕí]f›ÃA˜»ÚÕ²F‹qÀžÅöº›{Àëõ8-T!ä³˜æ `q¤Í:“Ýãó{ì=mJ1Ÿ©´€ˆXÕÖcÃ³3ãC.L§: äDM­ÝÄàXhqey>èw÷#((T´mcáåèzd1èw™Úš„E¬¨éÄûGÃ+±d"²0é³wµÈ¹Œ¦±" ZßÛ72³#S‰µÙ@¿¥C-A8õ((Qµ›œÃÁ¥X*M®/N9º[Îâ±€vßäB”Ì¤+¡³}½úf*€ê</àø\$™É$#scVƒVêI ÇÂ«‰t†Œ.LzíÝ­M"0‡x^À•x:“Š-‡¦v•a²˜tÑfÒñ•™ €ZÚÀeP'\\§\úñNŒ‘ Ï	88>& CFæÆlÆ0ƒlÛYY@¹¶÷f×À¤Ö©¤d´•	hî;ZMd²iJ@Pr:1—z9žÎfè
+23²ˆ•­=Ž¡©¥Xz#KFf†RÚC…
+´‹œXXOml &	XîŸ´½\kÀ=cs‘ÔÆf&¾r€}¬š€eëº:è2M‡ùÌhxÜØÌ&WgFÜ˜®¹š€TìTÿäpB¨`7¨àdvs#¡÷ ¬Š€tìTÿ4Š=*x9žÙÜLW Kð'·ÁJû4%rUKæšZŒ{ À”Á¤jäúgSs‹®ËâšZXOoæ²É•¿KPPE `r—*5­Ýf»g$¸HÙokáÑ3å
+ª" ½øäê6ƒÉêðOÌ®Ä3¹s¹tt~ÌcíÔV­ òâ“k@ÿëóçÀ’ÛÞÙÚˆ/Nz‰.´RAÿÙþ ½x0§w,´¼žÚÜ)”J…­ÔêŒßIuÂjK@¤l3Å³’Ìåwß¸téâëÅ\|>  ôÓÐ8ˆLÛeE7K—ö¯\{ûRicmÚG™lÂ5µ,žP©³£[o\y÷æíÛ·n\.e–ÆÎô¶+EU)("¶@¢1:Ë¹ŸÜº{ïþ§¸óÞ~)5?â0jeUû •Aƒ¼µw0D¾víö½‡þË£Ï?þõ;¥dØgíhfp¨yµž+Tvg—·~~óÞ£'‡‡_?ºwëJ)>=`nW2èä@¾XÓåžŒïþò÷Ÿüíß>¾ÿÛw
+ëSýX«¢,Âª°Ú;8›}óƒOûô‡§ß<¾ÿ›ýó‘ñ¾TÎD‚znc“Îê_ÚÞ¿ýàëïþùÃ÷‡_|rã­sË£Î.­´z'eÈ©:HáêGzò÷§ßûÕƒöÒ³C¶NµDÀ©ªá3	b®ÿî=üæð«‡ß¸¼™ô0¬‚:¶@ÚÒÓLì^¿óÙ£/¿üâÁÝö‹ÉY?}ª:	å:F1Ït¢tåæÝûŸöÉ‡ïý¢”ZíÃ*½œQažàúù·~uóÎ‡·Þ¿zq'A­£f­¤ìÀtfbus÷òÕë×Þ¾XÌFB#ns‡V.dp3 ³ Ý®³sñ\ñµ½ç³ëóã^»I§‘«ì„ÇH5hdÑd:_››r[Œ­*ŸUý0@Ï‚¤Y‡9}ã3³sá`Àç¶vë4
+q³»Ñ³ÃH§Ùéñû<N¼[¯UJ….»žÉý®|š¨ÐN“ÅF8fÔi•2!Âc3¼Ò[:_(UiÛ;†N]«F)!<=Óëe¥©H*µFÓ¬TH„Gæ/55 -R·J±D*‹¨{%$Š›%ÝX9\¾ A—M~º‹)å´v6‡Ãf³êOk^ö@.hjOo^v|ÐÔ0•îß¸(óRÖÿËèõþ­äp¬CG½7@DÁÿ¡X¡Hæ‘)¤>f4ˆXÐ4ømAÍôgq±Ú0«ÝeGq'f&¬ôb%0nµ¢¸³˜64‡XA'0Âb³SOpÌEØ,(nÅÌf§“zò‚Ÿ’Bæ*CYÊCÑ#&;j0¢‹t@!¤ÈQ@Þ“ÑÙÐ]=°ÃŽƒàìj·b¸Œ9„é”^ð9îRÚN¥’q:¬TZvÌî²:QÜ9Ìh#0Çé´¬V³<);-„µ€'fG%Ñ~ª§5‡¸ŽþÒG{½ùâp6QÌnoÅò{¨<2˜1Ü†;-6#Ú.æ³[iÔàóy‰Ò¹Ðv1F½jD{À‹}àç¤/¥žÐF=¡Ž>:õ_ ló±Š7€zKÅm´\QÙ×Écc:VÔàMnÇÉ¨7àŠã2LFÇÉ½hù¥Âs)YÀ»[Ô …	ßQ­NÄöÈ¼É„èõÓ±49›es tÓ…ØmmQ‘‘;à4'Åí<‰2Û»Ô`òìu°
+‚#È¿ Ú|l1endstreamendobj137 0 obj2126 endobj138 0 obj/DeviceRGB endobj139 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS true >> endobj141 0 obj67 endobj142 0 obj1331 endobj143 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 56 /Height 62 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceGray /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 56 /Colors 3 /BitsPerComponent 4 >> /Length 142 0 R >> stream
+H‰´—ISãVÇý´ï²Ë`ÀfÀ3Lå”K¾BrÎ!§R9Ì!‡9¤òe‡1`À»eÉZl-¶ÓO²dðT%]6ÅÁ?õÿu÷ën¡Òÿ`h÷_¢Õê»ŠþÝÎ©ìƒøæèJBÂÈÆvQŠ9‚ 	¬vµÄ¶šc$EÂ'ã™÷ªRðFRÍÐ˜\-Ò$IÓÝîå IÑ,Ç±M––‹$Ž¢³¯è€ñ‚ ð,M¬ÒhŽ-JRD‘/¢ØÃ‹’¬ÈK•ÒhA˜¡àtY¢¤9QV5­¬ZD¡?õ|?˜Eqœ,–ÛPà(†“TÝ¬˜ºÊ“Ë8ô\ÇN}dªóÝâ•5³º¿g2‹’ÐslÛž¸S?ç$L*PPt«vxX«ê"µœ{Îx4;Íô¦Ë2SÊ
+Š±wx|\?´Ê<Š}g<èèÇ@!Jà³H+>¢ {G'§§ÇµŠL/gîxÐítº½ÁÈ¹Qò\ë:¦ ÔØ¯7ÎÎNßìk{ã~ç¬ÓN\ãJ(J"Í+ú^ýô¼Ù|[·zNú÷·7è·Ÿoïô‚yRBlhNÖ«G§Í÷ï›šÎ£ÈtÚW­ÖUû¾?v|8ãò›#¢u6X©l5Î/>¼—2•x£ÎMëËå—«ÛîÐñf8¬…± š'À]4ßì—Ùe0î´[èÓï—­›ûíÍ¢- >£±üöÝ‡ÍÆ. Ù¤×n]~þüåú®oOÃç±Ag”´ìŒÍÆQE$bwp}ùùÀÞxD…AÍ¥–+µ“³æ»sà$:õínýóçeëúƒÛ‚
+iäeÈãìüíÉaEa  †ÛëÖÕÍ]oTTô5’fÕêÓ“ãš©r(	&Ãîmû¦}×M¼-ùÏ¥ªFõ ¥ºg(<µŠýý×NwhçR‹£ÊðRÙ¬Öjû–7™X%áÔö ZcÇÃµú¤Æ7JAC"5Ó²¬ŠQVDŽ¡ 	øÎ¨ßëõ†¶l­U¸ÿ¢RÖ]+«²(ðC¢O…pEzýÁ.Ö¼°tÖJVTU‘%Q”$Iä”†®à´~sÈM“Æ½HAà¯OEŽHgîhÐÇ¤?‹ž—yÞÄi–åxŒ$UÓ5ôÇG|:i»˜|Þ`ldÝ?3–Ð0÷,2ê÷8!Ãƒž0n°Á€øËÔ$¦ù“aÿ…ðà±H’ ˜É‚¬êôË¯¦&ÒÐílÐ:xŸ¯.‰l:æ‰É2jªµ˜MÇëð„ól =QZZñ|DBËjÕ‚Ú#³ðôú#ÛÙÚ°Ðz¶b­eôÃOÕjE—9"Îê§?š¸pÊÂ‚]³0$aøh&¸45™YEžUO^°˜+ÑYb ˆÖ§,Ã0˜9YÝ]?kçEÔ„ùŠ¬ºnZÕŠ¡p¾™X+vYØ±6$®>O<§’^Íó¸BÇÊ¥n[&òòÃ¹4+]áÁ#D&–ZØˆ—3Ò4TæÏÔ†·Žê[Ê‹ ¦º¡«"ƒâÀñ¬›¿¨´´¹à²\V$¥sß™8îC6¶sÙæ>ó$Û¦S/Ø2ž8°—šgÉU:<Íó‹üâ‚–-g¾Ô,C®I4›Í£ø¡˜ËÉì^ÓDi™&Ùr¶¥NŸ¹’¢Hà`­[oW¥W—ÞõâJâÕW¼nÛ¬ž(}@ñÊ»ÊwÞÞO´ÙÎ­Ø»¼Hä;ØÉÛ£‡æoßó±ÃCÿ;{ñ¡ÿ
+0  ‚¥endstreamendobj144 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 56 /Height 62 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceRGB /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 56 /Colors 3 /BitsPerComponent 4 >> /Length 141 0 R /SMask 143 0 R >> stream
+H‰ìÌ1   ×?ô,ááH;ç"•J¥R©T*•J¥R©T*•J¥R©T*•J¥R©T*•J¥R©Tú#] RR÷…endstreamendobj145 0 obj/DeviceGray endobj146 0 obj<< /Subtype /Form /BBox [ 79.92285 58.09082 84.55469 63.11816 ] /Length 147 0 R /Resources << /ColorSpace << /CS0 145 0 R >> >> /Group 148 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+1 g0 i /RelativeColorimetric ri84.55469 60.66895 m82.42969 60.0498 l81.40039 58.09082 l79.92285 63.11816 l84.55469 60.66895 lhfendstreamendobj147 0 obj137 endobj148 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj149 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj150 0 obj<< /Subtype /Form /BBox [ 79.92285 58.09082 84.55469 63.11816 ] /Length 151 0 R /Resources << /XObject << /Fm0 146 0 R >> /ExtGState << /GS0 149 0 R >> >> /Group 152 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+q /RelativeColorimetric ri/GS0 gs/Fm0 DoQendstreamendobj151 0 obj45 endobj152 0 obj<< /Type /Group /S /Transparency /I false /K true >> endobj153 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj154 0 obj<< /Subtype /Form /BBox [ 80.45117 33.6123 104.54883 61.8418 ] /Length 155 0 R /Resources << /ColorSpace << /CS0 145 0 R /CS1 138 0 R >> >> /Group 156 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+0 0 0 RG0 i 4 w 4 M 0 j 0 J []0 d /RelativeColorimetric ri82 60.57617 m103 34.87793 lSendstreamendobj155 0 obj92 endobj156 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj157 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj158 0 obj<< /Subtype /Form /BBox [ 73.69141 50.63574 92.21973 70.74414 ] /Length 159 0 R /Resources << /ColorSpace << /CS0 138 0 R /CS1 145 0 R >> >> /Group 160 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+0 0 0 rg0 i /RelativeColorimetric ri92.21973 60.94824 m83.71973 58.47168 l79.60059 50.63574 l73.69141 70.74414 l92.21973 60.94824 lhfendstreamendobj159 0 obj143 endobj160 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj162 0 obj<< /Subtype /Form /BBox [ 73.69141 33.6123 104.54883 70.74414 ] /Length 163 0 R /Resources << /XObject << /Fm0 154 0 R /Fm1 158 0 R >> /ExtGState << /GS0 157 0 R >> >> /Group 164 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+q /RelativeColorimetric ri/GS0 gs/Fm0 DoQq /RelativeColorimetric ri/GS0 gs/Fm1 DoQendstreamendobj163 0 obj90 endobj164 0 obj<< /Type /Group /S /Transparency /I false /K true >> endobj168 0 obj98 endobj169 0 obj1189 endobj170 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 96 /Height 41 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceGray /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 96 /Colors 3 /BitsPerComponent 4 >> /Length 169 0 R >> stream
+H‰ÌWëv¢H¦ä*F£ù³û»±û »0Ï>£ÆxGØª¦ãd&'sr¶ŽÁ>šþ¾ª¯.ÝåfäÓ	‰R–o}ÿAðÚÞdyfžŠÐ‘àW‘px¢²JV”‚æ{½_Õ4UUAÆˆ>†pñ5LcEV–KÅà)¥†Au]UÊüÊŒ“T´úY\± etÃ0;Ó0tRä×óår†¿'yOR)2Ý9¾FÍŽí8¶mQµÌ/ç,M³,;DÂ•ú9T¾Æ'[UÙ¥†å¸žï{¶	œÓôt<Á+ˆ£
+B¹£P#QdXQòø`þVÇºax¶¡—ì”Ð’$ˆB0Ü@×±`€ð¦VâùjU>†eûa¯ßïu=KS®irˆ÷»¾âäxÊ -”ðQò•ÔÝ„õÎß5õwüÞàñqÐªäYï¢ím»‹ ÈYRQ7D¸[ÃÞønÐGÃAèZ*D›õr±X,×›í>‘òF"DÂ–dmÉL€sÀú;òÇŸ°@Ã§§Ç‡ £Y²ß®///³Ù|¹Žâ#hT‰xÔ:Õa§Ö°HÐÿ˜¯ßrƒp0zzö›–çd·YÎgÓÉtú<_nöÉéÌðyù©le½Ï9ÐWMÂÔÈÀRÜ‡ †ƒ®c A´^ þøÛx:[¬£C
+\¢ª$LèIË2èþ
+Ÿ#6!0…þùW$Á°½îÃãh4Œ ZÍŸ'ã¯_Ç“ç6ø%‡=éØƒÐ$_%¹êìW]à=ÀìwA¡,Þ®^ÐÿoãÉl¹ÞÉ
+a Ô´]hJÏu`²P6›×5Eš–&P¦L¢!¤ØÖŠt¿Y"Áx2yž¯¶{)Å„Ç‚ ë»¶eb R¥’Ö$úò…ŸYD7;^ØÇ6€6»÷PAÏS°àï¬jÐ?±éË l¼Ë°lºó#‹,ºUÚ}€@®I.˜a¨O¬ÐÕf8f<„X¯°×tM±l!NþNT
+lN@†³C´Z,æóÀGÿ"ÆDß³-á_kc#žüýWÁg=ø½‡^èC“¥q´^-—«õ6ÚŽÇôrÍë
+ÁTìnÇ¤šÂ€+tDãb	OØ«QËÁ=kªù)Þm×0pÊÒ¬'RŽý +(%§«s¶Â'n€i{l…9zØGà{|¨à_:/ëe%ª«¤lià¹B¿ÿÆñ‘ ¼‚=–Žƒ:Žc^ÀËG™Ôe¬P•ù/|md)æ5„}†	—W<i’{è¤žÔ´À@µH2‘^T@@pØÁhË+–§Oâ¼u›TsF«ÏRö•¿s\bšJµzöÀm‚jO{´Èù
+žOjùúÔ‚¬î‚Í]­êqá¢1Þ‡ª›Êkç›³FŒJ©i•VºÑ¶Î6°à£œÙ=ç…Hl<¶¯Èj“²úW€8^UöÉíEîƒ"M´_•»÷qROW1Mî “Ö†W_ÿøRF¤‘õÖÿJ{Þõ3è&äÏ·Oÿ¡ø#{·Cÿ	0 –æendstreamendobj171 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 96 /Height 41 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceRGB /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 96 /Colors 3 /BitsPerComponent 4 >> /Length 168 0 R /SMask 170 0 R >> stream
+H‰ìÎ1 0À Õ¿èNBÞ €Ù}§ŒP*BE¨¡"T„ŠP*BE¨¡"T„ŠP*BE¨¡"T„ŠP*BE¨¡"T„ŠP*BE¨¡"T„Ê¹Ð` ‰V£¯endstreamendobj172 0 obj<< /Subtype /Form /BBox [ 93.77246 20.9043 98.76855 24.96094 ] /Length 173 0 R /Resources << /ColorSpace << /CS0 145 0 R >> >> /Group 174 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+1 g0 i /RelativeColorimetric ri94.15137 20.9043 m94.82324 23.0127 l93.77246 24.96094 l98.76855 23.38184 l94.15137 20.9043 lhfendstreamendobj173 0 obj135 endobj174 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj175 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj176 0 obj<< /Subtype /Form /BBox [ 93.77246 20.9043 98.76855 24.96094 ] /Length 177 0 R /Resources << /XObject << /Fm0 172 0 R >> /ExtGState << /GS0 175 0 R >> >> /Group 178 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+q /RelativeColorimetric ri/GS0 gs/Fm0 DoQendstreamendobj177 0 obj45 endobj178 0 obj<< /Type /Group /S /Transparency /I false /K true >> endobj180 0 obj<< /Subtype /Form /BBox [ 37.63574 15.69922 95.68555 25.06738 ] /Length 181 0 R /Resources << /ColorSpace << /CS0 145 0 R /CS1 138 0 R >> >> /Group 182 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+0 0 0 RG0 i 4 w 4 M 0 j 0 J []0 d /RelativeColorimetric ri95.5 23.07617 m37.82178 17.69043 lSendstreamendobj181 0 obj99 endobj182 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj183 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj184 0 obj<< /Subtype /Form /BBox [ 88.59082 14.3877 108.57422 30.61426 ] /Length 185 0 R /Resources << /ColorSpace << /CS0 138 0 R /CS1 145 0 R >> >> /Group 186 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+0 0 0 rg0 i /RelativeColorimetric ri90.10547 14.3877 m92.79395 22.82324 l88.59082 30.61426 l108.57422 24.29688 l90.10547 14.3877 lhfendstreamendobj185 0 obj142 endobj186 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj188 0 obj<< /Subtype /Form /BBox [ 37.63574 14.3877 108.57422 30.61426 ] /Length 189 0 R /Resources << /XObject << /Fm0 180 0 R /Fm1 184 0 R >> /ExtGState << /GS0 183 0 R >> >> /Group 190 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+q /RelativeColorimetric ri/GS0 gs/Fm0 DoQq /RelativeColorimetric ri/GS0 gs/Fm1 DoQendstreamendobj189 0 obj90 endobj190 0 obj<< /Type /Group /S /Transparency /I false /K true >> endobj193 0 obj3157 endobj194 0 obj1841 endobj195 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 128 /Height 128 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceGray /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 128 /Colors 3 /BitsPerComponent 4 >> /Length 194 0 R >> stream
+H‰Ô—HTYÇßÁ˜EQ¥˜eBq1ÃFZ\Å0\¥E1cBQZÅ0E1¥PÃ˜0FŒ$IV’$)’¢Ø¡Ø0•$1
+D)E)ÎŽóæ÷¼wÍ{µûñÞ{÷Üó=·ï›{Ïé|ïÂåÛ. ¯·¹>_Û”ì0Úªö¯@’¶°]l³•Ä:/Bô¿…ñ•¶á"ƒ|­ù uÆZ[¿Åw»	Ú@$¹ÉÞ•ðäÄ†èè@z›½%=øaHá¢¶€ì.{S¢ÂóMˆÑ¶ ",ý¶j£Ê U¬¹‘E#¶²xõñàÂ%0]l™m¤8’<A·—ÎhµZ"hQQ°XFê‰£Ý¹,qðI#I×·Œ·e0NÐº éX‡½9…=<6îÃt àŠí¼‰kF¬„'éÅP8l«Üˆ|Ó4* ºÄy´FLÖr`¿óh-4ˆÌ”¤TX›èÁtÞv¥ÀwËíÀQx†zJ³½ãXóCõy0;ÖÃa©+ÀJn÷hƒÒÉÊí@Ìs‹GXmVµ£•“`}º‘ÅÎ£5Vu…ÈÄ;OÖ"âÉÊí@>Ì±†«,õhåäLÜ«:èìd³5W*@‘ô{[H#«·ô²œl2_R~‡[÷Á8;ÙZ~nÊ”Ã˜ÚÁÙÈVYE¸P- öÎj±ÈÑÊÉ¸pïs ê//I50¤<`Åa‘|Ü¨Ð"ð¬ïsà‹¡Gyàfˆäãv ú”>£î¿€ç—Ûû¦×Ÿy0áª®â+=5Ó„o¡l|,”—Í×íå­/É!8*T Ç¥ÒÎeÕQ¯Ø¬‡úîÍœÓÏYÇñ” Ù•ÆÌž5Â¸Ï0¼>_¹“ù“Ô ¯ëÈ{R˜8Rúš=:×ÅdÔ˜Í<îàÉ“…OÄ
+Pd1?•µçõ8P†vÍäwÛcZw9ç4c‡˜˜‚ó©9‹ÜyF±B¬€Ú÷µ~å÷8ð³4‘ß8‘ÀÐï‡ò{à I™+"i¢ñ³˜~ Oã~!œuŠ¸ÈÀèÏÇälŠÍ<…ã‚šþÌEåo¦iÀnÁ™>cR–ïv`­áêo‰áØ÷ƒxˆ¹ÔüSŠRBû(…	a}iMÄñ¥žšÖ²­JBÄUøCHYvÀðe'B5dsª±nhÅp§€ç]ÌAÁ×4\PYê©»4³w¨Ø±L1ÀãÀi¸)®/á]…§ÛSõÎ•Ë×”^qiß!žÍßÙ…ß wé.
+ð>1Í9¸&¦/Óµþ·ÛÓ5þÛyüûuµcBv`;.ŠwÿàZ¼×+—¡}®ŽA¹¨´ìÀLvý»=}±îjèÇC	Þ&g)‡1Ñö‚Ë=5!+—‡ÿÙQØ~ÜÈ$Ðùë!”W.s¯ç¿ƒƒÂÚ.L–5Å¥ËVwÈ{¤ô~.€Ž‡	£.®ÃYøÓ)¢gÀ@8†Ïh!íÐ*\ V’†]tÂ%Ýô#Ö¿P¿U N8?ÕÞ£&™‚ß„ 1ˆÕÄq—Ëð“n¼ÅDzÐQx%šŸæ@2¾aÈÂùFÄÝ`­ÀQr€|l$$°f”¤ôÞ¯\g¦½n®Á9¶|æŽñæ©ú<h<Æl¦Äu0@Êî¶7¸^(ömk)[€÷{à2\$ÆwV{:*æÛ„«l’4{èø’ÊPd^SGK–ßƒpÆsIq ° }½yâÌLHSœVyáBUðI6	'ÙrVá%Â÷E¶Çædç­ÙY‡ó÷`2£Í%Ey…iJ³æ Ÿ­€6laäÃ™žKŠÃhÕ£€%8ÄHëÃƒ`e°>Ä\ôTváÏ%Å¿Ð¬GRl3ÅÑA1¤áSœçKIkRaÑ}Eq€©àgxÎG×tà8Ì2Å- â.6¥0á¾úN¿³ÀÖ‹ü‰…”Aüš"Œ­7¾^„â@-öëR k/’…O(‚ø5#D"·¶"EòÓðõ"´n”þ
+ÁÜ‹Xq˜ è€_3B&vë£øzš:ý™{)qç­4.è€_3B£›D(x{ªRôÂg#Ö^ÄIÚÖá-tÀ¯¡S£B$¼½ÝI—Ó€µ‘©ÆAµ!Q|ÍEïÆ
+é¨q®ÉL8I~ñ&CË¡‡o‚áÂzo´ÂsQX›!?Œ#o«ˆ;"+/ûÚ/O®¹oXpßð¬;%,íÅ±¡¡¡ù]ñ·ï•Dø?`w`erh`hî“¸¶£µ·¹Œç3i×11379áP–ærÀKâ©¦¶êÃÔ°—“s3ÓOß	iÐ0˜K,¹ÙfxÆ`YÇ’ëï‘cIeLfWŽeî©bü‡{ÿ
+0 žR²endstreamendobj196 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 128 /Height 128 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceRGB /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 128 /Colors 3 /BitsPerComponent 4 >> /Length 193 0 R /SMask 195 0 R >> stream
+H‰ì×}Pgðx‡g/^{(žSÚQ+êÉõ¬§bG¬Ë(v ÅS±T±¢bÇ«=µõ­hÕzrŒB³I $&¢yQ„F$P^’½uÚc$,„}öIL¾óü	›ý}?O²ÏŽCQŠMgœc Èq ;Ž`ÇZ(Ééîàß]&‰ÏÍ5ï­e ‹s mZ&êìádðBXm´<
+-}Zxc£yq˜U7*µëRXÛE›¹]Ï‹XéhGËx
+*'y¯Ð/[7¨x‡ È´6Äìú©üÄCYø­¿¸2'wt˜w}‡À0‘Õëï!fó.œ.¹øÅm³Ri‚xX¥•²%ç‹­6£x‡À˜#¾Óó„_únJ8½É’â–`b Jc ˆ±| }?Z"RvóòÖrB­c*þÅeîýØŸ€º-uhîapZ'aÅ;FŠòZÎoqb3výâ‹wì,YÉ“9s#E¾9€Å¬Þ”J%n ëþ r™^‚Ô¾Å;~›ŒÖ_\Ï:Qgç1`C4À£‡º¤jçäÅJ²‹·oªbµœ'^‚D%<‚VüÀjoC]\ÌÀFS”Ý¥äŒã¾–¬€_üÀjjÐÏ˜aÆ6& íCËD=lA ?„Õö|àqÐ+·U7Z&l3 ¬ÂÀÌžA;@¦í‰¡‚¯ ²éûD~Ù:ü­N@Z£sw7cHkPÈ¶Ô•ŸpøÖÈ[@M¥vÁ3¦µ"Ç?÷ßGªçòÎ-5c`‡À˜S]¦iäI"_\®³d`‡€¥)ûQÕÆ/öBÂéMcØêÊo÷¬XaF¤
+èûÑ‘RÅ­ç…2Z‰Ø!0Š¨{ÑRa»ŽÍý˜¿™ÛEðÀáÓÑŽJ„-NHòg"ÔÀV'P|«{Õ*¨­Í†
+Nƒ/1Rä›c >°Õ	dtúùÁËô’”³ù1§~"u`»xX¥}Ä©šÇ>[g`{¨(T7óJ—!û lu9ß?Ù´	˜@¡@©âç¿Ï&ì,ù
+ÜºÙ²e¡Ú>´DØ¡agnâ§uÂŸÐž”ÏÐ¬Æ.Q`füÁlF@ø_EHAe?ª(4ø#Ù˜ ?®aÏ‚„—eswÃÉŽØŠ×‡?’ Œ}éðG²1ôoj?ÿœ Ô…'/VÂÉÆxçë"#	þÉªOAV$À\rî wéz¯ÎeKS§šQ¿)…Ü 6ëHŸ~ac±ÿÊÎ^¨³³y­J@|§Gÿü‚­N õoGNJ6ô½óŽå­J@Dož¾~ÁÖ"À^}4 :8HïæFLñ#¤ûDÃ/²@Öx¿3ìU{z\üÈÈÆ´0&ü‚¡	`?ó±{k·o3ûÉJ˜ ké¹³¥ð† €Ðâ¿ÚÛþá‡`‹Y€?98­~Á¤
+0>bE×yxÔ½)ŽvôÞøí’'ÀXðïÓšÅ‹Iíþ×àTªµËá·K†@ê_¿¸q©{Õ*Ò›ÿðr’[Þü~»`°sãäÈatÂÒk!øé§ª½ŽÂo  syÌõ»;é…	¾ œùéMøí‚H=*ùêKÔÉ‰ô¶ñ‚/Àz÷Âé"øí/9)8ƒÞéçGzÏÃ_ ãõPF+üv	`/Šæ¦égÌ ½d“ÁPu£å¯Á¯–`æ²Bêì¡cÓÁxPÑ§\¿Z"°ç.Vÿ«¯Âhx¤àä2ž¼¾~µ„	 ´x~&J¥Â¨wÁàž­]z~µÄ`/\åeVºûŽ k§(è*üj	Lë<<`;êà0WÆ¿MFyXA×¼“·?ˆJxF —Ù¶aŒVÍ	Ž ïÍ°dÀâ9³¢ÎäÓµÂÍØ#ØvÌw€Q£R3c, íCoS}s@¶ûnß†Öýv Ç>(Ý/áð­±^_€ûFXíC«þùˆ±@Ý}ÝÓyo÷ oå*otÂ„A„qw~OÀGàd_oþä2{´<Æw¸öS%ÂWü“|m÷¡I=,ö‰&G sÇ¾ NN$ÔG@Œ,>ŠšØîF)ÊîúÃû„}Ípñ²]»€¶FdŒX{óãÌÙîÞô=¾õ»ÝÒÑŽz„2Z	`÷ÔÒŒ:;è
+LŒßÄCY„m÷¡AûÒ	«G€±™›’B`AÀc,>sbÃ°Û=ÌGŠmw77?,Õö—Y?ŽÀ­›-[¶Œ½ò2H`èQ”óÖþsnw£`xŒéåkTM£ýA´’Õëg³Ý‡&ó¢tá~‚ë7À^~ù…°;&'ƒrCã=¶ûÐ`_€,·°d`ä½¸ü|‚otŒŸ€"¼,›»›øúÛ³¯]#cC’@êüc±Õà˜11dÌC`È¨*V«—©ßX õ¨äÄ	àó2m‚m×I`ÿKüõ×Àç!6ÀôýhÖÔà´NR˜Ÿå÷ØypBòkAÕo,ÀXŸÌã‡ð `†åmŒ'K {|üì<„¸ wz8½‰,lÕTj, ;±+ «×7ÎX?Ž€U=Œ±‡`—uq1õ7`Dôæé[ÉÈœ,ýy„¡IÈÃ*mmÒ]ï!7NËwì0õ—`@?p°Å]¹p*©.ÓÈ8â%HTÂ£ßn†w¾.2ÒÔ¿€`yÅœú‰tçß„ÿÔ‡‡Ì(â;=­¼b/ç‘7âK"Xþd€o¦°Å>XzæÀÙ”ÏÐÊÜö~QÞZN(£uØûcFÄÄ˜º@…Ü ¶~SØb¬N¸r©ÎÂFR÷¢Õw»•ù’ù¢§‹FuŒ­‚¤$S×(P’ÓýûÕP°•ý;ß” Ì° åÔÉÉ’1êîëä%
+jAöÚ’c±ÕfßÃŸÁá˜º>@a‚|v(l%˜xÍ‡±méÏ™OæÍÖ¸Ít^Â¾¯ÏZ4¯P4•JS+›|/Åcú§\ªëý!´øÜ\Hi_J¼OZ ¬Å^]^I€µStÕî8³¢¤RHH c_ºÝdL	yú’ seÜñÛv/5ÞO«…$úèoÅv/€­Þ”J…"0ß’ÓÛK(Ð¢0¸ºÂHŸ¹?±Á!@¡Iktîî0¸ÓÃéM
+­²Híéé€¸îfu­YC ím^)_\fÛ†0g¡ß–àª|ÇÈ:úï|]d$fXÞÆx‡ …–zTrâ~lýü‡ …ÆŒ(ˆ‰!PQ¨Ö.wPhŒ­‚¤$ê^ôŽ‹¿@ãðgp80(¤<Œm@ ¡ÅçæB^–ÍÝm÷ìEÑåå”ÏÐbW°?D6 À™%•B €?“Ú€@Æ”§Oá	ÈeúÚ9~Ù:;Èï§ÕÂÀ’z¨Ô÷;ÀVoJ¥ÂPu£"Ï#—jìX Eapu…'€¥î¾N¾È#Ù6¤5:ww¨XDôæé[íU ²Híé	[ ?¶~~„]
+ÜÍêZ³Æ
+°üp©áíÿ){äÅÀ¾UoBCG ÁáïXã"7~I1°}ÆÃôtìÁ1 1 ïý=Ô<áâˆ‰7ËÊ°‡ÅÀÄ üúù×”[Úõ![¾Ž€ØÔs«¸{@X@ÀËçÿÕì
+_ì³ë÷°‹5úÍÕNÇýmÞÚÙüÃðîíÿ#soªÍ*™sw(ÇÀZµÊ&ãQfwìŒ¿š›ýgg'Êóƒ"ààÄ®Oïg­N_ï±÷ßPˆ²¹ÝÆ+Ì®9›}61þ/ @ŽŸW@ °hº¸é¡ÀÁáGr=1°“Õg¹n[™úÆ`Ås¶ŠO,~¨ªäh`0Æ 2xòðïÝã¯˜îwÝW9ó½b X„W*®ˆR<î¦þÐL÷»‚Ü?Zùp°Ç 2 6Ÿn_þññæîûWÔív~4?õuã&ñÔ/É	ãZæ¶2ÅÕáB»Ý…N;(>”g¥laþ?ªªtõÕPŠ¬ ÝÏžüûðâ
+ú«¤4@$†]90ê  cç)3endstreamendobj199 0 obj80 endobj200 0 obj1557 endobj201 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 65 /Height 74 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceGray /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 65 /Colors 3 /BitsPerComponent 4 >> /Length 200 0 R >> stream
+H‰Ì—ÍrâFÇ¡$$!Ÿë¼^¯½UIU®¹å–C*§TnÉ1yŽTåÈSä”Kªò*ëµØ ˆtdÖ»6H›ª¤2.
+èÿLÿº§»‡$þõEþo[ðç›Í?ÚÍ	ø(‘Ð>Xh¬G[DÛ3°PÁÇµ‰}
+0LHlü5]ñ%P ÌY–å¸$Cüõj	ïâxA8AàyŽIø+oáyÞrŽÄõ8^H‰¢À'ko>›Í(W0,Ë§$9-‰Br³šOg:[,W~L/€a’R’¢ªŠ$$ýÅÔžLlXÅô‚0„åy1­d4MMÌzf[£‘å¸‹U</ xV´\.›‘ù„çŒÍÁÐšLï0ìõ‚2´\>¯g$ÎŸMÌ~`N¦óX ‘!'lYÓó…BN™åtÔ7Œ¾9~x†}ÈP”3¹B±˜×d~3n¯oNÜ‡w{A €¡ŠENà9£~¯ÛX¶ëmc¹2T³äÓÏKp„4@@ ?Oç¨- !z¡T*ä~³°M81}É§½ Šr(€Ñ h"}xÈ°D¾ù.#±+w<0z@qìÌ¼èdzÀ°TÔ)‚‰iôŒþ R
+<áÅ¢…¬2 †#ÛG_ëwÑ>§À0Â†£	B”ÀC†E]I1K× ÀðIäC-DÈgÄäÚµ†T B.GUÇ€¡œÉæK4XN¾ýŠ2°œ‡eeƒ€a¾i€çpeOw1$ï©@NˆgCõ ã1D{AR2„½Jô2“ÏÎvB|ÏœÜ3€ €B>ÌC¼JIâ¾¥’0óÅr)Ÿ•ñ.Òr y´Ÿ!îI@Ó@Â<,ßßEb×]Ù	1 kÚÙí]ÔU,“–“ÑØÙË÷Æ~
+.#­GÉÕÔ
+Ê‰{j"ös4æXèjÁm.èš”\ß—#¸‹„M®w2 ôÀ˜çAÓ´¨çð2Ï'ÈÓÀ]ìE€™È´Ô”(IiUËB_IsaAëaÍ¼½é-”Ò²œ†¬d2Ð¹äa¿KËM£=-‰`
+ÂÙÕŒ¦Š"+²”b7^„ð*íËÃ0Èé'ºžËj*t÷ÇøÔƒNÇ mï]¤'€Ê—Êp³jšX;wÚ—æ‚^€/*ÙBùY­Z)B[…ÙÀƒ$èÞµÛÞ0º$c%’2ùr|ýýa­’W%Ö_8#£sÛºiw3ã>†áD9[¬ÕOê‡ÕBÆF»Õl4o:O"Øáú ©zåðäôå‹ãZAå}×2ÚÍëëëÆmw0Žœ „´V¬Ÿž‘Ÿ~=©viîZ×——W[ àFI@!%çÊÏO^]\œÕkù4³÷nþº|CÌÉÌ[nÃø¤IQÕŸž¿…jNL¸f§yuùæÍU³m˜ö,b>@¤L¡züòâõùíÏŠÆ¯A»
+—×­;cäDugÈFAÖŠÏëgç§E%éMŒÛÆÕÛË·ˆÑšb.míŸòbKáìüü¬þ|˜[½ÛÆõÕU£ÕŽ•
+  èåƒ“—¯ÎNÈïp«©Ù½m6ÍV»‡¹ˆ õÊAýôôÅQ%'¨©ÝöM«u{×Ðþþ„Ç^„ÉT~~\¯A&ðkhÝ;XÚß£[K PªV‹Y‘üò3LHP×qF²°¹EJ^„ù¦R«UK9è+s{4ìã¨kMÀƒÇeñ‘ƒ¬AY(—è|1³G¦iŽ¬±ã"‚UÔ„@#óŽ£¶5|ùÅ>ÀUô,(ŽrFËfU‰g|ÏulÛvÜœE§´ˆ!'œ1$*«$°d½˜¹Óé¶§ c<"i…ç±;ˆPV7ðl#•Â<Ü?Þ#”vlQ—$þŠ¾üBóÄÓö¼ÀNËÁb“ðtô×K4§øâ¾`i¯e±]“ÍÆ[h¬þGØã.ø+?€·×üqF…ÿß„+îö[‰D`OÉm¢^¬»4[‰è_ÿ“->ný—[ü-À MH“endstreamendobj202 0 obj<< /Type /XObject /Subtype /Image /Name /X /Width 65 /Height 74 /BitsPerComponent 8 /Intent /Perceptual /ColorSpace /DeviceRGB /Filter /FlateDecode /DecodeParms << /Predictor 15 /Columns 65 /Colors 3 /BitsPerComponent 4 >> /Length 199 0 R /SMask 201 0 R >> stream
+H‰ìÍ1   ×?ôlàçH;Ï¢P(
+…B¡P(
+…B¡P(
+…B¡P(
+…B¡P(
+…B¡P(
+…B¡P(
+…Bq+À K6'|endstreamendobj203 0 obj<< /Subtype /Form /BBox [ 32.9541 23.00879 37.55566 28.05371 ] /Length 204 0 R /Resources << /ColorSpace << /CS0 145 0 R >> >> /Group 205 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+1 g0 i /RelativeColorimetric ri34.36963 28.05371 m35.42334 26.10742 l37.55566 25.51465 l32.9541 23.00879 l34.36963 28.05371 lhfendstreamendobj204 0 obj137 endobj205 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj206 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj207 0 obj<< /Subtype /Form /BBox [ 32.9541 23.00879 37.55566 28.05371 ] /Length 208 0 R /Resources << /XObject << /Fm0 203 0 R >> /ExtGState << /GS0 206 0 R >> >> /Group 209 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+q /RelativeColorimetric ri/GS0 gs/Fm0 DoQendstreamendobj208 0 obj45 endobj209 0 obj<< /Type /Group /S /Transparency /I false /K true >> endobj211 0 obj<< /Subtype /Form /BBox [ 33.43604 24.33008 66.56445 64.46533 ] /Length 212 0 R /Resources << /ColorSpace << /CS0 145 0 R /CS1 138 0 R >> >> /Group 213 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+0 0 0 RG0 i 4 w 4 M 0 j 0 J []0 d /RelativeColorimetric ri35 25.57617 m65 63.21875 lSendstreamendobj212 0 obj91 endobj213 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj214 0 obj<< /Type /ExtGState /ca 1 /CA 1 /BM /Normal /AIS false >> endobj215 0 obj<< /Subtype /Form /BBox [ 26.81592 15.30762 45.22266 35.4873 ] /Length 216 0 R /Resources << /ColorSpace << /CS0 138 0 R /CS1 145 0 R >> >> /Group 217 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+0 0 0 rg0 i /RelativeColorimetric ri32.47852 35.4873 m36.69385 27.70117 l45.22266 25.33008 l26.81592 15.30762 l32.47852 35.4873 lhfendstreamendobj216 0 obj141 endobj217 0 obj<< /Type /Group /S /Transparency /I false /K false >> endobj219 0 obj<< /Subtype /Form /BBox [ 26.81592 15.30762 66.56445 64.46533 ] /Length 220 0 R /Resources << /XObject << /Fm0 211 0 R /Fm1 215 0 R >> /ExtGState << /GS0 214 0 R >> >> /Group 221 0 R /FormType 1 /Matrix [ 1 0 0 1 0 0 ] >> stream
+q /RelativeColorimetric ri/GS0 gs/Fm0 DoQq /RelativeColorimetric ri/GS0 gs/Fm1 DoQendstreamendobj220 0 obj90 endobj221 0 obj<< /Type /Group /S /Transparency /I false /K true >> endobj223 0 obj<< /Type /Group /S /Transparency /I false /K false /CS /DeviceRGB >> endobj224 0 obj<< /Height 128 /Width 124 /BitsPerComponent 8 /ColorSpace /DeviceRGB /Filter /FlateDecode /Length 225 0 R >> stream
+H‰ì×T“çp¼ jª[£RZŽ‡¶P`áÊ°Ô‚X2´Öá:Ú•ÚbGuxf·ìHç¨Rñ"Ò$ŠãR‰bnŒÜM•©‚RÐ‘Eä&Â»'ù4~$!|ðªäžãá„ø%üò~Ïó!cŒ1f\DÕÚZ‘™‰û]Œ—”r8|›\(ÜïåyN__ßí›7##ù––„¶Ñ|ôÚµµBLm4§6===µEE¢  A‘æÔ¦«³SÈbéCm4aÚTªêìl¾‹Ë°´æ†EÙÒ"ON6€Úh®g`6Õ×DDéô‘8ÍõIooï…BhjJµÑ|ˆ<èé‡„PN­-¸wpÿ‰OKîwwÿ(‘äøûž¶ÑRž–Æwpmä~÷î¿CZ››Kâãù66c¬=Íá¦nih0X¨Ç›ycmm›-¤Ñðjƒ·Ç¨äþýû9[¶`ç´º:;qóP™Žöv…H$ðòÂ;Ìï*•U<vO}ªM¥Â­5ÒÈ¹\¾vÉçØv¦úz!ŽÎàRµ¶âVÔ7×««¥»v	MM±£°àÛnKm¶¶¨HŒÝj<˜Ã|²XØ‰žoseKKYj*v“Ñ.˜G¸¥Õ)Žå3™Ø5Æƒ9,!»ÃXVcm-Fsø"ƒ]`ì0ŒæÏÊ7ÇçÉv±¯ŸJJ0šçøûcûª“Ë1š«é™³eKuv6Þå¼M¥Âî0ª¥‰:;:0
+Ì­º:ì,£Q¢M›®äç÷ôôà$5vjKH£µ·µáv*E`W¢ªø..°ôööâFÕ>“‰Ýj„UÙÝÕ…rÁ.6’’„…u´·ã&v°»\//Üx;S6@Ür†;àp‹xÛ²ºÀ(¡ûÎ4“Õ‡ˆ²ÿ<Ù7œ•Y^ß¬ÂKª3Øõ/÷×ÙIÅæGµÔƒà—×µà¦}b°KêYðç\iNmrm;&Å­;Húúú°cêÃ«${Nˆv;Æ”ýë/ÍYûÐ¨OªÒ×d¦X|G~4å½§küåúuìžº+4º4Yl	çAðÉòO;|kÃO:dÁBx¶äš0µ{èrŠJ ·wÜÒ#çr±«Î`ÜQÞÕöp ß}ï¼>àÙaÏÁý0âÑ€xxPr©–†ØR´-eà	Dü'ñÛðãÄ·úƒûa„¦¦#Î¿^]­½¦$,Œp¾ƒôaí!ï×Ãµ¶ßVÚßîjæMÛ=Áç'G‘šHwW×ˆ´=<”-ýw`Yt4U÷Ë­º:P"ÀéÆ'x÷#T©ˆG´øîñ''ú†òûW¿ÓÔd qªôô¼`@@8| pAø¦I˜ÃZ8œ >€„PQŽ¶ˆG¢Ô¥Æß~-ËÔ/zÒ5û˜÷Ï°–@¨âñlmþ{çUàP7ê> kaëß`àjÛC(ç0E«Kü¨DðÈ¡Çø‚YÄNñ‹yIuãé®]CüÕC…àÐ ˆk}J»®Áj´cøÊE’£H§ù*åÆhüiN¾;aúÚ#S#­¹9:–ú†ïæÖïÒéylöµ²²žÁZÇƒBó¦úzâ² M´bÒÄT7j¢¥à }IãQÞ÷(ÿ¸¦à‡ïP<øG4øNá\ú†¸ëæá6'/-àÛàKQµªkÂí°€&5Ù7úÿÇåãN€ƒs*LDE'‘Œ(ø9Ž
+à³ˆCR·ˆ”ù¿û~Î¦øüË8Íá$Û€SÝ/pª´¡NNÚ+/üèôa3VÌŽkYÚNôðèÇà ìèû›uì8Jñt1]<.¦ ’$T¿â ‚·÷¤.ú8VôBÅ­Ëá;
+Á%'^LHÐ^Üó¯™Ð‡iëbýyg´ËÉa84 ‡6r&£âÀ¨P†ÕümœÝgQÅ¨<•¥¡K€Ïé”¹î8ãøÅ)Û­IªönŒVTEÈbQeà’I“*22´áUÍ
+ˆƒVì°;ñ°f!ö“”½ú4$$ØoËSLe®•ÅvÎ?. šs¨
+ü÷VøìÎZñUÆÚžÇçDYÚÛÚ¨—˜šþ˜›«½þÛwç~ð´b¨Šóp¶5¥ÞLò"è!iHž…*V&¤XÛ/ÞŸ{BˆŸÏýýaÀ7ÙÇ.Ôà£¢,|&“ZpéÔ©ééä—ðÈf€Z¾ïÔ1Í63‘XT`tr‘ì*…6GÚ3ÐÏd@–,sÚðçÃ;Žl•ÜVu`r¢2”µqÜÌ,F“íÝK~‰’«¿@ÖÔÉ?ðxÄHG0‡‰™‰Ê/ êðŒèæD˜¯9Æ¥Kq)Qªæ¦dòd<ßÜ<×Ç§ß«ìÏ,³Û¼×vó7ÛRBÄç‰œØOjÌ@|T#EWŸdN$00°þÑæÿì†š®àS¦äMŸàsæYZvwu‘_¥±©eÊ4Úd³éÖ+?uúÓiV\flG>r*ä¢âÓ¨Î9aîîûîÐìÏºü­º:JÚ8€K§MËŸ9³à¥—Š^~¹ØÚºÐÛ»¯¯OûBöööZ±ùŽ«~’âðeJwð?ÒD$KÑôsè-`¾-ò+æsss6›­T*áâ]™™W®`R^äÉÉTÍÍ¼3
+fÏ.²°(f2Kmm/½ùæU€x8–d.†ír‡/Rì¶&-	æ¾|ÒýïgŽf…]oO•ì9Wvä¬>æD¶xzžZº”x?ur9^L=#¦`nø/äÓé…óæÉ,(}ýuù²eåË—W­ZÕüóÏ‡¬>U\é¾3ÍöÓ$›O¸P¶Ÿ%¹|yÚëo™÷ñ·ÅIÃO•Z2m†¦^úÆ›ÝÝã-,ÈoI!áæÔ+.Šçæ¬Y…sçÊ¬¬J–,‘;9•»»xÍÚµiÞÞýÑ‡ïvt§Ëþížõ«aŸq=íI2_¹.pPê™3gº9;'2ƒ¾«ò´4ÌšzDÕÚJåÜ|å•¹ƒC™›[åÊ• ^¼~ýŒ)SÈh¹¤ïJÚÀ&)ÿ©9A¤W6\mT*ïuÁÓàÉïººþñ­·ö[[ëù®
+""ÆœpØ¡CÙÜ´´,^´è¢½}™«k¥§g5‹¥xÿýÅ³g“Áw8;_NMm¨©¹ÓÔD¯<èho‡º«T–¥¦æ±ÙÂÕ«yc¡¡1õ4@ƒÁÏÍ_TÏÍ…Kíì.¹¸T¬XQíë{yãF?kk2¸ï‚ÕkÖT¼óÎ%gghøÐö¡AG‚¾ŸÜ2pYuË2ì¾Ó”hÓ&Ü¢º#çriãO˜›°¨TxxTùø\ØãêJ·¡Ó‹||*½¼à.€{îØ'áÃ‚®Wƒk‰¹ÀÃ·¨îˆCB†>ôÜ|ï½šõëÓW¯&ƒCK¬Z#ž wt,Y¼Xöê«…L˜Tr(!†[Twàf¤Ü\æç×onžðô„bÌ¡p‹êŽÅ–¹Ž]ÅÛvh#dðË–A«†SþöÛÐ|vòyó )©;¹™™œŠÆBToo/nTá»¹\×®âÇd’ÁaŒÂ0…‘
+ƒõÌ—\Í÷Ç‡žTºB(¬õÂX§¡'³¤”Q´–Çº³Jkñ²;ÜÝ»¦a­!Òsz ÔÅ2zt
+¥'…<lk»WòZÌÃ•K¿ûùŸ_ýû;Î9étŽïë÷òJ¯çüþïß÷÷ù|¾°W˜,¬†‹q•«äÊjr¬§mmê†*§òmlz\zV±µ¥Ye‹µ58‚"ò9ÇÑecÇâ°pd88FU”
+ëÞÝ»ê†*§ŠÁŠe•l	ß„pAj 8ˆ$B9êg×¦&uC•Sò=T®oÎ™Ãøæ¢EÒ}sáBÆ7gÌÀÃø“®@NeœW*sLyê†*§0ñ)¤*ßDÞ@ê ¾)zï=Æ7½¼fŽÉ¾ÑÊŠú&®€¤oêë+1w_Õê†*§ëêäw¸Tßäñßtq¹äé¹|Ò¤}ÓÖ¶Ë7_œ€”®*t}îéÙÚÚªn®²êáŸÊjï|³úí·ßœ7ï¢‡Ç›î¾‰ƒè9y<ø&wÎšÅçóÕÍUN&8Èp|é®lôhÆ7§N=om}ÁÑñ¢»{öüù\ÇÏ˜@!5ÈŽÊ|“»Ö‰³Shh¨º¹Êª.I§êÊ‰…p®oŽ_5eJÍÌ™ŒoººVxzëës›<zî\FÆ]]ñ€*}“»þÉãÑÍ¤¦¦ªmÕÞÞþmVO´µ»€Sßœ4‰úfý‚È$¾diÙ!ãŽŽ¸¸'âj¨À7¹+ÖÄ„îÇÀÀ@$©›nÕ…}(Ž(Œžèé1À Ð‡JssÆ7ß}·nþ|¤n	ßt45mX¶¬cü±³ƒàW˜™•£ßä®ŒáÃÙ]™šš¾²~Z4dC½-¦§cŸ¡C±à4¨XX &ì[Û|ÓÐ°ÒÇ‡Ê8ÆŸjKKP‡Œ«Ä7¹+OG‡»7uÓ•^—òó%j]]†6zŽ9r$Ð1ÀiPqr‚td¿ÿ¾„oæ¸»K‘q#£ßäÊx?§ËÛÛ›‹] ¨°ôj{òDhbÂ4¶¡!p!‚3lBR ÜÆ†)¾éèÈÈ¸»»”ñ‡õÍþ—qîºÛÒÂãñtÖ«ì§·oÞ+ˆ0PCQ° 
+Í<sÔ(.ðOßy§Á×jƒ¬Ž‹ÀÈ8†çú¦*›ëÑƒÃ†(.J^(J¼¯èÆaýo·ï«vW5]¹‚ÆF¯Â.Ñ´XH)Œ†óù—}|VL™"é›Ë—ÃOáªðÖîãZ€cÝ»{ïRR‚¦1H\ #ÀAäœ»±rg¡éG©¯¹Fq—EpfHb)NA-Øk¦OGÇŠìíÑºXõâÍ¼uölIß\²ä²·7r#3þLŸŽñyR•ãOOëNS}—¨¨(mmm---MMM±–ÛºíÆàE—y,ûÙh~UG'`‚{öìY]D8h_õó;âå%é›èüz77‘ƒ¦$¨&&éãjcýTYÉ¾‘¿¿¿®áàY«µÅhyÄhzDkð£¹3äu}bÞØ˜$•<z^eÌ###1J€<~n¹yóÚ'Ÿ\
+:8fÈn“Ç8;Ó4ÎÈ¸;þHÈ¸*}“»nÔÔ°otïQÛèÂÇë{Åé~«ãc•îWqx;Éß&^ß“¼°‡'|Š¾õMŠDÃ·>|¢æ|>Ÿ®šjj~Þ´ÉÚÔ”<ØÊ
+UaÒ8+ãìø£>/òönùý÷çÏŸ³¯sÿQ›ËWGÇRF.Ûó—¥I¶ßglºsr')Œ$…;H°sÉc­½qÔ88‹]ÌÑä,muTHH¸“™ÙõÕ«a=<¡*L71éJãª•ñ—_jkÜ—ž=>Ž*ž´R@ú«öþ5ÿhÆS»Iñ.RÄ%ÏÅŽ5#2Me"ƒ4Å²µ··Çorrr$fº›×¯ÿRR‚@ëdšÜÂáªòBW*ðB=½b_ßsÑÑMW¯>~ô¨½½]Á×)Ýrü2göú¬×\#ÌK%g÷Ó‰¤”K^ìýj©-˜˜È¶=
+?‹D"úäógÏþhn¾’Ÿ_¶jUGVá„Ã>Ê8$âlxø…#G~mh€›ËØ0Ü½Ù[É­5I§wÒcóñ€Ì‚¤j?©ØGÊA>‰œŽ'%R±³Ì±X‘éW…As™ëééqÿÛÓ(÷ßÇ›oÝº^^~>3óÔŠ
+[4pÙ¶m5ééÀKÛøéÓ§Šo¸µµÕ´Ók°yÀg»¢æ§æuÉg>/	L8•óäÂQ"Ê&çA>ƒT¤‘²=äLB'v±ÈHiõ€úÃl«76÷un‚•—5ü»òÚml¬®±¥á×?·ý­òZÏ…+ð_„.FîêãÎ»:Ab«8ìvç¾ÜðC5›²*ã«j‹É•|ré8©Ë!µIõþNì´Û£ÄÚ.µÕ'nH¢ÌC÷W¼Üö|¢ŽÕÙ¬;8|Iâ¸•)S3ìþvÈ-,×oWÑú´²¿ØÚp¼¤^©¨”Y¦/Æ*¶Œç¸û†eÄ–‘ŸKÈÕrùGRìHu9‘¶Ç¡D«s™/.:Øyù:³ÒpI"æ‚×?Œá›4Þ/ÓîœÙ^ßžŒâ­Ýeô9
+zŽ$‰¾’*žj,	£ï^ú¯/xnÎ‰F·ç’:ˆL©ÜKÊi«G“STÕ»3ÿ{s.+/½Ú´ˆ÷Y&Æ.Œ`ƒ=c1ŒZ¾gú†L÷Ý9+’O„dú*»lóªÁzú²wÎ-8×+EûQpç6|‡àÔ¯SZ‹ÓIyr§ª³Nº­ö—`.ºq1ÞbÚsã€¤¥?f‡·âëp¿~ 5'H½\M>—«8pLLj.®[¨¸põ \Âý©Ù‚ýÁàxž2Ÿ»gÿ·ó!_¸P)ä,¬ä09’\,%×V…†Èß¥JÚÁƒR¥Hq¾öââ¦Ö>–®¾WèªøÖ‚dyÚòÌ¡ü8„eiñ!œ#Ì_‘@Já Ð4J¹æoZL–K[)6Š#£H‘ë(UŠ´'TzÍ¸ímÒè‚ 'ÓC{«ç©Eôa0÷)>„ÄÇâ@q•à×øF–ùñÖj›43&¥ RfeÝ}¥×<?¹ñ$®ö¿HÕ¾1/•{›[LýRéó3#ÓðQ=1‡¶„åDKÝ¤Ž®þ‡A¡Û×r?¶¶¶¶ººº°°pÇŽ...NNN†††0`@£ÃñÑ«AÏ÷Gœ••%ãO,í­v
+Ó‘Ñ{ÅœÍç!‰¥Š7¹Îâè°‡'º3O%e™¤@duxHláJðà5	ùŸ'ŸE’\ÿ]¢¿¿¿³³³Ç377711122:t(fUMMÍAƒ)…9t›"Å\C©Ò‹Ã˜Rä¥~Úèñæ…Æ´]¡)‘Oç„óhRÜ“rçPD¹Ì‘…ôá‘iøsiÌ=DjŽ‘F¦ÆÜ}Î,:ÖZUH.o-)_Yè~ráš(++«iÓ¦™™™7Ž×××	à)Ì‘"…pQªr_JFu×.Ä’ÏÂ¾H=Wòå±3G‰!W1E<ŽÎ¸gOMnœÐ+a¡q‡%Á_³ÆÍÂ·ãÐ·‹2Ù}ÚñçîkÌÏ#Ñü8‹˜Ær×MÇ¿Ì±[›aii9yòä	&1‚íp---
+œ2—¸ûvŠRßª2
+¾,qSð¥ø}Åµÿøí*ò‰ÈsËý¦¶=¶—”áÅ;;\RU¸ÌÑ«l“ëSdìóô(óÎÜRGJ`ÙôR!ˆ\‹}¾eÿöË/¤©(ŽãPDÈ(¬—òI¡¡‡0È!faP”ö`X‚+h¢«VMsÚbË•™5¥¨ÒÑÀ…=DHõƒ 	*ÉÑŸ—õÙ=íp¸³¸æìªìÇïáîÞsïÎùœßùþ~¿²óÃ>8ˆ<!q;5Ê$·œºSÖØSRß-ÂÛb±€Ôjµ¢á6›­µµµ¥¥%‚ÔÄŠ]
+´Ùeusí¡‘Ê³‘òÓ}¬¢)þ˜U»µ‚Ü¥IŠàF”c_Äø‚#]ÙÌ¯hòBú`ÇÙ÷­‡v4E.B¸7õç‚È^eÐŸŠ½ÅÇBë_?™%b37J#€£ÿÙGéë·ŸUŽû¥ÇÃ¬‚¢b›³§=ùD„·s*à‡2oâ›nœƒdÎë’y»Æœ?Òä…PöjØI¦ÁÔÈ´ÇqPÿTŒ G+o»µæ ¿p¿/öúCŽIåÎH9eoÞÚÞ<°V[EÁ>Oa­§ÜÕÝ06 ^ïSÃ[ §©48‡Äø„N[TI¡ŽšÝ£‰ÌµTÌŸq~²@ãPTçgž+öº_%>æö%ùƒÄÄ*–ï¹ºlwçÒ]Kª;ïtðn8ã[}´KE=-IQM¾K¡¨“B=ƒýi§FÂÂ»2¨yÄ€¶ä œçl øÏz»±.(h/ªJ;Ý"®£M•b0iêŒs!¾@'¥u‰‘,Ù¤#íiÎ.Í…Üá†îŠ¨ åœ€YÖG¼ªÆ­£ÚS`ÿma¤KUÏ`ÿM^À¿œá,“^l÷‹¨hô=ËáªçŽAXxN¾Fß$wP”è:ì‚¼pÿ ü)žÖEÄÄtayÃÐ%Áœ~JUu#ÌÏM>ZwÒ+€WØï™½”ycj¨SéB]…¯º¸¿ùRP¦˜|OËšÃÏ%öG@F{6|éŒ)udBçf/bþ¹Xb§-UË˜l§/P‹UÞ5{úóÕTì‚|e8¬&V®¹Ã}uXøÍÙÿre;»Ûú“3Þì)/KŒOè~Jg#Ížì‚²Ï“ß‰ájÇÙ¨â\s‡û<5{‚sÚ~	0 Œ}ñendstreamendobj225 0 obj6474 endobj226 0 obj<< /Filter /FlateDecode /Length 227 0 R >> stream
+H‰¬TMo9ýýê·«Êå	å@†E‹@ÚK”Ã0iB£™	éL@üû}îöj™ q˜i»ìúxUï¹_ÝlîwÃþðf8Ü¢'Oú³õõð×4^{ºPOÊtÙŸßo‡é_£'O—''«³®¹þ:LÕéíxØôhÙËãþïñn|Ëaº¨?›†Ïãð¥íž]‡õ·‡ãþ0\µÝjÜí°y¿ÞÞawz³½™è"š©‘x‘Ðþ/û÷ÛõaI×î¾Öû»OëiØo¾6ÛÉÉÓÕiçó…˜¼KÂiºî ÂIÉ^ñµ$èü9Œ#)}¡@¯€ñ#~/èâÒÓuýù€„ãça.iÜ‡iÜÐ4v9¸˜,eJÁ-Áh×åèÄ,GŠÙ™E6Êâ4²*Eqì½JæJ– Q€pÈ´ébqVJd²ÜbEuÔ¬úe”ÙYT\ÇeAÄêg±×ÔŠ¥ê–ÓœÕK¢ä[AY]TQSŠXÆ$”­Â¡/ZýØÕ\LÁmºÝÓî¶ëŸ¿ñt}×¡›•8˜„i³ëú?wžV7Ýëî–pëµþ£6^l, •½Ï$É‰÷‚² zFTï2'ÔÇÈ¨«€vŠÂ‚¶ä
+‹”¦MÇ>:ó-ów>äÄ”Jv!F$d’a›®ÄEdËavK©()Ò1[”ZQj.3®ùXÁ0)‰4µ`µÒv)Î²z¦‡¿oeYZ€doä#]“#6]lÏ^þŸ*ù'UÙäô²\¤¨’ÐÇE¢¿"Ë[ÊÏˆëWI0µ95àòC@ú»Ÿ™Ï·Í¯àÁðÍ¼`øÉE	3‰µ8V®T(Py#Z$R _ñ"d-V’ÑW…‰€Fzb²ºGç¹ø@7ÇXé4•Ê3°°„™…Òâpv2+^Ð² ‘Îˆ´Õ‚Fë¬'dÂƒÃ!ÚLù9ê+É§êæ«dè!¬ïy÷:Å”`CŸáh8b³ÿÆü  üœ¸endstreamendobj227 0 obj758 endobj228 0 obj<< /Type /Metadata /Subtype /XML /Length 818 >> stream
+<?xpacket begin='' id='W5M0MpCehiHzreSzNTczkc9d' bytes='818'?>
+
+<rdf:RDF xmlns:rdf='http://www.w3.org/1999/02/22-rdf-syntax-ns#'
+ xmlns:iX='http://ns.adobe.com/iX/1.0/'>
+
+ <rdf:Description about=''
+  xmlns='http://ns.adobe.com/pdf/1.3/'
+  xmlns:pdf='http://ns.adobe.com/pdf/1.3/'>
+  <pdf:CreationDate>2005-10-17T20:40:30Z</pdf:CreationDate>
+  <pdf:ModDate>2005-10-17T16:43:20-04:00</pdf:ModDate>
+ </rdf:Description>
+
+ <rdf:Description about=''
+  xmlns='http://ns.adobe.com/xap/1.0/'
+  xmlns:xap='http://ns.adobe.com/xap/1.0/'>
+  <xap:CreateDate>2005-10-17T20:40:30Z</xap:CreateDate>
+  <xap:ModifyDate>2005-10-17T16:43:20-04:00</xap:ModifyDate>
+  <xap:CreatorTool>Adobe Illustrator 10</xap:CreatorTool>
+  <xap:MetadataDate>2005-10-17T16:43:20-04:00</xap:MetadataDate>
+ </rdf:Description>
+
+</rdf:RDF>
+<?xpacket end='r'?>endstreamendobjxref0 229 0000000004 65535 f 0000000016 00000 n 0000000088 00000 n 0000000152 00000 n 0000000007 00002 f 0000000311 00000 n 0000000853 00001 n 0000000008 00001 f 0000000009 00001 f 0000000010 00001 f 0000000011 00001 f 0000000012 00001 f 0000000013 00001 f 0000000014 00001 f 0000000015 00001 f 0000000016 00001 f 0000000017 00001 f 0000000018 00001 f 0000000019 00001 f 0000000020 00001 f 0000000021 00001 f 0000000022 00001 f 0000000023 00001 f 0000000024 00001 f 0000000025 00001 f 0000000026 00001 f 0000000027 00001 f 0000000028 00001 f 0000000029 00001 f 0000000030 00001 f 0000000031 00001 f 0000000032 00001 f 0000000033 00001 f 0000000034 00001 f 0000000035 00001 f 0000000036 00001 f 0000000037 00001 f 0000000039 00001 f 0000002014 00001 n 0000000040 00001 f 0000000041 00001 f 0000000042 00001 f 0000000043 00001 f 0000000044 00001 f 0000000045 00001 f 0000000046 00001 f 0000000047 00001 f 0000000048 00001 f 0000000049 00001 f 0000000050 00001 f 0000000051 00001 f 0000000052 00001 f 0000000053 00001 f 0000000054 00001 f 0000000055 00001 f 0000000056 00001 f 0000000057 00001 f 0000000058 00001 f 0000000060 00001 f 0000017620 00001 n 0000000061 00001 f 0000000062 00001 f 0000000066 00001 f 0000035483 00001 n 0000035506 00001 n 0000052874 00001 n 0000000067 00001 f 0000000068 00001 f 0000000069 00001 f 0000000070 00001 f 0000000071 00001 f 0000000072 00001 f 0000000073 00001 f 0000000074 00001 f 0000000075 00001 f 0000000076 00001 f 0000000078 00001 f 0000052897 00001 n 0000000079 00001 f 0000000080 00001 f 0000000081 00001 f 0000000082 00001 f 0000000083 00001 f 0000000084 00001 f 0000000086 00001 f 0000072294 00001 n 0000000087 00001 f 0000000088 00001 f 0000000091 00001 f 0000072317 00001 n 0000092563 00001 n 0000000092 00001 f 0000000093 00001 f 0000000094 00001 f 0000000097 00001 f 0000092586 00001 n 0000104831 00001 n 0000000098 00001 f 0000000099 00001 f 0000000100 00001 f 0000000101 00001 f 0000000102 00001 f 0000000103 00001 f 0000000104 00001 f 0000000105 00001 f 0000000106 00001 f 0000000107 00001 f 0000000109 00001 f 0000104854 00001 n 0000000110 00001 f 0000000111 00001 f 0000000112 00001 f 0000000113 00001 f 0000000114 00001 f 0000000115 00001 f 0000000117 00001 f 0000108480 00001 n 0000000118 00001 f 0000000119 00001 f 0000000121 00001 f 0000108503 00001 n 0000000124 00001 f 0000126953 00001 n 0000127036 00001 n 0000000125 00001 f 0000000126 00001 f 0000000140 00001 f 0000127480 00000 n 0000127504 00000 n 0000149759 00000 n 0000149783 00000 n 0000168231 00000 n 0000168255 00000 n 0000177950 00000 n 0000177973 00000 n 0000182019 00000 n 0000182042 00000 n 0000184252 00000 n 0000184275 00000 n 0000184304 00000 n 0000000161 00001 f 0000184385 00000 n 0000184406 00000 n 0000184429 00000 n 0000186043 00000 n 0000186407 00000 n 0000186437 00000 n 0000186794 00000 n 0000186816 00000 n 0000186893 00000 n 0000186975 00000 n 0000187267 00000 n 0000187288 00000 n 0000187364 00000 n 0000187446 00000 n 0000187770 00000 n 0000187791 00000 n 0000187868 00000 n 0000187950 00000 n 0000188326 00000 n 0000188348 00000 n 0000000165 00001 f 0000188425 00000 n 0000188775 00000 n 0000188796 00000 n 0000000166 00001 f 0000000167 00001 f 0000000179 00001 f 0000188872 00000 n 0000188893 00000 n 0000188916 00000 n 0000190388 00000 n 0000190783 00000 n 0000191137 00000 n 0000191159 00000 n 0000191236 00000 n 0000191318 00000 n 0000191609 00000 n 0000191630 00000 n 0000000187 00001 f 0000191706 00000 n 0000192038 00000 n 0000192059 00000 n 0000192136 00000 n 0000192218 00000 n 0000192593 00000 n 0000192615 00000 n 0000000191 00001 f 0000192692 00000 n 0000193042 00000 n 0000193063 00000 n 0000000192 00001 f 0000000197 00001 f 0000193139 00000 n 0000193162 00000 n 0000193185 00000 n 0000195312 00000 n 0000000198 00001 f 0000000210 00001 f 0000198769 00000 n 0000198790 00000 n 0000198813 00000 n 0000200653 00000 n 0000201030 00000 n 0000201386 00000 n 0000201408 00000 n 0000201485 00000 n 0000201567 00000 n 0000201858 00000 n 0000201879 00000 n 0000000218 00001 f 0000201955 00000 n 0000202279 00000 n 0000202300 00000 n 0000202377 00000 n 0000202459 00000 n 0000202832 00000 n 0000202854 00000 n 0000000222 00001 f 0000202931 00000 n 0000203281 00000 n 0000203302 00000 n 0000000000 00001 f 0000203378 00000 n 0000203471 00000 n 0000210092 00000 n 0000210115 00000 n 0000210953 00000 n 0000210975 00000 n trailer<</Size 229/Info 3 0 R /Root 1 0 R /ID[<67115efbad7488c37824388130539d5d><1d9e36fbb5c7afd0fa6d2e20b13122ab>]>>startxref211878%%EOF
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.classpath ./tools/storyboard/org.tekkotsu.ui/.classpath
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.classpath	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/.classpath	2006-02-14 00:22:32.000000000 -0500
@@ -0,0 +1,7 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<classpath>
+	<classpathentry kind="src" path="src"/>
+	<classpathentry kind="con" path="org.eclipse.jdt.launching.JRE_CONTAINER"/>
+	<classpathentry exported="true" kind="con" path="org.eclipse.pde.core.requiredPlugins"/>
+	<classpathentry kind="output" path="bin"/>
+</classpath>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.cvsignore ./tools/storyboard/org.tekkotsu.ui/.cvsignore
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.cvsignore	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/.cvsignore	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1 @@
+bin
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.project ./tools/storyboard/org.tekkotsu.ui/.project
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.project	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/.project	2005-09-08 22:09:54.000000000 -0400
@@ -0,0 +1,28 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<projectDescription>
+	<name>org.tekkotsu.ui</name>
+	<comment></comment>
+	<projects>
+	</projects>
+	<buildSpec>
+		<buildCommand>
+			<name>org.eclipse.jdt.core.javabuilder</name>
+			<arguments>
+			</arguments>
+		</buildCommand>
+		<buildCommand>
+			<name>org.eclipse.pde.ManifestBuilder</name>
+			<arguments>
+			</arguments>
+		</buildCommand>
+		<buildCommand>
+			<name>org.eclipse.pde.SchemaBuilder</name>
+			<arguments>
+			</arguments>
+		</buildCommand>
+	</buildSpec>
+	<natures>
+		<nature>org.eclipse.pde.PluginNature</nature>
+		<nature>org.eclipse.jdt.core.javanature</nature>
+	</natures>
+</projectDescription>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.settings/org.eclipse.jdt.ui.prefs ./tools/storyboard/org.tekkotsu.ui/.settings/org.eclipse.jdt.ui.prefs
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/.settings/org.eclipse.jdt.ui.prefs	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/.settings/org.eclipse.jdt.ui.prefs	2005-10-18 15:11:19.000000000 -0400
@@ -0,0 +1,3 @@
+#Thu Oct 13 13:33:12 EDT 2005
+eclipse.preferences.version=1
+org.eclipse.jdt.ui.text.custom_code_templates=<?xml version\="1.0" encoding\="UTF-8"?><templates/>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/META-INF/MANIFEST.MF ./tools/storyboard/org.tekkotsu.ui/META-INF/MANIFEST.MF
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/META-INF/MANIFEST.MF	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/META-INF/MANIFEST.MF	2007-03-01 15:26:26.000000000 -0500
@@ -0,0 +1,42 @@
+Manifest-Version: 1.0
+Bundle-ManifestVersion: 2
+Bundle-Name: Storyboard Plug-in
+Bundle-SymbolicName: org.tekkotsu.ui; singleton:=true
+Bundle-Version: 1.0.1
+Bundle-ClassPath: storyboard.jar,
+ lib/jdom.jar
+Bundle-Vendor: tekkotsu.org
+Bundle-Localization: plugin
+Export-Package: .,
+ org.jdom,
+ org.jdom.adapters,
+ org.jdom.filter,
+ org.jdom.input,
+ org.jdom.output,
+ org.jdom.transform,
+ org.jdom.xpath,
+ org.tekkotsu.ui.editor,
+ org.tekkotsu.ui.editor.editparts,
+ org.tekkotsu.ui.editor.editpolicies,
+ org.tekkotsu.ui.editor.icons,
+ org.tekkotsu.ui.editor.model,
+ org.tekkotsu.ui.editor.model.commands,
+ org.tekkotsu.ui.editor.resources,
+ org.tekkotsu.ui.rcp,
+ org.tekkotsu.ui.rcp.actions,
+ org.tekkotsu.ui.rcp.editors,
+ org.tekkotsu.ui.rcp.editors.xml,
+ org.tekkotsu.ui.storyboard,
+ org.tekkotsu.ui.storyboard.components,
+ org.tekkotsu.ui.storyboard.icons,
+ org.tekkotsu.ui.storyboard.model,
+ org.tekkotsu.ui.storyboard.views
+Require-Bundle: org.eclipse.ui,
+ org.eclipse.core.runtime,
+ org.eclipse.draw2d,
+ org.eclipse.ui.views,
+ org.eclipse.gef,
+ org.eclipse.jface.text,
+ org.eclipse.ui.workbench.texteditor,
+ org.eclipse.ui.console
+Eclipse-LazyStart: true
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/README ./tools/storyboard/org.tekkotsu.ui/README
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/README	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/README	2005-09-08 22:05:44.000000000 -0400
@@ -0,0 +1,4 @@
+Tekkotsu Storyboard Tool:
+- repackaged for eclipse 3.1 (included JDOM 1.0 library)
+- make sure you've downloaded and installed GEF 3.1
+- open plugin.xml -> overview -> Testing -> Launch an eclipse application.
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/build.properties ./tools/storyboard/org.tekkotsu.ui/build.properties
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/build.properties	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/build.properties	2006-02-14 00:22:32.000000000 -0500
@@ -0,0 +1,13 @@
+source.storyboard.jar = src/
+output.storyboard.jar = bin/
+bin.includes = storyboard.jar,\
+               META-INF/,\
+               plugin.xml,\
+               build.properties,\
+               lib/,\
+               icons/,\
+               samples/
+src.includes = src/,\
+               plugin.xml,\
+               lib/
+jars.extra.classpath = lib/jdom.jar
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard.icns and ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard.icns differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard.ico and ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard.ico differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.gif and ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.png and ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.xpm ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.xpm
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.xpm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard128.xpm	2005-10-18 14:06:37.000000000 -0400
@@ -0,0 +1,390 @@
+/* XPM */
+static char *Storyboard128[] = {
+/* width height ncolors chars_per_pixel */
+"128 128 256 2",
+/* colors */
+"AA s bg c None",
+"BA c #2A2A29292929",
+"CA c #CACA2B2B2B2B",
+"DA c #CECE3B3B3B3B",
+"EA c #AAAAFFFFCBCB",
+"FA c #444444444444",
+"GA c #C9C927272727",
+"HA c #CECE3D3D3D3D",
+"IA c #111158589999",
+"JA c #060650509595",
+"KA c #CCCC32323232",
+"LA c #A4A4FFFFC7C7",
+"MA c #C5C518181818",
+"NA c #D6D65D5D5D5D",
+"OA c #76769F9FC4C4",
+"PA c #9696FFFFC0C0",
+"AB c #31316E6EA7A7",
+"BB c #C8C823232323",
+"CB c #232323232323",
+"DB c #15155B5B9B9B",
+"EB c #CACA2D2D2D2D",
+"FB c #2C2C6B6BA5A5",
+"GB c #24246565A2A2",
+"HB c #CFCF40404040",
+"IB c #C7C721212121",
+"JB c #66663C3C3C3C",
+"KB c #B6B6FFFFD2D2",
+"LB c #CBCB30303030",
+"MB c #C9C929292929",
+"NB c #2D2D6C6CA5A5",
+"OB c #3C3C7676ACAC",
+"PB c #2D2D2D2D2D2D",
+"AC c #3A3A7575ABAB",
+"BC c #7878A1A1C6C6",
+"CC c #BFBF00000000",
+"DC c #5E5E8E8EBABA",
+"EC c #59598A8AB8B8",
+"FC c #22226464A1A1",
+"GC c #BEBEFFFFD7D7",
+"HC c #BABAFFFFD5D5",
+"IC c #1D1D1D1D1D1D",
+"JC c #48487F7FB1B1",
+"KC c #57578989B7B7",
+"LC c #262626262626",
+"MC c #090909090909",
+"NC c #62629191BCBC",
+"OC c #28286868A3A3",
+"PC c #DADA6B6B6B6B",
+"AD c #161616161616",
+"BD c #45457C7CAFAF",
+"CD c #0E0E56569898",
+"DD c #0D0D0D0D0D0D",
+"ED c #101010101010",
+"FD c #34347171A9A9",
+"GD c #050505050505",
+"HD c #29296868A4A4",
+"ID c #313131313131",
+"JD c #00004C4C9292",
+"KD c #020202020202",
+"LD c #8B8BFFFFB8B8",
+"MD c #8C8CFFFFB9B9",
+"ND c #BFBF01010101",
+"OD c #8D8DFFFFB9B9",
+"PD c #C0C002020202",
+"AE c #8E8EFFFFBABA",
+"BE c #9090FFFFBBBB",
+"CE c #C0C003030303",
+"DE c #01014D4D9292",
+"EE c #9191FFFFBCBC",
+"FE c #C0C005050505",
+"GE c #C0C004040404",
+"HE c #8F8FFFFFBABA",
+"IE c #9595FFFFBEBE",
+"JE c #8F8FFFFFBBBB",
+"KE c #02024D4D9393",
+"LE c #9A9AFFFFC1C1",
+"ME c #C1C106060606",
+"NE c #C1C108080808",
+"OE c #9393FFFFBDBD",
+"PE c #9D9DFFFFC3C3",
+"AF c #9898FFFFC0C0",
+"BF c #9494FFFFBEBE",
+"CF c #C2C20B0B0B0B",
+"DF c #C1C107070707",
+"EF c #9292FFFFBCBC",
+"FF c #C3C30F0F0F0F",
+"GF c #A0A0FFFFC5C5",
+"HF c #03034E4E9393",
+"IF c #C1C109090909",
+"JF c #C2C20A0A0A0A",
+"KF c #C3C310101010",
+"LF c #9B9BFFFFC2C2",
+"MF c #9696FFFFBFBF",
+"NF c #C2C20C0C0C0C",
+"OF c #9494FFFFBDBD",
+"PF c #C3C30E0E0E0E",
+"AG c #C8C825252525",
+"BG c #9F9FFFFFC4C4",
+"CG c #C4C415151515",
+"DG c #9797FFFFBFBF",
+"EG c #AFAFFFFFCECE",
+"FG c #0A0A53539696",
+"GG c #C2C20D0D0D0D",
+"HG c #C5C517171717",
+"IG c #C4C413131313",
+"JG c #D5D559595959",
+"KG c #A2A2FFFFC6C6",
+"LG c #D3D34F4F4F4F",
+"MG c #050550509494",
+"NG c #C6C61C1C1C1C",
+"OG c #C7C71F1F1F1F",
+"PG c #C6C61A1A1A1A",
+"AH c #9E9EFFFFC3C3",
+"BH c #A7A7FFFFC9C9",
+"CH c #C4C414141414",
+"DH c #C3C311111111",
+"EH c #04044F4F9494",
+"FH c #D3D351515151",
+"GH c #D6D65B5B5B5B",
+"HH c #D5D557575757",
+"IH c #CDCD36363636",
+"JH c #0D0D55559898",
+"KH c #C6C61D1D1D1D",
+"LH c #A5A5FFFFC8C8",
+"MH c #19195E5E9D9D",
+"NH c #D4D453535353",
+"OH c #A9A9FFFFCACA",
+"PH c #CBCB2F2F2F2F",
+"AI c #D1D149494949",
+"BI c #D1D146464646",
+"CI c #C7C71E1E1E1E",
+"DI c #9999FFFFC0C0",
+"EI c #C5C516161616",
+"FI c #080852529595",
+"GI c #B2B2FFFFD0D0",
+"HI c #CDCD39393939",
+"II c #D2D24A4A4A4A",
+"JI c #C4C412121212",
+"KI c #CCCC34343434",
+"LI c #1F1F62629F9F",
+"MI c #A3A3FFFFC7C7",
+"NI c #33337070A8A8",
+"OI c #D3D34E4E4E4E",
+"PI c #D2D24D4D4D4D",
+"AJ c #B1B1FFFFCFCF",
+"BJ c #9C9CFFFFC2C2",
+"CJ c #A9A9FFFFCBCB",
+"DJ c #A8A8FFFFCACA",
+"EJ c #9E9EFFFFC4C4",
+"FJ c #ACACFFFFCCCC",
+"GJ c #D5D558585858",
+"HJ c #B9B9FFFFD4D4",
+"IJ c #D4D455555555",
+"JJ c #D0D042424242",
+"KJ c #D0D043434343",
+"LJ c #CFCF3E3E3E3E",
+"MJ c #CFCF3F3F3F3F",
+"NJ c #CBCB2E2E2E2E",
+"OJ c #D0D044444444",
+"PJ c #C6C61B1B1B1B",
+"AK c #D0D045454545",
+"BK c #A1A1FFFFC6C6",
+"CK c #AEAEFFFFCDCD",
+"DK c #9999FFFFC1C1",
+"EK c #9C9CFFFFC3C3",
+"FK c #CCCC35353535",
+"GK c #B5B5FFFFD2D2",
+"HK c #2B2B6A6AA4A4",
+"IK c #D4D454545454",
+"JK c #D2D24C4C4C4C",
+"KK c #CDCD38383838",
+"LK c #4D4D8282B3B3",
+"MK c #A3A3FFFFC6C6",
+"NK c #1E1E61619F9F",
+"OK c #D6D65A5A5A5A",
+"PK c #CDCD37373737",
+"AL c #D2D24B4B4B4B",
+"BL c #9F9FFFFFC5C5",
+"CL c #C8C824242424",
+"DL c #D8D862626262",
+"EL c #090952529696",
+"FL c #B8B8FFFFD3D3",
+"GL c #A4A4FFFFC8C8",
+"HL c #B8B8FFFFD4D4",
+"IL c #D5D556565656",
+"JL c #D4D452525252",
+"KL c #D1D148484848",
+"LL c #D1D147474747",
+"ML c #A1A1FFFFC5C5",
+"NL c #37377373AAAA",
+"OL c #60608F8FBBBB",
+"PL c #0B0B54549797",
+"AM c #27276868A3A3",
+"BM c #B4B4FFFFD1D1",
+"CM c #17175C5C9C9C",
+"DM c #6B6B9797C0C0",
+"EM c #6C6C9898C0C0",
+"FM c #ADADFFFFCDCD",
+"GM c #43437B7BAFAF",
+"HM c #2A2A6969A4A4",
+"IM c #BFBFFFFFD8D8",
+"JM c #B0B0FFFFCFCF",
+"KM c #69699696BFBF",
+"LM c #D3D350505050",
+"MM c #4C4C8181B2B2",
+"NM c #6F6F9A9AC1C1",
+"OM c #D7D760606060",
+"PM c #9595FFFFBFBF",
+"AN c #525252525252",
+"BN c #7D7D30303030",
+"CN c #A4A412121212",
+"DN c #32327070A7A7",
+"EN c #8D8DFFFFBABA",
+"FN c #8A8A28282828",
+"GN c #DBDB70707070",
+"HN c #64649292BDBD",
+"IN c #96961E1E1E1E",
+"JN c #54548787B6B6",
+"KN c #B5B505050505",
+"LN c #6A6A9696BFBF",
+"MN c #B3B3FFFFD1D1",
+"NN c #9393FFFFBCBC",
+"ON c #A2A2FFFFC7C7",
+"PN c #36367272A9A9",
+"AO c #3D3D37373737",
+"BO c #ABABFFFFCCCC",
+"CO c #38387373A9A9",
+"DO c #20206262A0A0",
+"EO c #4B4B8181B2B2",
+"FO c #50508484B4B4",
+"GO c #ADADFFFFCCCC",
+"HO c #84842B2B2B2B",
+"IO c #8E8E24242424",
+"JO c #45453B3B3B3B",
+"KO c #B1B1FFFFD0D0",
+"LO c #A3A3FFFFC8C8",
+"MO c #6F6F9999C1C1",
+"NO c #73739D9DC3C3",
+"OO c #74749D9DC4C4",
+"PO c #737337373737",
+"AP c #58583F3F3F3F",
+"BP c #61619090BBBB",
+"CP c #D9D967676767",
+"DP c #3A3A3A3A3A3A",
+"EP c #343431313131",
+"FP c #363636363636",
+"GP c #1D1D60609E9E",
+"HP c #40407979ADAD",
+"IP c #41417A7AAEAE",
+"JP c #18185D5D9C9C",
+"KP c #0F0F57579898",
+"LP c #1A1A5E5E9D9D",
+"MP c #1B1B5F5F9E9E",
+"NP c #9A9AFFFFC2C2",
+"OP c #68689494BEBE",
+"PP c #000000000000",
+/* pixels */
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAJDJDJDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAJDJDJDJDJDJDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAACDJDJDJDJDJDJDJDJDJDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAJDJDJDJDJDJDLDLDLDLDLDLDLDLDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAJDJDJDJDJDLDLDLDLDLDLDLDLDLDLDLDLDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAJDJDJDJDLDLDLDLDLDLDLDLDLDLDLDLDLDLDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAJDJDJDJDLDLDLDLDLDLDMDMDMDMDMDMDMDMDMDLDDEDEJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAJDJDJDLDLDLDLDLDMDMDMDODODODODODODODMDMDMDKEDEDEJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAJDJDJDJDLDLDLDLDMDMDODODAEAEHEHEHEHEAEAEODODHFKEKEDEAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAJDJDJDLDLDLDLDMDMDODAEHEBEBEEEEEEEEEBEBEJEHEAEMGHFKEAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAJDJDJDLDLDLDMDMDODAEJEBEEFOEOFBFBFBFOFOEEFBEBEFIJAMGAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAADEDEDELDLDLDMDODAEJEEEOEIEMFDGAFDIAFAFDGIEBFEFJHFGFIJAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAACCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAADEKEKEMDMDMDENODHEBEOEIEDGLELFPEAHAHPEBJLEAFMFDBIAJHFGAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAHFHFEHODODAEAEJEEEOEIEDGLEAHGFKGLALALAKGGFEJLFLIMHDBIAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDAAAAAAAAMGJAJAAEAEJEBEBEEFBFDGLEEJPPPPPPEABOEACJBHLHKGHKGBLIMHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDPDAAAAAAAAELFGPLBEBEEEEENNBFMFLEPEMLPPPPPPPPGIGIAJEGFMCJACNIFBAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEAAAAAAAACDKPIAIAOEOEOFBFPMAFLFGFLHCJPPPPPPPPPPHCHLGKGILKBDACAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEFEAAAAAAAADBCMMHMHMFMFMFPAAFLEPEBKBHGOPPPPPPPPPPPPPPGCLNBPKCLKAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEFENEAAAAAAAAAALIFCFCGBNPLEDKLELFAHMIDJEGPPPPPPPPPPPPPPPPPPOADMAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDCEFEDFCFAAAAAAAAAAHMFBFBFBEJPEBJBJBJBGMIEAJMFLPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDPDGEDFCFFFAAAAAAAAAAAANLPPPPDNGFAHPEAHGFLAEAKOHJPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDGEMEJFFFCGNGAAAAAAAAAAPPPPPPPPFDNBBGBGBLLOOHJMHJPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEMEIFPFCHPJCLAAAAAAAAAAPPPPPPPPPPABFBAHBGONBHEGFLPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEFENEGGJIPGBBCAIHAAAAAAPPPPPPPPPPOBDNFBHMHMABOBMMDCOOPPPPPPPPPPPPPPPPPPPPPPPPPPPPBAINCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDCEFENENFDHMAIBCAFKHBIIAAPPPPPPPPPPPPOBNIHKAMAMNBCOJCECMOPPPPPPPPPPPPPPPPDDAOJBCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDPDGEDFCFKFHGOGMBKIMJIINHPPPPPPPPPPPPAAAAAAOCGBGBHDNIIPJNOPPPPPPPPPPPMCEPHOCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDGEMEJFFFCGKHGAKAHAKLNHPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAPPCBJOIOCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEMEIFPFCHNGAGPHDABIFHOKPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEFENEGGIGPGBBEBKKOJLGJGPPPPPPPPPPGJOIKJPKCAIBHGKFCFMEGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDCEFENENFDHMAIBCAIHJJPIHHPPPPPPPPPPPPJLLLDAPHAGPJIGGGNEFECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCNDNDPDGEDFCFKFHGOGMBKIMJALIJPPPPPPPPPPPPIJIIMJKAGACIEIFFJFMEGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCCCNDPDGEMEJFFFCGKHGAKAHAAINHPPPPPPPPPPPPHHPIHBIHCAIBMADHCFDFGECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCCCNDPDCEMEIFPFCHNGAGPHDABIFHGHPPPPPPPPPPJGLGOJKKEBBBPGJIGGNEFECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCCCNDPDCEFENEGGIGPGBBEBHIOJLGJGPPPPPPPPPPGHFHBIDAPHAGNGCHPFIFMECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCCCNDNDCEFENENFDHMAIBCAIHJJPIGJPPPPPPPPPPPPNHAIHAKAGAKHCGFFJFMEGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCNDNDPDGEDFCFKFHGOGMBKIHBALILPPPPPPPPPPPPIJALMJKIMBOGHGKFCFDFGEPDNDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCCCNDPDGEMEJFFFEICIGAKALJAIIKPPPPPPPPPPPPHHPIJJIHCAIBMADHNFNEFECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCCCNDPDCEMEIFPFCHNGAGLBDALLJLNAPPPPPPPPPPJGLGOJHIEBBBPGIGGGNEFECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCCCCCNDPDCEFENEGGIGPGBBNJHIAKLMOKPPPPPPPPPPGHJLLLDALBAGNGCHPFIFMECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCJBAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCCCCCCCNDPDCEFENENFJIMAIBCAPKKJOIJGPPPPPPPPPPPPIKAILJKAGAKHCGFFJFMEGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCPOPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACCCCCCNDNDNDPDCEFEDFCFKFHGIBCAFKHBJKHHPPPPPPPPPPPPHHJKHBKIMBOGHGKFCFDFGEPDNDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCBNPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAANDNDNDNDPDPDCEFEDFCFKFEICIGAKALJIIIJPPPPPPPPPPPPJGLGKJPKCABBMADHNFNEFECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCFNPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPDPDCEGEGEMENECFFFCGKHGALBDAKLNHNAPPPPPPPPPPNAFHBIDANJCLPJIGGGNEFECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCNPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAGEFEMENEIFNFKFCGNGAGPHDABIFHGHPPPPPPPPPPPPIKAIHALBGAKHCGPFIFMECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCKNPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADFIFJFNFFFJIHGKHAGNJHIOJLGOKPPPPPPPPPPPPHHJKHBKIMBOGEIFFJFDFGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCMCPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAANFPFKFIGEIPGOGGANJKKKJOIGJPPPPPPPPPPPPJGOIJJIHCAIBMADHCFDFGECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCADPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAACHMAPJOGCLCALBDAKJOIHHPPPPPPPPPPPPGHFHAKHINJBBPGJINFNEFECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAIBGACALBIHLJBILGGJOMPPPPPPPPPPNANHKLDALBAGNGCHPFIFFECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAKDKDKDPPPPPPAAAAAAJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAKAHIMJAKJKIKGHDLPPPPPPPPPPPPILIILJKAGACICGFFJFMEGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAGDKDKDKDKDDEDEDEJDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPAAAALGIJGHDLCPPPPPPPPPPPPPGJPIHBFKCAIBHGKFCFDFGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAMCGDMGEHHFKEKEDEDEDEJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPAAAAAAPCGNPPPPPPPPPPPPNAFHAKKKCABBMAJINFNEFECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAADDFGELJAJAMGEHHFMDMDLDLDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPAAAAAAAAPPPPPPPPPPPPDLILAIDALBAGPJIGGGIFFECEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAADBIAKPPLFGHEAEODODMDMDLDLDLDLDJDJDJDJDJDAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPAAAAAAPPPPPPPPPPPCNALMJJFKMBCIEIFFJFMEGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAFCNKMPCMDBOEEEBEJEAEODODMDMDLDLDLDJDJDJDJDJDAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPAAAAPPPPPPPPPPPPAAJGIIDAPHBBMADHCFDFGEPDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPNABFBOCGBDIDGIEOEEEBEJEAEODMDMDLDLDLDJDJDJDJDJDAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAACICGPFIFFECENDNDCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPAAAAAAAAAAAAAAJCGMOBNLBKBGBJLEDGIEOEEEJEAEODMDMDLDLDLDJDJDJDJDAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAANDCCCCCCCCCCCCCCCCCCCCCCCCAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPAAAAAANCDCKCFOFJOHLHKGBGLFAFIEOEEEJEAEODMDLDLDLDLDJDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPBCNOEMHNGKAJFMOHGLGFEKDIIEOEBEHEODMDMDLDLDLDJDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJAPLIAGPHMACLKNCOAPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPGCHJBMEGEALHGFEKAFIEEFBEAEODMDLDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAKEEHJAJHDBDOABHPJNKMPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPPPPPGKEGCJLABGLEMFOEBEHEODMDLDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAADEKEMGELKPJPGBNIBDECNMPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPBHBKEKAFBFEEJEODMDLDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDDEHFMGFGIADGPELAFJKBIMPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPEDIIEEEJEAEMDMDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDDEHFJABEOEAFEJLHCKFLPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPEDIIEEEJEAEMDMDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDDEKEODAEBEBFDKBGBHEGHLPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPDJKGPEAFBFEEJEODMDLDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDDEMDODHEEEIELEGFBHEGHLPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPGIFJLHGFLFDGOEBEHEODMDLDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDDEMDODHEEEIELEGFBHEGFLPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAADEDMCGDGDKDPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAPPPPPPPPPPPPPPPPPPPPPPPPHCBMCKDJKGPEDKIEEFBEAEODMDLDLDLDLDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDLDMDODHEEEIELEBLBHCKPPPPPPPPPPPPPPPPPPOOKMDCANFADPIDLCICADEDMCMCGDKDKDPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPPPPPIMHJMNCKDJMIBGLEMFOFEEJEAEMDMDLDLDLDJDJDJDJDAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDMDODHEEEIELEBGLHBOPPPPPPPPPPPPPPGCHCOLKCEOFAFPPBCBICADEDDDMCGDKDKDPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPPPOADMOLAJFJBHMKEJLEDGBFEEBEAEODMDLDLDLDJDJDJDJDAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDMDODHEEEBFAFPEMKDJPPPPPPPPPPHJFLGKGIMMGMACIDBACBICADEDMCMCGDGDKDPPPPPPPPPPPPPPPPAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPPPPPAAEMNCECLKCJLHMLPELEMFBFEFBEAEODMDMDLDLDLDJDJDJDJDAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDMDODAEBEOFDGLFGFGLPPPPPPAJGIAJEGFJOHACNIHKCBICADEDDDMCMCGDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPPPAAAAAAAAFOBDOBNIHKLFAFIEOEEEBEAEODMDMDLDLDLDJDJDJDJDAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDMDODAEBEEFIEDKPEPPPPPPOHEAEAOHBHGLKGHKGBNKAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPPPPPAAAAAAAAAAAAFDFBGBLIMHBFEFBEJEAEODMDMDLDLDJDJDJDJDJDAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDMDMDAEJEEEOFDGLEPEBLBKMKMIMIKGGFAHLFNKMHDBAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAPPPPAAAAAAAAAAAAAAAAAALILPDBIAJHFGHEAEODMDMDLDDEJDJDJDJDJDAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDLDMDODHEBEEFBFDGDILFEKPEPEPELFLEAFMFDBIAJHAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAIAJHFGFIJAEHHFKEDEDEJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDLDMDODAEJEBEEFOFIEDGAFAFAFDGMFIEOFEFJHFGFIAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAFIJAEHHFKEKEDEDEJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDLDLDMDODAEJEBEEEEFOEOFBFOFOEOEEFBEBEFIJAMGAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAKEDEDEJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDLDLDLDMDMDODAEHEJEBEBEEEEEBEBEBEJEAEJAEHHFKEAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDLDLDLDLDMDMDODODAEAEAEHEHEAEAEAEODODHFKEKEAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDLDLDLDLDMDMDMDMDODODODODODODMDMDKEKEDEDEAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDLDLDLDLDLDLDMDMDMDMDMDMDMDLDDEDEDEJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDJDLDLDLDLDLDLDLDLDLDLDLDLDDEJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDJDJDLDLDLDLDLDLDLDLDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDJDJDJDJDLDLDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDJDJDJDJDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDJDJDJDJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAJDJDJDJDJDAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA",
+"AAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAAA"};
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/Storyboard32.gif and ./tools/storyboard/org.tekkotsu.ui/icons/Storyboard32.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/eclipse_lg.gif and ./tools/storyboard/org.tekkotsu.ui/icons/eclipse_lg.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/inbox.gif and ./tools/storyboard/org.tekkotsu.ui/icons/inbox.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/inbox.png and ./tools/storyboard/org.tekkotsu.ui/icons/inbox.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/open.gif and ./tools/storyboard/org.tekkotsu.ui/icons/open.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/perspective.gif and ./tools/storyboard/org.tekkotsu.ui/icons/perspective.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/tekkotsu16.gif and ./tools/storyboard/org.tekkotsu.ui/icons/tekkotsu16.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/tekkotsu32.gif and ./tools/storyboard/org.tekkotsu.ui/icons/tekkotsu32.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/icons/text.gif and ./tools/storyboard/org.tekkotsu.ui/icons/text.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/lib/jdom.jar and ./tools/storyboard/org.tekkotsu.ui/lib/jdom.jar differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/plugin.xml ./tools/storyboard/org.tekkotsu.ui/plugin.xml
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/plugin.xml	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/plugin.xml	2007-03-01 15:27:11.000000000 -0500
@@ -0,0 +1,187 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<?eclipse version="3.0"?>
+<plugin>
+
+     <extension
+         point="org.eclipse.ui.views">
+      <category
+            name="Tekkotsu Category"
+            id="org.tekkotsu.ui.storyboard">
+      </category>
+      <view
+            name="Storyboard"
+            category="org.tekkotsu.ui.storyboard"
+            class="org.tekkotsu.ui.storyboard.views.StoryboardView"
+            id="org.tekkotsu.ui.storyboard.views.StoryboardView">
+      </view>
+      <view
+            class="org.tekkotsu.ui.storyboard.views.RuntimeView"
+            category="org.tekkotsu.ui.storyboard"
+            name="Runtime View"
+            id="org.tekkotsu.ui.storyboard.views.RuntimeView"/>
+   </extension>
+   <extension
+         point="org.eclipse.ui.perspectiveExtensions">
+      <perspectiveExtension
+            targetID="org.eclipse.ui.resourcePerspective">
+         <view
+               ratio="0.5"
+               relative="org.eclipse.ui.views.TaskList"
+               relationship="right"
+               id="org.tekkotsu.ui.storyboard.views.StoryboardView">
+         </view>
+         <view
+               ratio="0.5"
+               relationship="right"
+               relative="org.eclipse.ui.views.TaskList"
+               id="org.tekkotsu.ui.storyboard.views.RuntimeView"/>
+      </perspectiveExtension>
+   </extension>
+   <extension
+         id="perspective"
+         name="RCP Storyboard Perspective"
+         point="org.eclipse.ui.perspectives">
+      <perspective
+            icon="icons/perspective.gif"
+            class="org.tekkotsu.ui.rcp.StoryboardPerspective"
+            fixed="false"
+            name="Tekkotsu Storyboard"
+            id="org.tekkotsu.ui.rcp.StoryboardPerspective"/>
+   </extension>
+   <extension
+         point="org.eclipse.ui.editors">
+      <editor
+            icon="icons/text.gif"
+            class="org.tekkotsu.ui.rcp.editors.xml.XMLEditor"
+            name="Sample XML Editor"
+            contributorClass="org.eclipse.ui.texteditor.BasicTextEditorActionContributor"
+            id="org.tekkotsu.ui.rcp.editors.xml.XMLEditor"
+            extensions="xml,html"/>
+      <editor
+            icon="icons/perspective.gif"
+            class="org.tekkotsu.ui.rcp.editors.SimpleEditor"
+            default="true"
+            name="Sample Editor"
+            contributorClass="org.eclipse.ui.texteditor.BasicTextEditorActionContributor"
+            id="org.tekkotsu.ui.rcp.editors.SimpleEditor"/>
+   </extension>
+   <extension
+         point="org.eclipse.ui.actionSets">
+      <actionSet
+            label="File Action Set"
+            visible="true"
+            id="org.tekkotsu.ui.rcp.fileActionSet">
+         <action
+               toolbarPath="group.file"
+               label="&amp;Pick Model"
+               icon="icons/inbox.gif"
+               tooltip="Choose model for current layout"
+               class="org.tekkotsu.ui.editor.resources.OpenModelAction"
+               style="push"
+               menubarPath="file/new.ext"
+               state="false"
+               id="org.tekkotsu.ui.editor.resources.OpenModelAction"/>               
+         <action
+               toolbarPath="group.file"
+               label="&amp;Open Layout"
+               icon="icons/open.gif"
+               tooltip="Open a layout"
+               class="org.tekkotsu.ui.rcp.actions.OpenFileAction"
+               definitionId="org.tekkotsu.ui.rcp.commands.OpenFile"
+               style="push"
+               menubarPath="file/new.ext"
+               state="false"
+               id="org.tekkotsu.ui.rcp.actions.OpenFile"/>
+         <action
+               toolbarPath="group.file"
+               label="&amp;New Layout"
+               icon="icons/tekkotsu16.gif"
+               tooltip="Create a new layout"
+               class="org.tekkotsu.ui.rcp.actions.NewFileAction"
+               definitionId="org.tekkotsu.ui.rcp.commands.NewFile"
+               style="push"
+               menubarPath="file/new.ext"
+               state="false"
+               id="org.tekkotsu.ui.rcp.actions.NewFile"/>
+      </actionSet>
+   </extension>
+   <extension
+         point="org.eclipse.ui.commands">
+      <command
+            description="Open a file"
+            name="Open"
+            id="org.tekkotsu.ui.rcp.commands.OpenFile"/>
+<!--      <keyBinding
+            command="org.tekkotsu.ui.rcp.commands.openFile"
+            keySequence="M1+O"/> -->
+      <command
+            description="Create a new file"
+            name="Create"
+            id="org.tekkotsu.ui.rcp.commands.NewFile"/>
+<!--      <keyBinding
+            command="org.tekkotsu.ui.rcp.commands.NewFile"
+            keySequence="M1+N"/> -->
+   </extension>
+
+   <extension
+         id="StoryboardApplication"
+         name="RCP Storyboard Application"
+         point="org.eclipse.core.runtime.applications">
+      <application>
+         <run class="org.tekkotsu.ui.rcp.StoryboardApplication"/>
+      </application>
+   </extension>
+
+   <extension
+         id="product"
+         point="org.eclipse.core.runtime.products">
+      <product
+            application="org.tekkotsu.ui.StoryboardApplication"
+            description="Tekkotsu Storyboard Viewer"
+            name="Tekkotsu Storyboard Viewer">
+         <property
+               name="appName"
+               value="Storyboard"/>
+         <property
+               name="aboutText"
+               value="Tekkotsu Storyboard Viewer"/>
+         <property
+               name="windowImages"
+               value="icons/tekkotsu16.gif,icons/Storyboard32.gif"/>
+      </product>
+   </extension>
+   
+   <extension
+         point="org.eclipse.ui.views">
+      <view
+            name="Storyboard View"
+            category="org.tekkotsu.ui.storyboard"
+            class="org.tekkotsu.ui.storyboard.views.StoryboardView"
+            id="org.tekkotsu.ui.storyboard.views.StoryboardView">
+      </view>
+      <view
+            name="Runtime View"
+            category="org.tekkotsu.ui.storyboard"
+            class="org.tekkotsu.ui.storyboard.views.RuntimeView"
+            id="org.tekkotsu.ui.storyboard.views.RuntimeView">
+      </view>
+      <view
+      		name="Image Preview"
+      		category="org.tekkotsu.ui.storyboard"
+      		class="org.tekkotsu.ui.storyboard.views.ImageView"
+      		id="org.tekkotsu.ui.storyboard.views.ImageView">
+      </view>
+   </extension>
+
+   <extension
+         point="org.eclipse.ui.editors">
+      <editor
+            class="org.tekkotsu.ui.editor.StateMachineEditor"
+            icon="icons/tekkotsu16.gif"
+            default="true"
+            name="State Machine Editor"
+            id="org.tekkotsu.ui.editor.StateMachineEditor"
+            extensions="tsl"/>
+   </extension>
+
+</plugin>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/ex1.txt ./tools/storyboard/org.tekkotsu.ui/samples/ex1.txt
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/ex1.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/ex1.txt	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,72 @@
+java.lang.NullPointerException
+	at org.tekkotsu.ui.editor.model.MultiTransitionModel.isSingleTransition(MultiTransitionModel.java:255)
+	at org.tekkotsu.ui.editor.editparts.MultiTransitionEditPart.createFigure(MultiTransitionEditPart.java:105)
+	at org.eclipse.gef.editparts.AbstractGraphicalEditPart.getFigure(AbstractGraphicalEditPart.java:435)
+	at org.eclipse.gef.editparts.AbstractGraphicalEditPart.addChildVisual(AbstractGraphicalEditPart.java:197)
+	at org.eclipse.gef.editparts.AbstractEditPart.addChild(AbstractEditPart.java:194)
+	at org.eclipse.gef.editparts.AbstractEditPart.refreshChildren(AbstractEditPart.java:734)
+	at org.eclipse.gef.editparts.AbstractEditPart.refresh(AbstractEditPart.java:684)
+	at org.eclipse.gef.editparts.AbstractGraphicalEditPart.refresh(AbstractGraphicalEditPart.java:554)
+	at org.eclipse.gef.editparts.AbstractEditPart.addNotify(AbstractEditPart.java:232)
+	at org.eclipse.gef.editparts.AbstractGraphicalEditPart.addNotify(AbstractGraphicalEditPart.java:212)
+	at org.eclipse.gef.editparts.AbstractEditPart.addChild(AbstractEditPart.java:195)
+	at org.eclipse.gef.editparts.ScalableRootEditPart.setContents(ScalableRootEditPart.java:404)
+	at org.eclipse.gef.ui.parts.AbstractEditPartViewer.setContents(AbstractEditPartViewer.java:583)
+	at org.eclipse.gef.ui.parts.AbstractEditPartViewer.setContents(AbstractEditPartViewer.java:592)
+	at org.tekkotsu.ui.editor.StateMachineEditor.initializeGraphicalViewer(StateMachineEditor.java:822)
+	at org.tekkotsu.ui.editor.MultiPageGraphicalEditorWithPalette.createGraphicalViewer(MultiPageGraphicalEditorWithPalette.java:126)
+	at org.tekkotsu.ui.editor.StateMachineEditor.createLayoutEditorPage(StateMachineEditor.java:396)
+	at org.tekkotsu.ui.editor.StateMachineEditor.createPages(StateMachineEditor.java:408)
+	at org.eclipse.ui.part.MultiPageEditorPart.createPartControl(MultiPageEditorPart.java:241)
+	at org.eclipse.ui.internal.EditorReference.createPartHelper(EditorReference.java:585)
+	at org.eclipse.ui.internal.EditorReference.createPart(EditorReference.java:365)
+	at org.eclipse.ui.internal.WorkbenchPartReference.getPart(WorkbenchPartReference.java:552)
+	at org.eclipse.ui.internal.PartPane.setVisible(PartPane.java:283)
+	at org.eclipse.ui.internal.presentations.PresentablePart.setVisible(PresentablePart.java:126)
+	at org.eclipse.ui.internal.presentations.util.PresentablePartFolder.select(PresentablePartFolder.java:268)
+	at org.eclipse.ui.internal.presentations.util.LeftToRightTabOrder.select(LeftToRightTabOrder.java:65)
+	at org.eclipse.ui.internal.presentations.util.TabbedStackPresentation.selectPart(TabbedStackPresentation.java:391)
+	at org.eclipse.ui.internal.PartStack.refreshPresentationSelection(PartStack.java:1102)
+	at org.eclipse.ui.internal.PartStack.setSelection(PartStack.java:1051)
+	at org.eclipse.ui.internal.PartStack.showPart(PartStack.java:1256)
+	at org.eclipse.ui.internal.PartStack.add(PartStack.java:442)
+	at org.eclipse.ui.internal.EditorStack.add(EditorStack.java:109)
+	at org.eclipse.ui.internal.EditorSashContainer.addEditor(EditorSashContainer.java:60)
+	at org.eclipse.ui.internal.EditorAreaHelper.addToLayout(EditorAreaHelper.java:212)
+	at org.eclipse.ui.internal.EditorAreaHelper.addEditor(EditorAreaHelper.java:202)
+	at org.eclipse.ui.internal.EditorManager.createEditorTab(EditorManager.java:753)
+	at org.eclipse.ui.internal.EditorManager.openEditorFromDescriptor(EditorManager.java:665)
+	at org.eclipse.ui.internal.EditorManager.openEditor(EditorManager.java:628)
+	at org.eclipse.ui.internal.WorkbenchPage.busyOpenEditorBatched(WorkbenchPage.java:2323)
+	at org.eclipse.ui.internal.WorkbenchPage.busyOpenEditor(WorkbenchPage.java:2258)
+	at org.eclipse.ui.internal.WorkbenchPage.access$9(WorkbenchPage.java:2250)
+	at org.eclipse.ui.internal.WorkbenchPage$9.run(WorkbenchPage.java:2236)
+	at org.eclipse.swt.custom.BusyIndicator.showWhile(BusyIndicator.java:69)
+	at org.eclipse.ui.internal.WorkbenchPage.openEditor(WorkbenchPage.java:2231)
+	at org.eclipse.ui.internal.WorkbenchPage.openEditor(WorkbenchPage.java:2204)
+	at org.tekkotsu.ui.editor.StateMachineEditor.doSaveAs(StateMachineEditor.java:734)
+	at org.eclipse.ui.internal.SaveAsAction.run(SaveAsAction.java:64)
+	at org.eclipse.jface.action.Action.runWithEvent(Action.java:996)
+	at org.eclipse.jface.action.ActionContributionItem.handleWidgetSelection(ActionContributionItem.java:538)
+	at org.eclipse.jface.action.ActionContributionItem.access$2(ActionContributionItem.java:488)
+	at org.eclipse.jface.action.ActionContributionItem$5.handleEvent(ActionContributionItem.java:400)
+	at org.eclipse.swt.widgets.EventTable.sendEvent(EventTable.java:66)
+	at org.eclipse.swt.widgets.Widget.sendEvent(Widget.java:1021)
+	at org.eclipse.swt.widgets.Display.runDeferredEvents(Display.java:2867)
+	at org.eclipse.swt.widgets.Display.readAndDispatch(Display.java:2572)
+	at org.eclipse.ui.internal.Workbench.runEventLoop(Workbench.java:1699)
+	at org.eclipse.ui.internal.Workbench.runUI(Workbench.java:1663)
+	at org.eclipse.ui.internal.Workbench.createAndRunWorkbench(Workbench.java:367)
+	at org.eclipse.ui.PlatformUI.createAndRunWorkbench(PlatformUI.java:143)
+	at org.tekkotsu.ui.rcp.StoryboardApplication.run(StoryboardApplication.java:23)
+	at org.eclipse.core.internal.runtime.PlatformActivator$1.run(PlatformActivator.java:226)
+	at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:376)
+	at org.eclipse.core.runtime.adaptor.EclipseStarter.run(EclipseStarter.java:163)
+	at sun.reflect.NativeMethodAccessorImpl.invoke0(Native Method)
+	at sun.reflect.NativeMethodAccessorImpl.invoke(NativeMethodAccessorImpl.java:39)
+	at sun.reflect.DelegatingMethodAccessorImpl.invoke(DelegatingMethodAccessorImpl.java:25)
+	at java.lang.reflect.Method.invoke(Method.java:585)
+	at org.eclipse.core.launcher.Main.invokeFramework(Main.java:334)
+	at org.eclipse.core.launcher.Main.basicRun(Main.java:278)
+	at org.eclipse.core.launcher.Main.run(Main.java:973)
+	at org.eclipse.core.launcher.Main.main(Main.java:948)
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/figure1.png and ./tools/storyboard/org.tekkotsu.ui/samples/figure1.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/figure2.png and ./tools/storyboard/org.tekkotsu.ui/samples/figure2.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/figure3.png and ./tools/storyboard/org.tekkotsu.ui/samples/figure3.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/figure4.png and ./tools/storyboard/org.tekkotsu.ui/samples/figure4.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/foo.tsl ./tools/storyboard/org.tekkotsu.ui/samples/foo.tsl
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/foo.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/foo.tsl	2005-09-25 19:44:44.000000000 -0400
@@ -0,0 +1,15 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="foo.tsm">
+  <state id="Logging Test" label="Logging Test" color="#ffc400" top="32" left="67" width="168" height="20" shape="Rectangle" />
+  <state id="Waiting" label="Waiting" color="#00ff00" top="186" left="165" width="50" height="20" shape="Rectangle" />
+  <state id="Image" label="Image" color="#00ffff" top="150" left="79" width="50" height="20" shape="Rectangle" />
+  <state id="Message" label="Message" color="#60ff60" top="108" left="116" width="50" height="20" shape="Rectangle" />
+  <state id="Webcam" label="Webcam" color="#ff0000" top="76" left="173" width="50" height="20" shape="Rectangle" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans" label="transition9" color="#000000" top="110" left="180" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans" label="transition13" color="#000000" top="110" left="220" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans" label="transition17" color="#000000" top="110" left="260" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition21" color="#000000" top="110" left="300" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition25" color="#000000" top="110" left="340" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition29" color="#000000" top="110" left="380" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/foo.tsm ./tools/storyboard/org.tekkotsu.ui/samples/foo.tsm
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/foo.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/foo.tsm	2005-09-25 19:44:44.000000000 -0400
@@ -0,0 +1,33 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Logging Test" class="LogTestMachine" />
+  <state id="Waiting" class="StateNode" />
+  <state id="Image" class="ImageLogTestNode" />
+  <state id="Message" class="MessageLogTestNode" />
+  <state id="Webcam" class="WebcamLogTestNode" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Image</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Message</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Webcam</destination>
+  </transition>
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Image</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Message</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Webcam</source>
+    <destination>Waiting</destination>
+  </transition>
+</model>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/foo2.tse ./tools/storyboard/org.tekkotsu.ui/samples/foo2.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/foo2.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/foo2.tse	2005-09-25 19:44:44.000000000 -0400
@@ -0,0 +1,93 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="458806" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="458808" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="467332" />
+    <statestop id="Waiting" time="467334" />
+    <statestart id="Webcam" time="467337" />
+  </event>
+  <event type="webcam" sid="Webcam" time="467338" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="467339" />
+    <statestop id="Webcam" time="467339" />
+    <statestart id="Waiting" time="467340" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="476586" />
+    <statestop id="Waiting" time="476588" />
+    <statestart id="Message" time="476589" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="476589">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="476601" />
+    <statestop id="Message" time="476603" />
+    <statestart id="Waiting" time="476603" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="483868" />
+    <statestop id="Waiting" time="483870" />
+    <statestart id="Message" time="483874" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="483874">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="483875" />
+    <statestop id="Message" time="483875" />
+    <statestart id="Waiting" time="483876" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="491562" />
+    <statestop id="Waiting" time="491564" />
+    <statestart id="Image" time="491565" />
+  </event>
+  <event type="image" sid="Image" time="491592"><image>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</image></event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="491626" />
+    <statestop id="Image" time="491628" />
+    <statestart id="Waiting" time="491628" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="503628" />
+    <statestop id="Waiting" time="503630" />
+    <statestart id="Message" time="503634" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="503634">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="503641" />
+    <statestop id="Message" time="503643" />
+    <statestart id="Waiting" time="503644" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="512259" />
+    <statestop id="Waiting" time="512261" />
+    <statestart id="Image" time="512262" />
+  </event>
+  <event type="image" sid="Image" time="512290"><image>/9j/4AAQSkZJRgABAQAAAQABAAD/2wBDAAUDBAQEAwUEBAQFBQUGBwwIBwcHBw8LCwkMEQ8SEhEPERETFhwXExQaFRERGCEYGh0dHx8fExciJCIeJBweHx7/2wBDAQUFBQcGBw4ICA4eFBEUHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh4eHh7/wAARCACgANADASIAAhEBAxEB/8QAHwAAAQUBAQEBAQEAAAAAAAAAAAECAwQFBgcICQoL/8QAtRAAAgEDAwIEAwUFBAQAAAF9AQIDAAQRBRIhMUEGE1FhByJxFDKBkaEII0KxwRVS0fAkM2JyggkKFhcYGRolJicoKSo0NTY3ODk6Q0RFRkdISUpTVFVWV1hZWmNkZWZnaGlqc3R1dnd4eXqDhIWGh4iJipKTlJWWl5iZmqKjpKWmp6ipqrKztLW2t7i5usLDxMXGx8jJytLT1NXW19jZ2uHi4+Tl5ufo6erx8vP09fb3+Pn6/8QAHwEAAwEBAQEBAQEBAQAAAAAAAAECAwQFBgcICQoL/8QAtREAAgECBAQDBAcFBAQAAQJ3AAECAxEEBSExBhJBUQdhcRMiMoEIFEKRobHBCSMzUvAVYnLRChYkNOEl8RcYGRomJygpKjU2Nzg5OkNERUZHSElKU1RVVldYWVpjZGVmZ2hpanN0dXZ3eHl6goOEhYaHiImKkpOUlZaXmJmaoqOkpaanqKmqsrO0tba3uLm6wsPExcbHyMnK0tPU1dbX2Nna4uPk5ebn6Onq8vP09fb3+Pn6/9oADAMBAAIRAxEAPwDwWzOeoBz2rZ09FLfLuX1OOKwLdnW6aJlIUHGc1vWDDcoJrpqS96zLitDbgWUfxBvqKuxFgCXjI45I5qraHgcmr8eNjfSuRzNIx6Hpn7L8QbxTr82P9XBEmfrzXv8AXh/7K8PzeJrnsZ4owfole4VbdzSK0CiiikUFFFFAHGfGbxafCHgW6vrc51G4xbWKdzK/AP8AwEZb8K+YNGsPsloqsxeQ5LueS7Hksfqa7b4v+ID4t+IEiwPu0vRi1tbYPEkp/wBa/wCGNo+hrn9gAwOg4rix1fl/crpq/Xt8l+LYqMeaTn939ef+RVMZwQKjZDnNXNowahkiypUHGfSvM9o0zaxV2knmo2U5PHFTxW+wnkkEdDyKXYPSrVVW0HZspSW0Uq/vEU/hUDWJXJileP2zkfrWi6YBPbsRVfa07lY8hBwzf4VcZisUAbp0kjUh2HG9RjAp0LpAoRkZD1y3Oa00hCDaFAHtR5Sk42/WtYO7J5SkhVhlWB44xTmjznPIHHSpWsoifu7fTbxTPssyHKSEjsGFdENNiGtCMJg8YproQpx9KlxIo+eJgMdRyKUYcYAFdUZ66mbiVCpIOB2qJuFw3T34q3IpOUjG4jqegFMFqd+9jvI7+ld9Kor2M2jktSAivWYDjPQfWrdjOpYHcMenSo/EACag+096LUgkbhn0JFcVedpX6lUttDo7OXJxj9a0lkAiY57Vz1sEBABKj2NaSO4jOJMgeveuCVVJ6nRynvv7Kig+FtbuMYMmpsp/4CoFex18ufC3x7qHgrTpbC2sbe9tprhp3DuUcE9gRkfpXp1h8bNIdF+3aNqEDcZMZWQe/cGuunUjKN7r7zO7Wlj1WiuN034n+C73A/tYWzk423EbJj8SMfrXR6ZrekakoNhqdpc5GcRzKx/LNa9LhzLqX64n40eKn8MeDJjZuBqd+fs1kM8hj95/oq5P5V2pYAZJAr5j+JfiMeLfHVxdxOH03Ts21lg8Nz+8k/4EwwPZRWdSvGhFzfTp59P67XBpy91dTnLGyW2tEijdhtXGc9fc+9SOsy/xI31GKlLc8f8A6qazDvXzcqrk22/U6UraIgLuv34mA/2eaaJ4icbwvsRipyeDimkKeCAfqKz9om7gMGOoIIpjgAEk4xSPFAilmAX/AHTj+VYmr6rFZhlO6fkDyy/T29cn0pw974R3tqaWw3TcHbCO/wDeqykIRAFHHYVgWvjLTGG2ZJbfHByuR+lbFnrGl3JAhvYXPpuwfyNbcs4u7RKnHuWAhINHl59MnrViPa3IPFSKgPHFOnUsh2uUzHTTGR6EVcYIgJZgMetdX4O+H+seIGWeYNYWBwRI6/vJBz91e3Tqfbg13UJuREmkjioLWe6uUtbWGSedzhI41yWP0rotP+G2tX6hrhViUjO1TnGQTyR34IwPzr3nwv4J0fQrQw2tsoLDEjt8zyH1Y9T0Bx09q6OO2gjGFjXjpx9f8a9BKXQwbctkfOsnwgvI1/0e5njI9DuHUDofr61z2teCdZ0xSTJbzjHQ5Ru/rkHp619WTRl02rgZ7/iKw7zw/YlGknHmOR3HfGP61tBtdTNt9j4c8QRn7ZMOfvGq1jINgBI96s6vNDczyTW774yxwe3U1Us+jK3GDwa5sXJ8zTLpJNI2LdhnqPzzVyOTCkenFZkIXIyozVqJRtBXg5HevMqc1tWdfSxtW8pABODxV6GY4rFi3rgK5/HmrUTyjkhSKwveI0a6ycEHBoAjL7woUjkFeCKoJMwzlG/nUqTDuSPqKxcmtYlWRsHXtat7ZooNZ1JI2BXYLliDkYPBPpWfaQtbW4ji2bR/DjpUKNvkB3DC9BVlX+Ws51qk/ibZKhFapC+ZMB80Wef4W/xo+0Acurr9RTs56Zp2Kxb0AjWaNjgOp/GlDZOOfwonWIITIikD1FVVtN7byXjH8IVsYp8ze4FPWLq55t7CB5JQcM4HCn0Hv79q5aXQtXuJS3ktg5JJ6/QfX8z3wOK7uO3mj/1dwxHo6g1MJJ0HzRI/+6cGtaVZ01pYhq+55/ceDNWkUyosS7RyGfk/T/I9qqx+Er7cPMniTnnvXpv2uMD97BKuf9nP8qzb4wI5kSQshI4xzn6VvHGVb2uL2cXqYGk6LdWwAXU7lcdkOB+Vd94L8O69r0ptdPiku9vEk8gCpH/vNjH4Dmuo+Hfw+tb5o7vW7mN0PK2cEmSf95gf0H517zotjBYWUdvbW0VtCgwkcagAflWtH99L3ndkuSj8Jxfgr4X6ZorJeag41DUByJHX5Iz/ALK9PxOT9K76CGOFcIMf5/8ArCpaSvap0YRWhFr6sKK5vxR448OeHi0V5fLLdDpbQfPJ+IHC/iRXl/if4peINTV4dKjTR7Y8b+HnI+vRfwH41pKpGO7Ba7HrviXxNofh23M2r6hFBxlY85kf6KOTXkHjD4v6jfh4PDlkLKE8fabjBkP0XoPxzXnV87vcPczzvPM5y0krFmb6k1ialrVva7RK67icBQeTUwqqT0Bw7s4YWT6e6WshO2SJZgfTPUUQrlyCcDtW94vjA1swqpXyYVX8f8isRV+bdyADzXJiJOUrvrqOnGysi9DG/dm6VcjSTkHafoKS2hduQx5q/HbuPc15lSb2R0JPYbF5gAynHsRVmN/VWH4VJHA4x8h/Cp1jOOUYfhWDdiuVjI3Q5G4VLu+X5ec0oRec/lTlhTJyoxWEpJjsOjUY5XNSIgxxx+NNWHHRmH409EbHDk/WspPzAcgO3hjSszoCSykemKQb1XnBoG/duZM+mD0pNt3JBQ5be659AO1SiRQOQQfcUgdQDkMPqtOEingMM0asXQVZEboyn8aUkAdvrTWCHgjPtioxEozkYz2HShMESbpJMiIYB/iP9Klt7eJAflDMfvFhyagBKA4cge9L9odepVh+VPyBGhbRpC3mRFopByGjYqR+IrbsvFHiSyZTbeIb9dvRZJPMH5NmuR/tDblACW9jULX7H/WOVHoP8a2ozqJaN2BxjLdHp8Pxa8VWxCyLpl77NEyMfxVsD8qzfEnxF8S60Gjnu/7NtT1gs8gn2L/eP4YFedTatBCp+cKPr1rMm12SYZt1bnu3Fd8cVXkrN6fIj2UUdUdQs4FOwqCepzyayb7XVG4REuR6Vzzme5OZnY57dhVuxsXlO2KJnI9BTUnuO1iO5vby5P3tiHsOtVlsd/Lrk5zk11th4buHG6QrEuPqa1ZvD0Ftp00oDMyISCTxXXTcndshy6HGeM7y11TxBd6habGhkICsh4IAH9c1iQxgllA2mrusWsOnyC0tgViQ/KM5qnA7LBLLtJ2KWq8RLmkTRSijZ0zy3UbgQa3bOzFxc29tFJteaZIwT2ycZrz2w1kxnJVwCc8V0mk+I0hvLW4JOYJUlww4O05wfyrz6lOUHqdUOVq6PYrr4YalDErRXUUuRnoD/hVYfDnX+iQxv9DioIfi9HchN9lCuB/BMy10Wj/FrTY0zJaT5xxtmDfzrVrDNWvY4/8AaY9Dg9d0W80e+SxvYCkzpvABzgZxz/ntVL7KOnln34pvi/W9Z1nxDPqtmyKsp4EhBIUdB/X6k1mLqXiBP9bZQyj2zXmVoRUn7Nq3qdcOblXMtTWFqnuKX7OBwrEn061Ho2p3t3I0dxYCHA67+9bKQD+JQxPWuGTlHRl2Mr7M45/pUc+22hMszLGg6szYFaWoy2thaNcTgqo6Y7mvGvGPiw6lMUhnbyg+4ADgYrowlCpiJWRlUkoLU7O58YaJCoYzswOcbV9Kyr3x/pyZWK2ldsd+BXl00ryuWZic00E9ya96GU0lq2zieIl0PWvD3jPTdTuhbTRm1mY4XLfK3410smVPDMPxzXgCMVIYHkV6V4F8RLeWpsb9y00YzG3dx7+4rlxmXqnHnp7dUaUq3NpI6uWeQZ8s7vqOKqzXDgkyYI9AcVXublmyIgy5HU1UkjllO1i0hPavPirbnQTzamqKVVT9BVR7y4mzg7B3APNSrZSkDOFFXLbTUYneT9T0raLSWg0ZCxlmG47mz1JzWpaaRcyKS+2FPU8068/dSpZxWxMR2sZ+ODvA211djpq3VypKhlC4Iz3rWKb1Ym7Gdpml2KH7sl03sOP8K6rTdLvJUCW1uIQemF3VsaBp+m2rW/2lHPnTLFHx1Y9uK9U0jRo4NoTYF7qoxXRGajojNxdrnn+meC5JY1e9JYkdGbj8ulaWv+F1g8M3zgH5IGxgdOK9PWxttoLKvTHPU1keMpLCPw9qlkJ4RcfZHcQ7xvxjrjriuhOTi7smCXMj5wm0WxjtrTU7vSjqMdxPskzIVCLnBxjv9at+KvANhY6Tqt7pDs9hJBuiDHLRt3XP8q5L4ZeJrmF7/RL557tJlPkP5pDQlTk+xz05/CvYOW+F2oOzFtwAGWzgDnjgeleXipV6WMV5aN7a7adPLudkFCpSfKj5cto/3hwOh5/OtWCHIPy8/WrGmaRNIchSK3rTQ5CANp/KuytWTbsTSWlzJggbbtIP8qsxQ4/LtW0mhXCgDBxRJpU6HBXiuJu92W7szIw6Z2s4/wCBVYimuUPEzn8c1K1q6ZBXFCx4Azx2qHYSRJb3t4jEiQnPqM1eh1W8UD5Ub8KppGemKsRwEjgVyyUX0Kdjz/4keKru8v5LNGKRxDyyoPBPUn+n4Vwr/OxIGPatTxMhGuXoJJ/ft1+pqLTdOe5BYnao6mvqcJGFGhFrseXOMqk2kU4oZJG2oCSaSSNo3KsCCK6eC3trNCzbVx3Y1DItjdyfNlj6qDT+s3e2h0PBWjq9Tmz16Vb0qea2vI54AxeNs4HetPUNIXYXtgcj+HPWo9LtpLdXlkib0Ixzir+sQlBtGSwk1NRe3c9JgdLm0juIuUkUMKs6NsTUFZ1G0A5H4VheDruKSzNkXG8ZeMHqRnn8v61t26kXHOeM818/OHJJxOuUeV2NOeVGkBVAB2zVbVZTb2NxLG6LIqkgtyBQHiS4SIuu5vug9T9BVS9lhkdraSR4WmyEk25ArOlEEZ+mSXNzfxh5ZJE8wdI9qD5xXq/hTTd8yckHOfSuH0jSIo7uGc3NxK4kUfOflwWBr1nwolnbt5095bxhRzukArqnK6TRml3Ou8GWTyKwmhA2N8hOCPqMdK7a1tpVHL7Vz2FcbpHjLwnassEuu6fG+enmjFWbq10u4tp9WvfFV9NYF2IFvIdih/lCjbnOO1VSjbV6BJnbGMHHU4HXNcX4s0a4Fxrmqtb2y250541kHMjfKOPYZBrqNBazbRrI6fK8loYV8l3zuZexOefzqv40IXwfqxzn/RZP5GvSlGKUkvP8iKbu1f8ArU+QvAGmPp95c3E6xeazFFY89+SK9ZuXf/hAJId2fNdgCO/H/wBevOoAZX+yxABmcncfeu8mkC2VppCo2yCMEv8A3ixyf5V5uJwk54mVWfnY76U4xpqMTkYtFngjU2tqJT3HFdb4V8MalqVgbhYLeNwxUo5I5H0zV9EgtbaS4nYRxRrudjwAB1NdJ8Ida0PU9JYWN7HO3mPIdpIIDHAOD9KyqRcndDi1GNrambJ4I1RNoFlFLk8lZh/WqmoeCtUSMu2lS4AydpVv6165sgcAhyNpxT7t0WylYyEhUJz+Fc06LTvcylVb6HztqOgDaSErnLrSpFc4UmvYl03zLOMkZJQVQm8PqzE7KwcnF2KtfY8zsNJkdgChrp9M8MMy5K111h4fVGBKV0djYJGANvT2rCdR9BNdz5e+L3wv1i21GfxBaW+/TWKtOynmLsTjriuTawWwARQpQAHPrX3IdPt57V4J4kkiddrqwyGB6g18n/Hn4f3/AIX8Ry3tnFKNFlKC0w+VQkcqe4weme2K9TB4uVRKlN7bE02qcnJI8y1OJpbwF/8AUryAOhNMiW6kuFEcgSIjovGPartkZri3b7RGFdWx+FODRQOSFyB1KjpXrKXL7pbpKo+dX1LccL7OSTkdaa4wpznngj2pjX0D4Afbx6YpJCSMA5zXLyyvqdnutaMRIJ47m3uoZBG9uwYehHp/Suln1eP7I1xaozSn5RHjJBPfiudQsI8EURSmJ8qx255qZR59+hm6UJe899C+dbJlgvXsxNcWpOArbSRznt7/AKVFe6xb6tBHPEWjZc/K/XOen/16pXe6NPtcYZgCNwHX60jxRT232i2VQ5+Zgo+971cKcFrYwqxcZ80NGbN5rOoTWcMUt48FoijeyfeYjoB71Vm1Z7gLy0NrEMIm75n9yarpH9q09kU8lcqPcVjSs5+Vj04GeK3o01do5cQmnzLZmjLevKLlyTv3gjnoK2PCvizVtHDQ2ty725ZWkt5CTFJg5AK1yisQzcn5lxRbSkSE57V1KnZM5OY+u/hz8dPDGpLDperxLoksSKiMOYD9D/CPrXoHi/UHuPC+qeQsc1k9k7JcJICGOOnFfBMUzAZJORwa6fQvGOv6XaNpMGqXS2Mn3oPMOxh6Y7U5UOZNLdmlOfK02ddoOoxPqafOuftGwe9d1dTT3OvxxwSosUCRlxu5PXP9K4iHwJPbXUN1B4itw/m+cI2j4+netaZtasfOnN1p78ZZ/LIbAHrTqQU3udFPmSvZjPiR400mbStT8Mi/azu2URmXBIHIJHHqOK1v2dLuysneGK6iuQlsFMiggEhvf61xunX/AIOnh+0eILK0lvJDulkMGdx/OtBNL0W923eiW1vHpq7gxibyzv47Zz6c15UozcvZRi9+ytf8/TUqOKpX95RT76rT5u34H1LY3cNxFuUofXD0uqyJ/ZdyqdfKbr9K+H9Z8XXWheK5ba3uL2O2gKqUS6kHuT96u9X9o0R6UbddNnlm8vbulYbW+uDmolhq1laN7lt07N86unt1Poi3iVYUU9gBTJbvToZPLmvbaNv7ryqD+pr5h8Y/HrWNV8NSWGnQQ2M9wgEk0LMHiGeQM+o4zXjE9xcTSNLNNJI7clmYkmopZTUq3c3y/iRVrxg7b+h+iFr9nlXdFLG49VYGrUaqDX546Prer6TdJc6bqV3aTIcq0UpX+Ve4aD+0rqFtZ20GraFHdyIgWWeOfYzkfxYxisa+T16esPe/D8yVXhLrY+gvHvj3w54H02K8166eMTMUhjjQu7kdcAenvXzx8avib4W8azWD6bf3MK2mTtlt25J69PoK5H9oXx9ZeONZ0qfTHf7Lb2nKMCCkjMdw59gvNeYIa7cDlceRVKl1I5qtdpuKPQlmtJ4pbm2nSSInDEAjb+fNZV6rhQsf3G6kd65yzvp7NyYHKlhgjsR7it6CYvZQTLNtaQMCnZeSOPyrplh3Sd1sdlHGRnG0tGQX/lx25iJzMRwvoPUn1qzasyxBGywwMH0qBrH/AJarJ5h9D1z709SynJByOgpuzjZM2jo+Zlwzchc44AINTCBJFJQ7T6VmOxByc5I/KoX1gQNtXEgzyc4xWapN/CafWIxXvmgl8Le5+yzKyk9CRwfardvapHv8vhXOSvaqlpeRXcQkIBxyAw5FXEIZtwzSa5dLWLVpq97roTxttABIyOmKoavbLKDcwr7uB/OppflB4/Gn20gU4PQ04+77y3BxjUjySOfbt696iZtjbh3/AJ1paza+S4kjGI5P0NZkoLRkd69KlJSjc8OtTdObiy05zyO4yRUkrkqpzzVSNi8YJPapQcrye1bxhZ+hKehoXkF/pc5W31JyTxkDH9a1NWtvEsItbSXWWm+14AXnj6/nVG8P2nWIIOu6RV/M11eoDzvG1hAMkQruPt3rnkneN+t39x1VasqM+SnJpLzZgt4b12A3cIu7SRLONXYsCM5BOPrxWO8urWtkl5uj8pHzsDMMkn0z7V3up3ZTS9en3LueURceygf1NcTrzlfD0EeRhnz/ADrlpVqsfe2d1/wTPCQVeFR1Oiv/AJFy00nU/G225i0l2dQU8y3TarH1ZjnOPrTPG3w51Hw3pqXhnS5TIDhUIK5ro/hr8SrDwx4ah0yaxaV0dmZ1B5yfrXQax8WfDuqaVPbS2k0TPGQrohJVscH86pzqwei0LqKFX35SvJ7+p4OUaMFWGD1po5NS3Ukk8hnkO5mPNQ/jXatjkTQoqaK0eaJ5QyqFGTuBGfxxiq+ccVda3ZrYMb6H7hJQsc8dB0qZOyDdWKBpV60lArQyHyI6csrDPqK3bJTJoETp9+KRufYmsSUSBQH3Y7ZrT8PXRRZYGBZMbsD07/0rCsm4XXQ0p25rFoSPEQyMVDjI/rUNwXlLIWOOoxxViYKPlUhlPzIc9PamBNw3r1Heudb3ZveSTRnm2lkbb9oJz6+n51cXSYk6yF29+lMuV8ufB4RhlCP4T6VLBcuB5bHnoD61bc2vdZVGVNSaqK4oSSLDAcfzrYgl3RKx9BVOC5TaFPB7ZqTzxk4xWEuaWjR6FBU4u8XoXGcOjDGM1WQ7DzUSzAA/N2qKaUSjg80Rg1oa863NSG5icGOVFcHjBHFF5pVpNHmJfKY9x0/KsRWYPkNj6Vp2motENrfMOOSa1dOS1izKVWnV0kjPfTLq3U/KHXsVquFdOGUqfpXUpPb3Cn5sE02WFccbWFdVOrK/vHLPCw3izL1Cwu1eGaxR5mPzFoskofwrLnutTgvjNJNcRzYxuZiGxUln4h1W1i8u1v57dQcgRnFUL69ub2dp7qd5pG+8zsSc11zUbnnylc2tCvzcxz6fcbpBId+5pGznPpnFXfH1tBaWmnxxBgWUlssT0A9a5nRZxDqsEjuFTcA7HoAepruPGFrpmsXFu1trtnHHFHtO5XJz+Arza8OWrF9Dpp3lQ5Yb319Dz0vFn5o2J/36ljngaHykilWUn7/mcY9MYraPhi05z4hsPX7kh/8AZaqXGjC0kEkN/b3SL94oCCPwIFae1p7f5mfsKq1sZsABQqxwR3xSNAM58xTRKuZSV7ntTJUmiI3qQD09609BRnDls4j1twfvOv4VFOgU/KeKNzhTnj8KaeRkmmkxOUGrJDccU5MZxgHmnIF28jJp2wEBYwdxNO5kbWq7G0GMhRuDDnH1rK0l9l4B/eBFXHN0tl5N1GECnI3cH8qzlPlTpIuPlINYUo2Ul3NJyvZm0XUEg48tuh9KWJwGIYd+ajfAcp1UjK+4phzHjumeCe31rNRVjS9izcxGSAjGWXlT6iqSHcNp6irUMgztJyrfpVa4jKOcetVCLWjJdrXJFZtuG60byOM5pq/OnvTcHJzWkYiv2H+Y2Tk+3Smlm9aaM++KXHFWoIbnLuKrNzyKcshHWmgHuKD0raMLkqoyxFOw6Gr9tqMirhiD9ayGHvipIQzL15FbRppuzLjXkf/Z</image></event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="512322" />
+    <statestop id="Image" time="512323" />
+    <statestart id="Waiting" time="512323" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="524427" />
+    <statestop id="Waiting" time="524428" />
+    <statestart id="Webcam" time="524429" />
+  </event>
+  <event type="webcam" sid="Webcam" time="524429" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="524441" />
+    <statestop id="Webcam" time="524443" />
+    <statestart id="Waiting" time="524444" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="532750" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="532752" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt-trace.tse ./tools/storyboard/org.tekkotsu.ui/samples/lt-trace.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt-trace.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/lt-trace.tse	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,76 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="302429" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="302430" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="310856" />
+    <statestop id="Waiting" time="310859" />
+    <statestart id="Image" time="310860" />
+  </event>
+  <event type="image" sid="Image" time="310886">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="310923" />
+    <statestop id="Image" time="310924" />
+    <statestart id="Waiting" time="310924" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="320628" />
+    <statestop id="Waiting" time="320630" />
+    <statestart id="Webcam" time="320632" />
+  </event>
+  <event type="webcam" sid="Webcam" time="320632" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="320643" />
+    <statestop id="Webcam" time="320645" />
+    <statestart id="Waiting" time="320645" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="327596" />
+    <statestop id="Waiting" time="327598" />
+    <statestart id="Message" time="327602" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="327603">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="327604" />
+    <statestop id="Message" time="327605" />
+    <statestart id="Waiting" time="327605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="338412" />
+    <statestop id="Waiting" time="338416" />
+    <statestart id="Message" time="338418" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="338419">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="338420" />
+    <statestop id="Message" time="338421" />
+    <statestart id="Waiting" time="338421" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="347770" />
+    <statestop id="Waiting" time="347773" />
+    <statestart id="Image" time="347774" />
+  </event>
+
+  <event type="image" sid="Image" time="347800">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="347829" />
+    <statestop id="Image" time="347835" />
+    <statestart id="Waiting" time="347835" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="359629" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="359635" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt-trace2.tse ./tools/storyboard/org.tekkotsu.ui/samples/lt-trace2.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt-trace2.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/lt-trace2.tse	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,173 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="563157" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="563158" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="569397" />
+    <statestop id="Waiting" time="569401" />
+    <statestart id="Image" time="569402" />
+  </event>
+  <event type="image" sid="Image" time="569428">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="569461" />
+    <statestop id="Image" time="569466" />
+    <statestart id="Waiting" time="569466" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="575116" />
+    <statestop id="Waiting" time="575118" />
+    <statestart id="Message" time="575122" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="575123">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="575124" />
+    <statestop id="Message" time="575125" />
+    <statestart id="Waiting" time="575125" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="582707" />
+    <statestop id="Waiting" time="582709" />
+    <statestart id="Webcam" time="582710" />
+  </event>
+  <event type="webcam" sid="Webcam" time="582710" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="582722" />
+    <statestop id="Webcam" time="582724" />
+    <statestart id="Waiting" time="582725" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="589467" />
+    <statestop id="Waiting" time="589469" />
+    <statestart id="Message" time="589470" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="589470">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="589474" />
+    <statestop id="Message" time="589482" />
+    <statestart id="Waiting" time="589482" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="605276" />
+    <statestop id="Waiting" time="605278" />
+    <statestart id="Image" time="605281" />
+  </event>
+  <event type="image" sid="Image" time="605307">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="605336" />
+    <statestop id="Image" time="605340" />
+    <statestart id="Waiting" time="605340" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="611514" />
+    <statestop id="Waiting" time="611516" />
+    <statestart id="Message" time="611517" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="611517">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="611523" />
+    <statestop id="Message" time="611528" />
+    <statestart id="Waiting" time="611528" />
+  </event>
+  <event>
+    <statestart id="Logging Test" time="672565" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="672566" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="677042" />
+    <statestop id="Waiting" time="677044" />
+    <statestart id="Message" time="677045" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="677045">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="677058" />
+    <statestop id="Message" time="677060" />
+    <statestart id="Waiting" time="677060" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="680995" />
+    <statestop id="Waiting" time="680998" />
+    <statestart id="Image" time="681001" />
+  </event>
+  <event type="image" sid="Image" time="681024">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="681053" />
+    <statestop id="Image" time="681062" />
+    <statestart id="Waiting" time="681064" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="691594" />
+    <statestop id="Waiting" time="691596" />
+    <statestart id="Webcam" time="691597" />
+  </event>
+  <event type="webcam" sid="Webcam" time="691597" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="691602" />
+    <statestop id="Webcam" time="691604" />
+    <statestart id="Waiting" time="691605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="694821" />
+    <statestop id="Waiting" time="694824" />
+    <statestart id="Message" time="694826" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="694827">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="694834" />
+    <statestop id="Message" time="694837" />
+    <statestart id="Waiting" time="694837" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="700540" />
+    <statestop id="Waiting" time="700544" />
+    <statestart id="Message" time="700546" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="700547">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="700549" />
+    <statestop id="Message" time="700550" />
+    <statestart id="Waiting" time="700550" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="704699" />
+    <statestop id="Waiting" time="704702" />
+    <statestart id="Image" time="704705" />
+  </event>
+  <event type="image" sid="Image" time="704731">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="704760" />
+    <statestop id="Image" time="704765" />
+    <statestart id="Waiting" time="704765" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="710315" />
+    <statestop id="Waiting" time="710317" />
+    <statestart id="Webcam" time="710318" />
+  </event>
+  <event type="webcam" sid="Webcam" time="710318" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="710323" />
+    <statestop id="Webcam" time="710325" />
+    <statestart id="Waiting" time="710325" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="717389" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="717394" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt-trace3.tse ./tools/storyboard/org.tekkotsu.ui/samples/lt-trace3.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt-trace3.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/lt-trace3.tse	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,163 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="302429" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="302430" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="310856" />
+    <statestop id="Waiting" time="310859" />
+    <statestart id="Image" time="310860" />
+  </event>
+  <event type="image" sid="Image" time="310886">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="310923" />
+    <statestop id="Image" time="310924" />
+    <statestart id="Waiting" time="310924" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="320628" />
+    <statestop id="Waiting" time="320630" />
+    <statestart id="Webcam" time="320632" />
+  </event>
+  <event type="webcam" sid="Webcam" time="320632" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="320643" />
+    <statestop id="Webcam" time="320645" />
+    <statestart id="Waiting" time="320645" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="327596" />
+    <statestop id="Waiting" time="327598" />
+    <statestart id="Message" time="327602" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="327603">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="327604" />
+    <statestop id="Message" time="327605" />
+    <statestart id="Waiting" time="327605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="338412" />
+    <statestop id="Waiting" time="338416" />
+    <statestart id="Message" time="338418" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="338419">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="338420" />
+    <statestop id="Message" time="338421" />
+    <statestart id="Waiting" time="338421" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="347770" />
+    <statestop id="Waiting" time="347773" />
+    <statestart id="Image" time="347774" />
+  </event>
+
+  <event type="image" sid="Image" time="347800">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="347829" />
+    <statestop id="Image" time="347835" />
+    <statestart id="Waiting" time="347835" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="359629" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="359635" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="1963930" />
+    <statestop id="Waiting" time="1963932" />
+    <statestart id="Message" time="1963933" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="1963934">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="1963938" />
+    <statestop id="Message" time="1963942" />
+    <statestart id="Waiting" time="1963942" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="1976619" />
+    <statestop id="Waiting" time="1976621" />
+    <statestart id="Webcam" time="1976622" />
+  </event>
+  <event type="webcam" sid="Webcam" time="1976622" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="1976626" />
+    <statestop id="Webcam" time="1976629" />
+    <statestart id="Waiting" time="1976629" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="1983795" />
+    <statestop id="Waiting" time="1983798" />
+    <statestart id="Image" time="1983801" />
+  </event>
+  <event type="image" sid="Image" time="1983828">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="1983861" />
+    <statestop id="Image" time="1983866" />
+    <statestart id="Waiting" time="1983866" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="1987644" />
+    <statestop id="Waiting" time="1987648" />
+    <statestart id="Message" time="1987650" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="1987651">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="1987653" />
+    <statestop id="Message" time="1987654" />
+    <statestart id="Waiting" time="1987654" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="1992740" />
+    <statestop id="Waiting" time="1992742" />
+    <statestart id="Webcam" time="1992746" />
+  </event>
+  <event type="webcam" sid="Webcam" time="1992746" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="1992753" />
+    <statestop id="Webcam" time="1992757" />
+    <statestart id="Waiting" time="1992757" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="1996067" />
+    <statestop id="Waiting" time="1996070" />
+    <statestart id="Image" time="1996072" />
+  </event>
+  <event type="image" sid="Image" time="1996096">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="1996125" />
+    <statestop id="Image" time="1996133" />
+    <statestart id="Waiting" time="1996133" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="2000747" />
+    <statestop id="Waiting" time="2000749" />
+    <statestart id="Message" time="2000750" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="2000750">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="2000754" />
+    <statestop id="Message" time="2000757" />
+    <statestart id="Waiting" time="2000757" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="2004811" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="2004813" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt.tsl ./tools/storyboard/org.tekkotsu.ui/samples/lt.tsl
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/lt.tsl	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,15 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="lt.tsm">
+  <state id="Logging Test" label="Logging Test" color="#ffc400" top="17" left="67" width="171" height="20" shape="Rectangle" />
+  <state id="Waiting" label="Waiting" color="#00ff00" top="165" left="150" width="50" height="20" shape="Rectangle" />
+  <state id="Image" label="Image" color="#00ffff" top="136" left="76" width="50" height="20" shape="Rectangle" />
+  <state id="Message" label="Message" color="#60ff60" top="93" left="111" width="50" height="20" shape="Rectangle" />
+  <state id="Webcam" label="Webcam" color="#ff0000" top="56" left="160" width="50" height="20" shape="Rectangle" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans" label="transition9" color="#000000" top="130" left="136" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans" label="transition13" color="#000000" top="118" left="160" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans" label="transition17" color="#000000" top="109" left="181" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition21" color="#000000" top="168" left="120" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition25" color="#000000" top="138" left="126" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition29" color="#000000" top="111" left="141" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt.tsm ./tools/storyboard/org.tekkotsu.ui/samples/lt.tsm
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/lt.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/lt.tsm	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,33 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Logging Test" class="LogTestMachine" />
+  <state id="Waiting" class="StateNode" />
+  <state id="Image" class="ImageLogTestNode" />
+  <state id="Message" class="MessageLogTestNode" />
+  <state id="Webcam" class="WebcamLogTestNode" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Image</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Message</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Webcam</destination>
+  </transition>
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Image</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Message</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Webcam</source>
+    <destination>Waiting</destination>
+  </transition>
+</model>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/test/aug.tsl ./tools/storyboard/org.tekkotsu.ui/samples/test/aug.tsl
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/test/aug.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/test/aug.tsl	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,15 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="foo.tsm">
+  <state id="Logging Test" label="Logging Test" color="#ffc400" top="32" left="67" width="168" height="20" shape="Rectangle" />
+  <state id="Waiting" label="Waiting" color="#00ff00" top="186" left="165" width="50" height="20" shape="Rectangle" />
+  <state id="Image" label="Image" color="#00ffff" top="150" left="79" width="50" height="20" shape="Rectangle" />
+  <state id="Message" label="Message" color="#60ff60" top="108" left="116" width="50" height="20" shape="Rectangle" />
+  <state id="Webcam" label="Webcam" color="#ff0000" top="76" left="173" width="50" height="20" shape="Rectangle" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans" label="transition9" color="#000000" top="149" left="146" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans" label="transition13" color="#000000" top="135" left="170" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans" label="transition17" color="#000000" top="129" left="196" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition21" color="#000000" top="185" left="130" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition25" color="#000000" top="157" left="136" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition29" color="#000000" top="131" left="156" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/test/test ./tools/storyboard/org.tekkotsu.ui/samples/test/test
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/samples/test/test	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/samples/test/test	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,33 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Logging Test" class="LogTestMachine" />
+  <state id="Waiting" class="StateNode" />
+  <state id="Image" class="ImageLogTestNode" />
+  <state id="Message" class="MessageLogTestNode" />
+  <state id="Webcam" class="WebcamLogTestNode" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Image</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Message</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Webcam</destination>
+  </transition>
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Image</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Message</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Webcam</source>
+    <destination>Waiting</destination>
+  </transition>
+</model>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurve.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurve.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurve.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurve.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,306 @@
+/*
+ * Created on Nov 19, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import java.util.List;
+
+import org.eclipse.draw2d.Connection;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Shape;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.PointList;
+import org.eclipse.draw2d.geometry.Rectangle;
+
+/**
+ * @author asangpet
+ *
+ */
+public class BezierCurve extends Shape {
+
+	PointList points = new PointList();	
+	private static final int TOLERANCE = 2;
+	private static final Rectangle LINEBOUNDS = Rectangle.SINGLETON;
+
+	{
+		bounds  = null;
+	}
+
+	/**
+	 * Adds the passed point to the Polyline.
+	 * 
+	 * @param pt the Point to be added to the Polyline
+	 * @since 2.0
+	 */
+	public void addPoint(Point pt) {
+		points.addPoint(pt);
+		bounds = null;
+		repaint();
+	}
+
+	/**
+	 * @see org.eclipse.draw2d.IFigure#containsPoint(int, int)
+	 */
+	public boolean containsPoint(int x, int y) {
+
+		int tolerance = lineWidth / 2 + TOLERANCE;
+		LINEBOUNDS.setBounds(getBounds());
+		LINEBOUNDS.expand(tolerance, tolerance);
+		if (!LINEBOUNDS.contains(x, y))
+			return false;
+		int ints[] = points.toIntArray();
+		for (int index = 0; index < ints.length - 3; index  += 2) {
+			if (lineContainsPoint(ints[index], ints[index + 1],
+				ints[index + 2], ints[index + 3], x, y, tolerance))
+				return true;
+		}
+		List children = getChildren();
+		for (int i = 0; i < children.size(); i++) {
+			if (((IFigure)children.get(i)).containsPoint(x, y))
+				return true;
+		}
+		return false;
+	}
+
+	private boolean lineContainsPoint(
+		int x1, int y1,
+		int x2, int y2,
+		int px, int py,
+		int tolerance) {
+		LINEBOUNDS.setSize(0, 0);
+		LINEBOUNDS.setLocation(x1, y1);
+		LINEBOUNDS.union(x2, y2);
+		LINEBOUNDS.expand(tolerance, tolerance);
+		if (!LINEBOUNDS.contains(px, py))
+			return false;
+
+		int v1x, v1y, v2x, v2y;
+		int numerator, denominator;
+		int result = 0;
+
+		/**
+		 * calculates the length squared of the cross product of two vectors, v1 & v2.
+		 */
+		if (x1 != x2 && y1 != y2) {
+			v1x = x2 - x1;
+			v1y = y2 - y1;
+			v2x = px - x1;
+			v2y = py - y1;
+			
+			numerator = v2x * v1y - v1x * v2y;
+			
+			denominator = v1x * v1x + v1y * v1y;
+
+			result = (int)((long)numerator * numerator / denominator);
+		}
+		
+		// if it is the same point, and it passes the bounding box test,
+		// the result is always true.
+		return result <= tolerance * tolerance;
+								
+	}
+
+	/**
+	 * Null implementation for a line.
+	 * @see org.eclipse.draw2d.Shape#fillShape(Graphics)
+	 */
+	protected void fillShape(Graphics g) { }
+
+	/**
+	 * @see org.eclipse.draw2d.IFigure#getBounds()
+	 */
+	public Rectangle getBounds() {
+		if (bounds == null) {
+			bounds = getPoints()
+				.getBounds()
+				.getExpanded(lineWidth / 2, lineWidth / 2);
+		}
+		return bounds;
+	}
+
+	/**
+	 * Returns the last point in the Polyline.
+	 * @since 2.0
+	 * @return the last point
+	 */
+	public Point getEnd() {
+		return points.getLastPoint();
+	}
+
+	/**
+	 * Returns the points in this Polyline <B>by reference</B>. If the returned list is 
+	 * modified, this Polyline must be informed by calling {@link #setPoints(PointList)}.  
+	 * Failure to do so will result in layout and paint problems.
+	 * 
+	 * @return this Polyline's points
+	 * @since 2.0
+	 */
+	public PointList getPoints() {
+		return points;
+	}
+
+	/**
+	 * @return the first point in the Polyline
+	 * @since 2.0
+	 */
+	public Point getStart() {
+		return points.getFirstPoint();
+	}
+
+	/**
+	 * Inserts a given point at a specified index in the Polyline.
+	 * 
+	 * @param pt the point to be added
+	 * @param index the position in the Polyline where the point is to be added
+	 * 
+	 * @since 2.0
+	 */
+	public void insertPoint(Point pt, int index) {
+		bounds = null;
+		points.insertPoint(pt, index);
+		repaint();
+	}
+
+	/**
+	 * @return <code>false</code> because Polyline's aren't filled
+	 */
+	public boolean isOpaque() {
+		return false;
+	}
+
+	Point getBezier(Point A, Point B, Point C, double t) {
+		Point P = new Point();				
+		P.x = (int)Math.round((1-t)*(1-t) * A.x + 2 * t * (1 -t) * B.x + t*t * C.x);
+		P.y = (int)Math.round((1-t)*(1-t) * A.y + 2 * t * (1 -t) * B.y + t*t * C.y);
+		return P;
+	}
+
+	/**
+	 * @see Shape#outlineShape(Graphics)
+	 */
+	protected void outlineShape(Graphics g) {										
+		Point POld=points.getPoint(0);
+		for(double t = 0.0;t <= 1.0; t += 0.1) {
+			Point P = getBezier(points.getPoint(0), points.getPoint(1), points.getPoint(2), t);
+			g.drawLine(POld.x,POld.y, P.x,P.y);
+			POld = P;
+		}
+	}
+
+	/**
+	 * @see Figure#primTranslate(int, int)
+	 */
+	public void primTranslate(int x, int y) { }
+
+	/** 
+	 * Erases the Polyline and removes all of its {@link Point Points}.
+	 * 
+	 * @since 2.0
+	 */
+	public void removeAllPoints() {
+		erase();
+		bounds = null;
+		points.removeAllPoints();		
+	}
+
+	/**
+	 * Removes a point from the Polyline.
+	 * 
+	 * @param index the position of the point to be removed
+	 * @since 2.0
+	 */
+	public void removePoint(int index) {
+		erase();
+		bounds = null;
+		points.removePoint(index);		
+	}
+
+	/**
+	 * Sets the end point of the Polyline
+	 * 
+	 * @param end the point that will become the last point in the Polyline
+	 * @since 2.0
+	 */
+	public void setEnd(Point end) {
+		if (points.size() < 2)
+			addPoint(end);
+		else
+			setPoint(end, points.size() - 1);
+	}
+
+	/**
+	 * Sets the points at both extremes of the Polyline
+	 * 
+	 * @param start the point to become the first point in the Polyline
+	 * @param end the point to become the last point in the Polyline
+	 * @since 2.0
+	 */
+	public void setEndpoints(Point start, Point end) {
+		setStart(start);
+		setEnd(end);
+	}
+
+	/**
+	 * @see org.eclipse.draw2d.Shape#setLineWidth(int)
+	 */
+	public void setLineWidth(int w) {
+		if (lineWidth == w)
+			return;
+		if (w < lineWidth) //The bounds will become smaller, so erase must occur first.
+			erase();
+		bounds = null;
+		super.setLineWidth(w);
+	}
+
+	/**
+	 * Sets the point at <code>index</code> to the Point <code>pt</code>.  Calling this method
+	 * results in a recalculation of the polyline's bounding box.  If you're going to set
+	 * multiple Points, use {@link #setPoints(PointList)}.
+	 * @param pt the point
+	 * @param index the index
+	 */
+	public void setPoint(Point pt, int index) {
+		erase();
+		points.setPoint(pt, index);
+		bounds = null;
+		repaint();
+	}
+
+	/**
+	 * Sets the list of points to be used by this polyline connection. Removes any previously 
+	 * existing points. The polyline will hold onto the given list by reference.
+	 *
+	 * @param points new set of points
+	 * @since 2.0
+	 */
+	public void setPoints(PointList points) {
+		erase();
+		this.points = points;				
+		bounds = null;
+		firePropertyChange(Connection.PROPERTY_POINTS, null, points); //$NON-NLS-1$
+		repaint();
+	}
+
+	/**
+	 * Sets the start point of the Polyline
+	 * 
+	 * @param start the point that will become the first point in the Polyline
+	 * @since 2.0
+	 */
+	public void setStart(Point start) {
+		if (points.size() == 0)
+			addPoint(start);
+		else
+			setPoint(start, 0);
+	}
+
+	/**
+	 * @see Figure#useLocalCoordinates()
+	 */
+	protected boolean useLocalCoordinates() {
+		return false;
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurveConnection.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurveConnection.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurveConnection.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/BezierCurveConnection.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,289 @@
+/*
+ * Created on Nov 19, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import java.util.List;
+
+import org.eclipse.draw2d.AnchorListener;
+import org.eclipse.draw2d.ArrowLocator;
+import org.eclipse.draw2d.Connection;
+import org.eclipse.draw2d.ConnectionAnchor;
+import org.eclipse.draw2d.ConnectionLocator;
+import org.eclipse.draw2d.ConnectionRouter;
+import org.eclipse.draw2d.DelegatingLayout;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.RotatableDecoration;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.PointList;
+import org.eclipse.draw2d.geometry.Rectangle;
+
+/**
+ * @author asangpet
+ *
+ */
+public class BezierCurveConnection extends BezierCurve implements Connection,TransitionConnection,
+		AnchorListener {
+
+	private ConnectionAnchor startAnchor, endAnchor;
+	private ConnectionRouter connectionRouter = ConnectionRouter.NULL;
+	private RotatableDecoration startArrow, endArrow;
+
+	{
+		setLayoutManager(new DelegatingLayout());
+		addPoint(new Point(0, 0));
+		addPoint(new Point(100, 100));
+	}
+	
+	/* (non-Javadoc)
+	 * @see org.eclipse.draw2d.Connection#setPoints(org.eclipse.draw2d.geometry.PointList)
+	 */
+	public void setPoints(PointList list) {		
+		PointList control = new PointList();
+		control.addPoint(list.getFirstPoint());
+		
+		int dx = list.getLastPoint().x - list.getFirstPoint().x;
+		int dy = list.getLastPoint().y - list.getFirstPoint().y;
+		float ds = (int)Math.sqrt(dx*dx+dy*dy);
+		int du = 20;
+		
+		control.addPoint(list.getMidpoint().getTranslated(Math.round(dy*du/ds),Math.round(-dx*du/ds)));
+		
+		control.addPoint(list.getLastPoint());
+		super.setPoints(control);
+	}
+	
+	/**
+	 * Hooks the source and target anchors.
+	 * @see Figure#addNotify()
+	 */
+	public void addNotify() {
+		super.addNotify();
+		hookSourceAnchor();
+		hookTargetAnchor();
+	}
+
+	/**
+	 * Called by the anchors of this connection when they have moved, revalidating this 
+	 * polyline connection.
+	 * @param anchor the anchor that moved
+	 */
+	public void anchorMoved(ConnectionAnchor anchor) {
+		revalidate();
+	}
+
+	/**
+	 * Returns the bounds which holds all the points in this polyline connection. Returns any 
+	 * previously existing bounds, else calculates by unioning all the children's
+	 * dimensions.
+	 * @return the bounds
+	 */
+	public Rectangle getBounds() {
+		if (bounds == null) {
+			super.getBounds();
+			for (int i = 0; i < getChildren().size(); i++) {
+				IFigure child = (IFigure)getChildren().get(i);
+				bounds.union(child.getBounds());
+			}
+		}
+		return bounds;
+	}
+
+	/**
+	 * Returns the <code>ConnectionRouter</code> used to layout this connection. Will not 
+	 * return <code>null</code>.
+	 * @return this connection's router
+	 */
+	public ConnectionRouter getConnectionRouter() {
+		return connectionRouter;
+	}
+
+	/**
+	 * Returns this connection's routing constraint from its connection router.  May return 
+	 * <code>null</code>.
+	 * @return the connection's routing constraint
+	 */
+	public Object getRoutingConstraint() {
+		if (getConnectionRouter() != null)
+			return (List)getConnectionRouter().getConstraint(this);
+		else
+			return null;
+	}
+
+	/**
+	 * @return the anchor at the start of this polyline connection (may be null)
+	 */
+	public ConnectionAnchor getSourceAnchor() {
+		return startAnchor;
+	}
+
+	/**
+	 * @return the source decoration (may be null)
+	 */
+	protected RotatableDecoration getSourceDecoration() {
+		return startArrow;
+	}
+
+	/**
+	 * @return the anchor at the end of this polyline connection (may be null)
+	 */
+	public ConnectionAnchor getTargetAnchor() {
+		return endAnchor;
+	}
+
+	/**
+	 * @return the target decoration (may be null)
+	 * 
+	 * @since 2.0
+	 */
+	protected RotatableDecoration getTargetDecoration() {
+		return endArrow;
+	}
+
+	private void hookSourceAnchor() {
+		if (getSourceAnchor() != null)
+			getSourceAnchor().addAnchorListener(this);
+	}
+
+	private void hookTargetAnchor() {
+		if (getTargetAnchor() != null)
+			getTargetAnchor().addAnchorListener(this);
+	}
+
+	/**
+	 * Layouts this polyline. If the start and end anchors are present, the connection router 
+	 * is used to route this, after which it is laid out. It also fires a moved method.
+	 */
+	public void layout() {
+		if (getSourceAnchor() != null && getTargetAnchor() != null)
+			getConnectionRouter().route(this);
+
+		Rectangle oldBounds = bounds;
+		super.layout();
+		bounds = null;
+		
+		if (!getBounds().contains(oldBounds)) {
+			getParent().translateToParent(oldBounds);
+			getUpdateManager().addDirtyRegion(getParent(), oldBounds);
+		}
+		
+		repaint();
+		fireMoved();
+	}
+
+	/**
+	 * Called just before the receiver is being removed from its parent. Results in removing 
+	 * itself from the connection router.
+	 * 
+	 * @since 2.0
+	 */
+	public void removeNotify() {
+		unhookSourceAnchor();
+		unhookTargetAnchor();
+		getConnectionRouter().remove(this);
+		super.removeNotify();
+	}
+
+	/**
+	 * @see org.eclipse.draw2d.IFigure#revalidate()
+	 */
+	public void revalidate() {
+		super.revalidate();
+		getConnectionRouter().invalidate(this);
+	}
+
+	/**
+	 * Sets the connection router which handles the layout of this polyline. Generally set by 
+	 * the parent handling the polyline connection.
+	 * @param cr the connection router
+	 */
+	public void setConnectionRouter(ConnectionRouter cr) {
+		if (cr == null)
+			cr = ConnectionRouter.NULL;
+		if (connectionRouter != cr) {
+			connectionRouter.remove(this);
+			Object old = connectionRouter;
+			connectionRouter = cr;
+			firePropertyChange(Connection.PROPERTY_CONNECTION_ROUTER, old, cr);
+			revalidate();
+		}
+	}
+
+	/**
+	 * Sets the routing constraint for this connection.
+	 * @param cons the constraint
+	 */
+	public void setRoutingConstraint(Object cons) {
+		if (getConnectionRouter() != null)
+			getConnectionRouter().setConstraint(this, cons);
+		revalidate();
+	}
+
+	/**
+	 * Sets the anchor to be used at the start of this polyline connection.
+	 * @param anchor the new source anchor
+	 */
+	public void setSourceAnchor(ConnectionAnchor anchor) {
+		unhookSourceAnchor();
+		//No longer needed, revalidate does this.
+		//getConnectionRouter().invalidate(this);
+		startAnchor = anchor;
+		if (getParent() != null)
+			hookSourceAnchor();
+		revalidate(); 
+	}
+
+	/**
+	 * Sets the decoration to be used at the start of the {@link Connection}.
+	 * @param dec the new source decoration
+	 * @since 2.0
+	 */
+	public void setSourceDecoration(RotatableDecoration dec) {
+		if (getSourceDecoration() != null)
+			remove(getSourceDecoration());
+		startArrow = dec;
+		if (dec != null)
+			add(dec, new ArrowLocator(this, ConnectionLocator.SOURCE));
+	}
+
+	/**
+	 * Sets the anchor to be used at the end of the polyline connection. Removes this listener 
+	 * from the old anchor and adds it to the new anchor.
+	 * @param anchor the new target anchor
+	 */
+	public void setTargetAnchor(ConnectionAnchor anchor) {
+		unhookTargetAnchor();
+		//No longer needed, revalidate does this.
+		//getConnectionRouter().invalidate(this);
+		endAnchor = anchor;
+		if (getParent() != null)
+			hookTargetAnchor();
+		revalidate();
+	}
+
+	/**
+	 * Sets the decoration to be used at the end of the {@link Connection}.
+	 * @param dec the new target decoration
+	 */
+	public void setTargetDecoration(RotatableDecoration dec) {
+		if (getTargetDecoration() != null)
+			remove(getTargetDecoration());
+		endArrow = dec;
+		if (dec != null)
+			add(dec, new ArrowLocator(this, ConnectionLocator.TARGET));
+	}
+
+	private void unhookSourceAnchor() {
+		if (getSourceAnchor() != null)
+			getSourceAnchor().removeAnchorListener(this);
+	}
+
+	private void unhookTargetAnchor() {
+		if (getTargetAnchor() != null)
+			getTargetAnchor().removeAnchorListener(this);
+	}
+
+
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/DummyServer.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/DummyServer.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/DummyServer.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/DummyServer.java	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,95 @@
+/*
+ * Created on Nov 4, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+/**
+ * @author asangpet
+ */
+import java.io.*;
+import java.net.*;
+import java.util.logging.Level;
+import java.util.logging.Logger;
+
+import org.tekkotsu.ui.editor.debug.TestResource;
+
+public class DummyServer {
+    private static Logger logger = Logger.getLogger(DummyServer.class.getName());
+	public static final int port = 10080;
+	//public static final String src = "Q:\\workspaces\\runtime-workspace\\test\\runlog.txt";
+	//public static final String src = "e:\\projects\\runtime-workspace\\runlog.txt";
+	//public static final String src = "/home/asangpet/runtime-workspace/rtu.tse";
+	//public static final String src = "e:\\tekkotsu\\viewer\\rtu.tse";
+	public static final String src = "lt-trace.tse";
+	//public static final String srcmod = "Q:\\workspaces\\runtime-workspace\\test\\rtu.tsm";
+	//public static final String srcmod = "e:\\projects\\runtime-workspace\\rtu.tsm";
+	//public static final String srcmod = "/home/asangpet/runtime-workspace/rtu.tsm";
+	//public static final String srcmod = "e:\\tekkotsu\\viewer\\rtu.tsm";
+	public static final String srcmod = "lt.tsm";
+	ServerSocket serverSocket; 
+	Socket clientSocket;
+	String machineName = "SampleBehavior";
+		
+	public void process() {	
+		try {
+			serverSocket = new ServerSocket(port);			
+			while (true) {
+				logger.info("waiting...port "+port);
+				serverSocket.setReuseAddress(true);
+				clientSocket = serverSocket.accept();
+				logger.info("Client connect "+clientSocket);
+				PrintWriter out = new PrintWriter(clientSocket.getOutputStream(), true);
+				BufferedReader in = new BufferedReader(new InputStreamReader(clientSocket.getInputStream()));
+				try {
+				while (clientSocket.isConnected()) {
+					String command = in.readLine();
+					logger.info(command);
+					if (command.startsWith("listen")) {
+						logger.info("tracing: "+command);
+						BufferedReader fin = null; 
+						fin = new BufferedReader(new InputStreamReader(TestResource.class.getResourceAsStream(src)));			
+						Thread.sleep(50);
+						String inputLine="";
+						while ((inputLine = fin.readLine())!=null) {						    
+							logger.info(inputLine);
+							if (inputLine.indexOf("trace")>=0) continue;
+							out.println(inputLine);
+							if (inputLine.startsWith("</event")) {
+								Thread.sleep(2000);
+							}
+							if (in.ready()) {
+								if (in.readLine().startsWith("clear")) break;
+							}
+						}
+					} else if (command.startsWith("spider")) {
+						machineName = command.substring(7);
+					    logger.fine("modeling: "+machineName);
+						BufferedReader fin = null; 
+						fin = new BufferedReader(new InputStreamReader(TestResource.class.getResourceAsStream(srcmod)));			
+						Thread.sleep(50);
+						String inputLine="";
+						while ((inputLine = fin.readLine())!=null) {
+							//logger.fine(inputLine);
+							out.println(inputLine);
+						}
+					} else if (command.startsWith("list")) {
+						logger.info("list statemachine");
+						out.println("1");
+						out.println(machineName);
+					}
+				}
+				} catch (Exception ee) {
+					ee.printStackTrace();
+					clientSocket.close();
+				}
+			}
+		} catch (Exception e) {
+			e.printStackTrace();
+		}
+	}
+	
+	public static void main(String args[]) {	    
+	    logger.setLevel(Level.FINE);
+		new DummyServer().process();
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/ModelConnector.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/ModelConnector.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/ModelConnector.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/ModelConnector.java	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,410 @@
+/*
+ * Created on Nov 4, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeSupport;
+import java.io.*;
+import java.net.*;
+import java.util.logging.Logger;
+
+import org.tekkotsu.ui.editor.resources.Debugger;
+
+/**
+ * @author asangpet
+ */
+public class ModelConnector implements Runnable, PropertyChangeListener {
+    private static Logger logger = Logger.getLogger(ModelConnector.class
+            .getName());
+
+    public static final String EVENT_DATA_UPDATE = "_model_conn_update";
+
+    public static final String EVENT_MODEL_UPDATE = "_model_conn_model_update";
+
+    public static final String EVENT_TRACE_UPDATE = "_model_conn_trace_update";
+
+    public static final String EVENT_TRACE_REFRESH = "_model_conn_trace_refresh";
+
+    public static final String EVENT_TRACE_UPDATE_TIME = "_model_conn_trace_update_time";
+
+    public static final String EVENT_TRACE_CLEAR = "_model_conn_trace_clear";
+
+    public static final String EVENT_TRACE_MODE_ENTER = "_model_conn_trace_mode";
+
+    public static final String EVENT_TRACE_MODE_EXIT = "_model_conn_trace_exit";
+
+    static String defaultHostName = "localhost";
+
+    static String defaultMachineName = "Explore State Machine";
+
+    static int defaultPort = 10080;
+
+    int hostPort = defaultPort;
+
+    String hostName = defaultHostName;
+
+    String command = "find";
+
+    String lastCommand;
+
+    String machineName = defaultMachineName;
+
+    Socket modelSocket = null;
+
+    PrintWriter out = null;
+
+    StringBuffer outbuf = null;
+
+    BufferedReader in = null;
+
+    Thread worker;
+
+    boolean isStop = false; // indicate whether the thread is sending info to
+
+    // client
+
+    boolean isReady = false; // indicate whether there is a thread running
+
+    boolean isResume = false;
+
+    boolean needReconnect = true;
+
+    boolean commandChange = true;
+
+    private PropertyChangeSupport listeners = new PropertyChangeSupport(this);
+
+    TimerTick tick = new TimerTick(0, this);
+
+    class TimerTick extends Thread {
+
+        ModelConnector conn;
+
+        int time;
+
+        boolean isCount = true;
+
+        public TimerTick(int startTime, ModelConnector conn) {
+            time = startTime;
+            this.conn = conn;
+        }
+
+        public synchronized void setTime(int time) {
+            this.time = time;
+        }
+
+        public synchronized int getTime() {
+            return time;
+        }
+
+        public void stopTime() {
+            isCount = false;
+        }
+
+        public void run() {
+            while (isCount) {
+                try {
+                    // sleep for 1 second
+                    sleep(1000);
+                    time = time + 1000;
+                    conn.firePropertyChange(
+                            ModelConnector.EVENT_TRACE_UPDATE_TIME, null,
+                            new Integer(time));
+                } catch (Exception e) {
+                }
+            }
+        }
+    }
+
+    public void propertyChange(PropertyChangeEvent evt) {
+        if (evt.getPropertyName().equals(EVENT_TRACE_UPDATE_TIME)) {
+            int time = ((Integer) evt.getNewValue()).intValue();
+            if (time > tick.getTime()) {
+                tick.setTime(time);
+            }
+            if (time < tick.getTime()) {
+                tick.setTime(time);
+                firePropertyChange(EVENT_TRACE_REFRESH, null, null);
+            }
+        }
+
+    }
+
+    public void addPropertyChangeListener(PropertyChangeListener listener) {
+        listeners.addPropertyChangeListener(listener);
+    }
+
+    public void firePropertyChange(String propName, Object oldValue,
+            Object newValue) {
+        listeners.firePropertyChange(propName, oldValue, newValue);
+    }
+
+    public void removePropertyChangeListener(PropertyChangeListener listener) {
+        listeners.removePropertyChangeListener(listener);
+    }
+
+    public void setMachineName(String machName) {
+        this.machineName = machName;
+        defaultMachineName = machName;
+        needReconnect = true;
+    }
+
+    public String getMachineName() {
+        return machineName;
+    }
+
+    // send a query to the robot
+    public void execute(String command) {
+        isStop = false;
+        setCommand(command);
+
+        if (!isReady) {
+            Thread t = new Thread(this);
+            t.start();
+        }
+    }
+
+    boolean connect() {
+        try {
+            try {
+                if (out != null) out.close();
+                if (in != null) in.close();
+                if (modelSocket != null) modelSocket.close();
+                modelSocket = null;
+            } catch (Exception e) {
+                e.printStackTrace();
+            }
+
+            firePropertyChange(EVENT_DATA_UPDATE, null, "Connecting to "
+                    + getHostName() + ":" + getHostPort() + "...");
+            modelSocket = new Socket(hostName, hostPort);
+            out = new PrintWriter(modelSocket.getOutputStream(), true);
+            in = new BufferedReader(new InputStreamReader(modelSocket
+                    .getInputStream()));
+            needReconnect = false;
+            firePropertyChange(EVENT_DATA_UPDATE, null, "Connected");
+            return true;
+        } catch (Exception e) {
+            firePropertyChange(EVENT_DATA_UPDATE, null,
+                    "Unable to connect, please try again");
+            e.printStackTrace();
+            return false;
+        }
+    }
+
+    public ModelConnector() {
+    }
+
+    public ModelConnector(String hostname, int port) {
+        setHostName(hostname);
+        setHostPort(port);
+    }
+
+    public String readLine() {
+        try {
+            String result = in.readLine();
+            Debugger.printDebug(Debugger.DEBUG_ALL, "read: " + result);
+            firePropertyChange(EVENT_DATA_UPDATE, null, result);
+            return result;
+        } catch (IOException e) {
+            return null;
+        }
+    }
+
+    public boolean isStop() {
+        return isStop;
+    }
+
+    void disconnect() {
+        try {
+            firePropertyChange(EVENT_DATA_UPDATE, null, "Disconnect");
+            if (out != null)
+                out.close();
+            if (in != null)
+                in.close();
+            if (modelSocket != null)
+                modelSocket.close();
+            modelSocket = null;
+            // isStop = true;
+            needReconnect = true;
+        } catch (Exception e) {
+            e.printStackTrace();
+        }
+    }
+
+    /**
+     * @return Returns the hostName.
+     */
+    public String getHostName() {
+        return hostName;
+    }
+
+    /**
+     * @param hostName
+     *            The hostName to set.
+     */
+    public void setHostName(String hostName) {
+        this.hostName = hostName;
+        defaultHostName = hostName;
+    }
+
+    /**
+     * @return Returns the hostPort.
+     */
+    public int getHostPort() {
+        return hostPort;
+    }
+
+    /**
+     * @param hostPort
+     *            The hostPort to set.
+     */
+    public void setHostPort(int hostPort) {
+        this.hostPort = hostPort;
+        defaultPort = hostPort;
+        needReconnect = true;
+    }
+
+    private String trimBuf(String prefix, String suffix, StringBuffer buf) {
+        int idstart = buf.indexOf(prefix);
+        int idend = buf.indexOf(suffix);
+        if (idstart == -1)
+            return prefix + ">" + suffix;       
+        return buf.substring(idstart, idend + suffix.length());
+    }
+
+    public void run() {
+        // event loop - keep reading
+        String result = "";
+        outbuf = new StringBuffer();
+        while (true) {
+            try {
+                isReady = true;
+                if (needReconnect) {
+                    isReady = connect();
+                }
+                if (!isReady) {
+                    isStop = true;
+                    tick.stopTime();
+                    return;
+                }
+                if (commandChange) {
+                    out.println("clear");
+                    if (getCommand().equals("clear")) {
+                        commandChange = false;
+                        logger.finest("reader spin");
+                        continue;
+                    }
+                    out.println(getCommand() + " " + machineName); // spider
+
+                    // start timer
+                    if (isReady) {
+                        if (command.startsWith("listen")) {
+                            //tick.setTime(0);
+                            //tick.start();
+                        }
+                    }
+
+                    // MachineName
+                    firePropertyChange(EVENT_DATA_UPDATE, null,
+                            "Enter reading loop " + getCommand() + " "
+                                    + machineName + " from " + getHostName()
+                                    + "\r\n");
+                    result = "";
+                    outbuf = new StringBuffer();
+                    if (!isResume) {
+                        // firePropertyChange(EVENT_TRACE_CLEAR, null, null);
+                        isResume = false;
+                    } else {
+                        // resuming
+                        // TODO implement resume code for timer, do we need this?
+                        /*
+                         * int time = tick.getTime(); tick = new
+                         * TimerTick(time,this); tick.start();
+                         */
+                    }
+                    commandChange = false;
+                }
+                if (in.ready()) {
+                    result = readLine();
+                    if (result != null) {
+                        outbuf.append(result + "\n");
+                        if (result.indexOf("</model>") > -1) {
+                            if (!isStop())
+                                firePropertyChange(EVENT_MODEL_UPDATE, null,
+                                        trimBuf("<model", "</model>", outbuf));
+                            outbuf = new StringBuffer();
+                        } else if (result.indexOf("</event>") > -1) {
+                            if (!isStop()) {
+                                while (outbuf.toString().indexOf("</event>") > -1) {
+                                	if (outbuf.toString().indexOf("<event ") > -1) {
+                                		String bufstr = outbuf.toString();
+                                		int idstart = bufstr.indexOf("<event ");
+                                		int idend = bufstr.indexOf("/>");
+                                		if (idend>-1) {
+                                			int idnend = bufstr.indexOf(">");
+                                			if (!(idnend > -1 && idnend < idend)) {                                				
+                                				firePropertyChange(EVENT_TRACE_UPDATE,
+                                						null, bufstr.substring(idstart,idend+ "/>".length()));          
+                                				outbuf.delete(0, idend+ ("/>".length()));
+                                			}
+                                		}
+                                	}
+                                    firePropertyChange(EVENT_TRACE_UPDATE,
+                                            null, trimBuf("<event", "</event>",
+                                                    outbuf));
+                                    int idend = outbuf.indexOf("</event>");
+                                    outbuf.delete(0, idend
+                                            + "</event>".length());
+                                }
+                            }
+                            outbuf = new StringBuffer();
+                        }
+                    }
+                    continue;
+                }
+                Thread.sleep(1000);
+                //Thread.yield();
+            } catch (Exception e) {
+                e.printStackTrace();
+            }
+        }
+    }
+
+    public StringBuffer getOutputBuffer() {
+        return outbuf;
+    }
+
+    public void stop() {
+        tick.stopTime();
+        lastCommand = command;
+        setCommand("clear");
+        isStop = true;
+    }
+
+    public void newTrace() {
+        tick.stopTime();
+        tick = new TimerTick(0, this);
+        tick.start();
+        execute("listen");
+    }
+
+    public void resume() {
+        isResume = true;
+        tick.stopTime();
+        int time = tick.getTime();
+        tick = new TimerTick(time, this);
+        tick.start();
+        execute(lastCommand);
+    }
+
+    public String getCommand() {
+        return command;
+    }
+
+    public void setCommand(String command) {
+        this.command = command;
+        commandChange = true;
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MultiPageGraphicalEditorWithPalette.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MultiPageGraphicalEditorWithPalette.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MultiPageGraphicalEditorWithPalette.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MultiPageGraphicalEditorWithPalette.java	2007-03-01 15:26:27.000000000 -0500
@@ -0,0 +1,454 @@
+/*
+ * Created on Sep 29, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import java.util.ArrayList;
+import java.util.EventObject;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.core.runtime.IProgressMonitor;
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.gef.ContextMenuProvider;
+import org.eclipse.gef.DefaultEditDomain;
+import org.eclipse.gef.EditPart;
+import org.eclipse.gef.GraphicalEditPart;
+import org.eclipse.gef.GraphicalViewer;
+import org.eclipse.gef.commands.CommandStack;
+import org.eclipse.gef.commands.CommandStackListener;
+import org.eclipse.gef.palette.PaletteRoot;
+import org.eclipse.gef.ui.actions.ActionBarContributor;
+import org.eclipse.gef.ui.actions.ActionRegistry;
+import org.eclipse.gef.ui.actions.DeleteAction;
+import org.eclipse.gef.ui.actions.PrintAction;
+import org.eclipse.gef.ui.actions.RedoAction;
+import org.eclipse.gef.ui.actions.SaveAction;
+import org.eclipse.gef.ui.actions.SelectAllAction;
+import org.eclipse.gef.ui.actions.UndoAction;
+import org.eclipse.gef.ui.actions.UpdateAction;
+import org.eclipse.gef.ui.palette.PaletteViewer;
+import org.eclipse.gef.ui.parts.ScrollingGraphicalViewer;
+import org.eclipse.gef.ui.parts.SelectionSynchronizer;
+import org.eclipse.jface.action.IAction;
+import org.eclipse.jface.viewers.ISelection;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.ui.IEditorInput;
+import org.eclipse.ui.IEditorSite;
+import org.eclipse.ui.ISelectionListener;
+import org.eclipse.ui.ISelectionService;
+import org.eclipse.ui.IWorkbenchPart;
+import org.eclipse.ui.PartInitException;
+import org.eclipse.ui.part.MultiPageEditorPart;
+import org.eclipse.ui.views.properties.PropertySheetPage;
+
+/**
+ * @author asangpet
+ *
+ */
+public abstract class MultiPageGraphicalEditorWithPalette extends MultiPageEditorPart
+	implements CommandStackListener, ISelectionListener
+{
+	private DefaultEditDomain editDomain;
+	private GraphicalViewer graphicalViewer;
+	private ActionRegistry actionRegistry;
+	private SelectionSynchronizer synchronizer;
+	private List selectionActions = new ArrayList();
+	private List stackActions = new ArrayList();
+	private List propertyActions = new ArrayList();
+
+	/**
+	 * Constructs the editor part
+	 */
+	public MultiPageGraphicalEditorWithPalette() { }
+
+	/**
+	 * When the command stack changes, the actions interested in the command stack are
+	 * updated.
+	 * @param event the change event
+	 */
+	public void commandStackChanged(EventObject event) {
+		updateActions(stackActions);
+	}
+
+	/**
+	 * Called to configure the graphical viewer before it receives its contents.  This is
+	 * where the root editpart should be configured. Subclasses should extend or override this
+	 * method as needed.
+	 */
+	protected void configureGraphicalViewer() {
+		getGraphicalViewer().getControl().setBackground(ColorConstants.listBackground);
+	}
+
+	/**
+	 * Creates actions for this editor.  Subclasses should override this method to create
+	 * and register actions with the {@link ActionRegistry}.
+	 */
+	protected void createActions() {
+		ActionRegistry registry = getActionRegistry();
+		IAction action;
+		
+		action = new UndoAction(this);
+		registry.registerAction(action);
+		getStackActions().add(action.getId());
+		
+		action = new RedoAction(this);
+		registry.registerAction(action);
+		getStackActions().add(action.getId());
+		
+		action = new SelectAllAction(this);
+		registry.registerAction(action);
+		
+		action = new DeleteAction((IWorkbenchPart)this);
+		registry.registerAction(action);
+		getSelectionActions().add(action.getId());
+		
+		action = new SaveAction(this);
+		registry.registerAction(action);
+		getPropertyActions().add(action.getId());
+		
+		action = new PrintAction(this);
+		registry.registerAction(action);
+	}
+
+	/**
+	 * Creates the GraphicalViewer on the specified <code>Composite</code>.
+	 * @param parent the parent composite
+	 */
+	protected void createGraphicalViewer(Composite parent) {
+		GraphicalViewer viewer = new ScrollingGraphicalViewer();
+		viewer.createControl(parent);
+		setGraphicalViewer(viewer);
+		configureGraphicalViewer();
+		hookGraphicalViewer();
+		initializeGraphicalViewer();
+	}
+
+	/**
+	 * @see org.eclipse.ui.IWorkbenchPart#dispose()
+	 */
+	public void dispose() {
+		getCommandStack().removeCommandStackListener(this);
+		getSite().getWorkbenchWindow().getSelectionService().removeSelectionListener(this);
+		getEditDomain().setActiveTool(null);
+		getActionRegistry().dispose();
+		super.dispose();
+	}
+
+	/**
+	 * @see org.eclipse.ui.part.WorkbenchPart#firePropertyChange(int)
+	 */
+	protected void firePropertyChange(int property) {
+		super.firePropertyChange(property);
+		updateActions(propertyActions);
+	}
+
+	/**
+	 * Lazily creates and returns the action registry.
+	 * @return the action registry
+	 */
+	protected ActionRegistry getActionRegistry() {
+		if (actionRegistry == null)
+			actionRegistry = new ActionRegistry();
+		return actionRegistry;
+	}
+
+	/** 
+	 * Returns the adapter for the specified key.
+	 * 
+	 * <P><EM>IMPORTANT</EM> certain requests, such as the property sheet, may be made before
+	 * or after {@link #createPartControl(Composite)} is called. The order is unspecified by
+	 * the Workbench.
+	 * @see org.eclipse.core.runtime.IAdaptable#getAdapter(java.lang.Class)
+	 */
+	public Object getAdapter(Class type) {
+		if (type == org.eclipse.ui.views.properties.IPropertySheetPage.class) {
+			PropertySheetPage page = new PropertySheetPage();
+			page.setRootEntry(new org.eclipse.gef.ui.properties.UndoablePropertySheetEntry(getCommandStack()));
+			return page;
+		}
+		if (type == GraphicalViewer.class)
+			return getGraphicalViewer();
+		if (type == CommandStack.class)
+			return getCommandStack();
+		if (type == ActionRegistry.class)
+			return getActionRegistry();
+		if (type == EditPart.class && getGraphicalViewer() != null)
+			return getGraphicalViewer().getRootEditPart();
+		if (type == IFigure.class && getGraphicalViewer() != null)
+			return ((GraphicalEditPart)getGraphicalViewer().getRootEditPart()).getFigure();
+		return super.getAdapter(type);
+	}
+
+	/**
+	 * Returns the command stack.
+	 * @return the command stack
+	 */
+	protected CommandStack getCommandStack() {
+		return getEditDomain().getCommandStack();
+	}
+
+	/**
+	 * Returns the edit domain.
+	 * @return the edit domain
+	 */
+	protected DefaultEditDomain getEditDomain() {
+		return editDomain;
+	}
+
+	/**
+	 * Returns the graphical viewer.
+	 * @return the graphical viewer
+	 */
+	protected GraphicalViewer getGraphicalViewer() {
+		return graphicalViewer;
+	}
+
+	/**
+	 * Returns the list of {@link IAction IActions} dependant on property changes in the
+	 * Editor.  These actions should implement the {@link UpdateAction} interface so that they
+	 * can be updated in response to property changes.  An example is the "Save" action.
+	 * @return the list of property-dependant actions
+	 */
+	protected List getPropertyActions() {
+		return propertyActions;
+	}
+
+	/**
+	 * Returns the list of {@link IAction IActions} dependant on changes in the workbench's
+	 * {@link ISelectionService}. These actions should implement the {@link UpdateAction}
+	 * interface so that they can be updated in response to selection changes.  An example is
+	 * the Delete action.
+	 * @return the list of selection-dependant actions
+	 */
+	protected List getSelectionActions() {
+		return selectionActions;
+	}
+
+	/**
+	 * Returns the selection syncronizer object. The synchronizer can be used to sync the
+	 * selection of 2 or more EditPartViewers.
+	 * @return the syncrhonizer
+	 */
+	protected SelectionSynchronizer getSelectionSynchronizer() {
+		if (synchronizer == null)
+			synchronizer = new SelectionSynchronizer();
+		return synchronizer;
+	}
+
+	/**
+	 * Returns the list of {@link IAction IActions} dependant on the CommmandStack's state. 
+	 * These actions should implement the {@link UpdateAction} interface so that they can be
+	 * updated in response to command stack changes.  An example is the "undo" action.
+	 * @return the list of stack-dependant actions
+	 */
+	protected List getStackActions() {
+		return stackActions;
+	}
+
+	/**
+	 * Hooks the GraphicalViewer to the rest of the Editor.  By default, the viewer
+	 * is added to the SelectionSynchronizer, which can be used to keep 2 or more
+	 * EditPartViewers in sync.  The viewer is also registered as the ISelectionProvider
+	 * for the Editor's PartSite.
+	 */
+	protected void hookGraphicalViewer() {
+		getSelectionSynchronizer().addViewer(getGraphicalViewer());
+		getSite().setSelectionProvider(getGraphicalViewer());
+	}
+
+	/**
+	 * Sets the site and input for this editor then creates and initializes the actions.
+	 * Subclasses may extend this method, but should always call <code>super.init(site, input)
+	 * </code>.
+	 * @see org.eclipse.ui.IEditorPart#init(IEditorSite, IEditorInput)
+	 */
+	public void init(IEditorSite site, IEditorInput input) throws PartInitException {		
+		setSite(site);
+		setInput(input);
+		getCommandStack().addCommandStackListener(this);
+		getSite().getWorkbenchWindow().getSelectionService().addSelectionListener(this);
+		initializeActionRegistry();
+	}
+
+	/**
+	 * Initializes the ActionRegistry.  This registry may be used by {@link
+	 * ActionBarContributor ActionBarContributors} and/or {@link ContextMenuProvider
+	 * ContextMenuProviders}.
+	 * <P>This method may be called on Editor creation, or lazily the first time {@link
+	 * #getActionRegistry()} is called.
+	 */
+	protected void initializeActionRegistry() {
+		createActions();
+		updateActions(propertyActions);
+		updateActions(stackActions);
+	} 
+
+	/**
+	 * @see org.eclipse.ui.ISelectionListener#selectionChanged(IWorkbenchPart, ISelection)
+	 */
+	public void selectionChanged(IWorkbenchPart part, ISelection selection) {
+		// If not the active editor, ignore selection changed.
+		if (this.equals(getSite().getPage().getActiveEditor()))
+			updateActions(selectionActions);
+	}
+
+	/**
+	 * Sets the ActionRegistry for this EditorPart.
+	 * @param registry the registry
+	 */
+	protected void setActionRegistry(ActionRegistry registry) {
+		actionRegistry = registry;
+	} 
+
+	/**
+	 * @see org.eclipse.ui.IWorkbenchPart#setFocus()
+	 */
+	public void setFocus() {
+		getGraphicalViewer().getControl().setFocus();
+	}
+
+	/**
+	 * Sets the graphicalViewer for this EditorPart.
+	 * @param viewer the graphical viewer
+	 */
+	protected void setGraphicalViewer(GraphicalViewer viewer) {
+		getEditDomain().addViewer(viewer);
+		this.graphicalViewer = viewer;
+	}
+
+	/**
+	 * A convenience method for updating a set of actions defined by the given List of action
+	 * IDs. The actions are found by looking up the ID in the {@link #getActionRegistry()
+	 * action registry}. If the corresponding action is an {@link UpdateAction}, it will have
+	 * its <code>update()</code> method called.
+	 * @param actionIds the list of IDs to update
+	 */
+	protected void updateActions(List actionIds) {
+		ActionRegistry registry = getActionRegistry();
+		Iterator iter = actionIds.iterator();
+		while (iter.hasNext()) {
+			IAction action = registry.getAction(iter.next());
+			if (action instanceof UpdateAction)
+				((UpdateAction)action).update();
+		}
+	}
+
+	private static final int PALETTE_SIZE = 125;
+
+	private PaletteViewer paletteViewer;
+
+	/**
+	 * Called to configure the viewer before it receives its contents.
+	 */
+	protected void configurePaletteViewer() { }
+
+	/**
+	 * Creates the palette on the given composite.
+	 * @param parent the composite
+	 */
+	protected void createPaletteViewer(Composite parent) {
+		PaletteViewer viewer = new PaletteViewer();
+		setPaletteViewer(viewer);
+		viewer.createControl(parent);
+		configurePaletteViewer();
+		hookPaletteViewer();
+		initializePaletteViewer();
+	}
+
+	/**
+	 * Returns the PaletteRoot for the palette viewer.
+	 * @return the palette root
+	 */
+	protected abstract PaletteRoot getPaletteRoot();
+
+	/**
+	 * Returns the initial palette size in pixels. Subclasses may override this method to
+	 * return a persisted value.
+	 * @see #handlePaletteResized(int)
+	 * @return the initial size of the palette in pixels.
+	 */
+	protected int getInitialPaletteSize() {
+		return PALETTE_SIZE;
+	}
+
+	/**
+	 * Returns the PaletteViewer.
+	 * @return the palette viewer
+	 */
+	protected PaletteViewer getPaletteViewer() {
+		return paletteViewer;
+	}
+
+	/**
+	 * Called whenever the user resizes the palette.
+	 * @param newSize the new size in pixels
+	 */
+	protected void handlePaletteResized(int newSize) {
+	}
+
+	/**
+	 * Called when the palette viewer is set. By default, the EditDomain is given the palette
+	 * viewer.
+	 */
+	protected void hookPaletteViewer() {
+		getEditDomain().setPaletteViewer(paletteViewer);
+	}
+
+	/**
+	 * Called to populate the palette viewer.
+	 */
+	protected void initializePaletteViewer() {
+	}
+
+	/**
+	 * Sets the palette viewer
+	 * @param paletteViewer the palette viewer
+	 */
+	protected void setPaletteViewer(PaletteViewer paletteViewer) {
+		this.paletteViewer = paletteViewer;
+	}
+
+	/**
+	 * Sets the {@link #getPaletteRoot() palette root} of the edit domain
+	 * @see org.eclipse.gef.ui.parts.GraphicalEditor#setEditDomain(org.eclipse.gef.DefaultEditDomain)
+	 */
+	protected void setEditDomain(DefaultEditDomain ed) {
+		this.editDomain = ed;
+		getEditDomain().setPaletteRoot(getPaletteRoot());
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.gef.ui.parts.GraphicalEditor#initializeGraphicalViewer()
+	 */
+	protected void initializeGraphicalViewer() {
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.ui.ISaveablePart#doSave(org.eclipse.core.runtime.IProgressMonitor)
+	 */
+	public void doSave(IProgressMonitor monitor) {
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.ui.ISaveablePart#doSaveAs()
+	 */
+	public void doSaveAs() {
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.ui.ISaveablePart#isDirty()
+	 */
+	public boolean isDirty() {
+		return false;
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.ui.ISaveablePart#isSaveAsAllowed()
+	 */
+	public boolean isSaveAsAllowed() {
+		return false;
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyContributor.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyContributor.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyContributor.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyContributor.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,36 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import org.eclipse.gef.ui.actions.ActionBarContributor;
+import org.eclipse.gef.ui.actions.DeleteRetargetAction;
+import org.eclipse.gef.ui.actions.RedoRetargetAction;
+import org.eclipse.gef.ui.actions.UndoRetargetAction;
+import org.eclipse.jface.action.IToolBarManager;
+import org.eclipse.ui.actions.ActionFactory;
+
+/**
+ * @author asangpet
+ */
+public class MyContributor extends ActionBarContributor {
+
+	public MyContributor() {
+	}
+	
+	protected void buildActions() {
+		addRetargetAction(new UndoRetargetAction());
+		addRetargetAction(new RedoRetargetAction());
+		addRetargetAction(new DeleteRetargetAction());
+	}
+	
+	protected void declareGlobalActionKeys() {
+	}
+	
+	public void contributeToToolBar(IToolBarManager toolBarManager) {		
+		toolBarManager.add(getActionRegistry().getAction(ActionFactory.DELETE.getId()));	
+		toolBarManager.add(getActionRegistry().getAction(ActionFactory.UNDO.getId()));
+		toolBarManager.add(getActionRegistry().getAction(ActionFactory.REDO.getId()));
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyPolylineConnection.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyPolylineConnection.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyPolylineConnection.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/MyPolylineConnection.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,15 @@
+/*
+ * Created on Dec 22, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import org.eclipse.draw2d.PolylineConnection;
+
+/**
+ * @author asangpet
+ *
+ */
+public class MyPolylineConnection extends PolylineConnection implements
+		TransitionConnection {
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/NewViewWizard.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/NewViewWizard.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/NewViewWizard.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/NewViewWizard.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,85 @@
+/*
+ * Created on Jan 27, 2005
+ */
+package org.tekkotsu.ui.editor;
+
+import org.eclipse.jface.viewers.IStructuredSelection;
+import org.eclipse.jface.wizard.Wizard;
+import org.eclipse.jface.wizard.WizardPage;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.layout.GridData;
+import org.eclipse.swt.layout.GridLayout;
+import org.eclipse.swt.widgets.Button;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.ui.IWorkbench;
+import org.tekkotsu.ui.editor.resources.Debugger;
+
+/**
+ * @author asangpet
+ */
+public class NewViewWizard extends Wizard {
+	
+	IWorkbench workbench;
+	IStructuredSelection selection;
+	
+	public void init(IWorkbench workbench, IStructuredSelection selection) {
+		this.workbench = workbench;
+		this.selection = selection;
+		this.setWindowTitle("New view");
+	}
+	
+	public void addPages() {
+		ModelSelectPage modelSelectPage = new ModelSelectPage();
+		addPage(modelSelectPage);		
+	}
+	
+	/* (non-Javadoc)
+	 * @see org.eclipse.jface.wizard.IWizard#performFinish()
+	 */
+	public boolean performFinish() {
+		Debugger.printDebug(Debugger.DEBUG_ALL,"done");
+		return true;
+	}
+	
+	public String getViewPath() {
+		return "noname.tsl";
+	}
+
+}
+
+class ModelSelectPage extends WizardPage {
+
+	public ModelSelectPage() {
+		super("modelselect","Create a new view",null);
+		this.setDescription("Select your model source");
+	}
+	
+	/* (non-Javadoc)
+	 * @see org.eclipse.jface.dialogs.IDialogPage#createControl(org.eclipse.swt.widgets.Composite)
+	 */
+	public void createControl(Composite parent) {
+		GridData gd;
+		Composite composite = new Composite(parent, SWT.NONE);
+		
+		GridLayout gl = new GridLayout();
+		int ncol = 4;
+		gl.numColumns = ncol;
+		composite.setLayout(gl);
+		
+		Button robotButton = new Button(composite, SWT.RADIO);
+		robotButton.setText("Retrieve a new model from AIBO");
+		gd = new GridData(GridData.FILL_HORIZONTAL);
+		gd.horizontalSpan = ncol;
+		robotButton.setLayoutData(gd);
+		robotButton.setSelection(true);
+
+		Button fileButton = new Button(composite, SWT.RADIO);
+		fileButton.setText("Use an existing model from file");
+		gd = new GridData(GridData.FILL_HORIZONTAL);
+		gd.horizontalSpan = ncol;
+		fileButton.setLayoutData(gd);
+		fileButton.setSelection(false);
+
+		setControl(composite);
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/Splitter.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/Splitter.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/Splitter.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/Splitter.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,388 @@
+/*******************************************************************************
+ * Copyright (c) 2000, 2004 IBM Corporation and others.
+ * All rights reserved. This program and the accompanying materials 
+ * are made available under the terms of the Common Public License v1.0
+ * which accompanies this distribution, and is available at
+ * http://www.eclipse.org/legal/cpl-v10.html
+ * 
+ * Contributors:
+ *     IBM Corporation - initial API and implementation
+ *******************************************************************************/
+package org.tekkotsu.ui.editor;
+
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeSupport;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.graphics.GC;
+import org.eclipse.swt.graphics.Point;
+import org.eclipse.swt.graphics.Rectangle;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.Control;
+import org.eclipse.swt.widgets.Event;
+import org.eclipse.swt.widgets.Layout;
+import org.eclipse.swt.widgets.Listener;
+import org.eclipse.swt.widgets.Sash;
+
+class Splitter extends Composite {
+
+public static final int DEFAULT_SASH_WIDTH = 5;
+private static final int DRAG_MINIMUM = 62;
+private static final String MAINTAIN_SIZE = "maintain size";  //$NON-NLS-1$
+
+private int fixedSize = 150;
+private int orientation = SWT.VERTICAL;
+private Sash[] sashes = new Sash[0];
+private Control[] controls = new Control[0];
+private Control maxControl = null;
+private Listener sashListener;
+private int sashWidth = DEFAULT_SASH_WIDTH;
+
+/**
+ * PropertyChangeSupport
+ */
+protected PropertyChangeSupport listeners = new PropertyChangeSupport(this);
+
+public void addFixedSizeChangeListener(PropertyChangeListener listener) {
+	listeners.addPropertyChangeListener(listener);
+}
+
+protected void firePropertyChange(int oldValue, int newValue) {
+	listeners.firePropertyChange(MAINTAIN_SIZE, oldValue, newValue);
+}
+
+public void removeFixedSizeChangeListener(PropertyChangeListener listener) {
+	listeners.removePropertyChangeListener(listener);
+}
+
+public int getFixedSize() {
+	return fixedSize;
+}
+
+public void setFixedSize(int newSize) {
+	if (newSize == fixedSize) {
+		return;
+	}
+	
+	firePropertyChange(fixedSize, fixedSize = newSize);
+}
+
+class SashPainter implements Listener {
+	public void handleEvent(Event e) {
+		paint ((Sash)e.widget, e.gc);
+	}
+}
+
+public Splitter(Composite parent, int style) {
+	super(parent, checkStyle(style));
+	
+	if ((style & SWT.HORIZONTAL) != 0)
+		orientation = SWT.HORIZONTAL;
+	
+	this.addListener(SWT.Resize, new Listener() {
+		public void handleEvent(Event e) {
+			layout(true);
+		}
+	});
+	
+	sashListener = new Listener() {
+		public void handleEvent(Event e) {
+			onDragSash(e);
+		}
+	};
+}
+
+private static int checkStyle (int style) {
+	int mask = SWT.BORDER;
+	return style & mask;
+}
+
+public Point computeSize (int wHint, int hHint, boolean changed) {
+	
+	Control[] controls = getControls(true);
+	if (controls.length == 0) return new Point(wHint, hHint);
+	
+	int width = 0;
+	int height = 0;
+	boolean vertical = (getStyle() & SWT.VERTICAL) != 0;
+	if (vertical) {
+		width = wHint;
+		height += (controls.length - 1) * getSashWidth();
+	} else {
+		height = hHint;
+		width += controls.length * getSashWidth();
+	}
+	for (int i = 0; i < controls.length; i++) {
+		if (vertical) {
+			Point size = controls[i].computeSize(wHint, SWT.DEFAULT);
+			height += size.y;	
+		} else {
+			Point size = controls[i].computeSize(SWT.DEFAULT, hHint);
+			if (controls[i].getData(MAINTAIN_SIZE) != null) {
+				size.x = fixedSize;
+			}
+			width += size.x;
+		}
+	}
+//	if (wHint != SWT.DEFAULT) width = wHint;
+//	if (hHint != SWT.DEFAULT) height = hHint;
+	
+	return new Point(width, height);
+}
+
+/**
+ * Answer SWT.HORIZONTAL if the controls in the SashForm are laid out side by side.
+ * Answer SWT.VERTICAL   if the controls in the SashForm are laid out top to bottom.
+ */
+public int getOrientation() {
+	return orientation;
+}
+
+public int getSashWidth() {
+	return sashWidth;
+}
+
+/**
+ * Answer the control that currently is maximized in the SashForm.  This value may be null.
+ */
+public Control getMaximizedControl() {
+	return this.maxControl;
+}
+
+private Control[] getControls(boolean onlyVisible) {
+	Control[] children = getChildren();
+	Control[] controls = new Control[0];
+	for (int i = 0; i < children.length; i++) {
+		if (children[i] instanceof Sash)
+			continue;
+		if (onlyVisible && !children[i].getVisible()) continue;
+
+		Control[] newControls = new Control[controls.length + 1];
+		System.arraycopy(controls, 0, newControls, 0, controls.length);
+		newControls[controls.length] = children[i];
+		controls = newControls;
+	}
+	return controls;
+}
+
+public void layout(boolean changed) {
+	Rectangle area = getClientArea();
+	if (area.width == 0 || area.height == 0) return;
+	
+	Control[] newControls = getControls(true);
+	if (controls.length == 0 && newControls.length == 0) return;
+	controls = newControls;
+	
+	if (maxControl != null && !maxControl.isDisposed()) {
+		for (int i = 0; i < controls.length; i++) {
+			if (controls[i] != maxControl) {
+				controls[i].setBounds(-200, -200, 0, 0);
+			} else {
+				controls[i].setBounds(area);
+			}
+		}
+		return;
+	}
+	
+	// keep just the right number of sashes
+	if (sashes.length < controls.length - 1) {
+		Sash[] newSashes = new Sash[controls.length - 1];
+		System.arraycopy(sashes, 0, newSashes, 0, sashes.length);
+		int sashOrientation =
+			(orientation == SWT.HORIZONTAL) ? SWT.VERTICAL : SWT.HORIZONTAL;
+		for (int i = sashes.length; i < newSashes.length; i++) {
+			newSashes[i] = new Sash(this, sashOrientation);
+			newSashes[i].setBackground(ColorConstants.button);
+			newSashes[i].addListener(SWT.Paint, new SashPainter());
+			newSashes[i].addListener(SWT.Selection, sashListener);
+		}
+		sashes = newSashes;
+	}
+	if (sashes.length > controls.length - 1) {
+		if (controls.length == 0) {
+			for (int i = 0; i < sashes.length; i++) {
+				sashes[i].dispose();
+			}
+			sashes = new Sash[0];
+		} else {
+			Sash[] newSashes = new Sash[controls.length - 1];
+			System.arraycopy(sashes, 0, newSashes, 0, newSashes.length);
+			for (int i = controls.length - 1; i < sashes.length; i++) {
+				sashes[i].dispose();
+			}
+			sashes = newSashes;
+		}
+	}
+	
+	if (controls.length == 0) return;
+	
+	//@TODO
+	// This only works if the orientation is horizontal, there are two children and one 
+	// of them has been set to maintain its size.
+	int x = area.x;
+	int width;
+	for (int i = 0; i < controls.length; i++) {
+		Control control = controls[i];
+		if (control.getData(MAINTAIN_SIZE) != null) {
+			width = fixedSize;
+			if (width > area.width) {
+				width = area.width - getSashWidth();
+			}
+			control.setBounds(x, area.y, width, area.height);
+			x += width + getSashWidth();
+		} else {
+			width = Math.max(area.width - fixedSize - getSashWidth(), 0);
+			control.setBounds(x, area.y, width, area.height);
+			x += (width + getSashWidth());
+		}
+	}
+	if (sashes.length > 0)
+		sashes[0].setBounds(controls[0].getBounds().x + controls[0].getBounds().width, area.y, 
+				getSashWidth(), area.height);
+}
+
+public void maintainSize(Control c) {
+	Control[] controls = getControls(false);
+	for (int i = 0; i < controls.length; i++) {
+		Control ctrl = controls[i];
+		if (ctrl == c) {
+			ctrl.setData(MAINTAIN_SIZE, new Boolean(true));
+			break;
+		}
+	}
+}
+
+
+void paint(Sash sash, GC gc) {
+	if (getSashWidth() == 0)
+		return;
+	Point size = sash.getSize();
+	if (getOrientation() == SWT.HORIZONTAL) {
+		gc.setForeground(ColorConstants.buttonDarker);
+		gc.drawLine(getSashWidth() - 1, 0, getSashWidth() - 1, size.y);
+		gc.setForeground(ColorConstants.buttonLightest);
+		gc.drawLine(0, 0, 0, size.y);
+	} else {
+		gc.setForeground(ColorConstants.buttonDarker);
+		gc.drawLine(0, 0, size.x, 0);
+		gc.drawLine(0, getSashWidth() - 1, size.x, getSashWidth() - 1);
+		gc.setForeground(ColorConstants.buttonLightest);
+		gc.drawLine(0, 1, size.x, 1);
+	}
+}
+
+private void onDragSash(Event event) {
+	if (event.detail == SWT.DRAG) {
+		// constrain feedback
+		Rectangle area = getClientArea();
+		if (orientation == SWT.HORIZONTAL) {
+			if (controls[0].getData(MAINTAIN_SIZE) != null) {
+				event.x = Math.max(event.x, DRAG_MINIMUM);
+			} else {
+				event.x = Math.min(event.x, area.width - DRAG_MINIMUM - getSashWidth());
+			}
+		} else {
+			event.y = Math.min(event.y, area.height - DRAG_MINIMUM - getSashWidth());
+		}
+		return;
+	}
+
+	Sash sash = (Sash)event.widget;
+	int sashIndex = -1;
+	for (int i = 0; i < sashes.length; i++) {
+		if (sashes[i] == sash) {
+			sashIndex = i;
+			break;
+		}
+	}
+	if (sashIndex == -1) return;
+
+	Control c1 = controls[sashIndex];
+	Control c2 = controls[sashIndex + 1];
+	Rectangle b1 = c1.getBounds();
+	Rectangle b2 = c2.getBounds();
+	controls = getControls(false);
+	
+	Rectangle sashBounds = sash.getBounds();
+	if (orientation == SWT.HORIZONTAL) {
+		int shift = event.x - sashBounds.x;
+		b1.width += shift;
+		b2.x += shift;
+		b2.width -= shift;
+	} else {
+		int shift = event.y - sashBounds.y;
+		b1.height += shift;
+		b2.y += shift;
+		b2.height -= shift;
+	}
+	
+	c1.setBounds(b1);
+	sash.setBounds(event.x, event.y, event.width, event.height);
+	c2.setBounds(b2);
+	//@TODO
+	// This will only work when you have two controls, one of whom is set to maintain size
+	if (c1.getData(MAINTAIN_SIZE) != null) {
+		setFixedSize(c1.getBounds().width);
+	} else {
+		setFixedSize(c2.getBounds().width);
+	}
+}
+
+/**
+ * If orientation is SWT.HORIZONTAL, lay the controls in the SashForm out side by side.
+ * If orientation is SWT.VERTICAL,   lay the controls in the SashForm out top to bottom.
+ */
+public void setOrientation(int orientation) {
+	if (this.orientation == orientation) return;
+	if (orientation != SWT.HORIZONTAL && orientation != SWT.VERTICAL) {
+		SWT.error(SWT.ERROR_INVALID_ARGUMENT);
+	}
+	this.orientation = orientation;
+	
+	int sashOrientation = (orientation == SWT.HORIZONTAL) ? SWT.VERTICAL : SWT.HORIZONTAL;
+	for (int i = 0; i < sashes.length; i++) {
+		sashes[i].dispose();
+		sashes[i] = new Sash(this, sashOrientation);
+		sashes[i].setBackground(ColorConstants.buttonLightest);
+		sashes[i].addListener(SWT.Selection, sashListener);
+	}
+	layout();
+}
+
+public void setSashWidth(int width) {
+	sashWidth = width;
+}
+
+public void setLayout (Layout layout) {
+	// SashForm does not use Layout
+}
+
+/**
+ * Specify the control that should take up the entire client area of the SashForm.  
+ * If one control has been maximized, and this method is called with a different control, 
+ * the previous control will be minimized and the new control will be maximized..
+ * if the value of control is null, the SashForm will minimize all controls and return to
+ * the default layout where all controls are laid out separated by sashes.
+ */
+public void setMaximizedControl(Control control) {
+	if (control == null) {
+		if (maxControl != null) {
+			this.maxControl = null;
+			layout();
+			for (int i = 0; i < sashes.length; i++) {
+				sashes[i].setVisible(true);
+			}
+		}
+		return;
+	}
+	
+	for (int i = 0; i < sashes.length; i++) {
+		sashes[i].setVisible(false);
+	}
+	maxControl = control;
+	layout();
+
+}
+
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditor.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditor.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditor.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditor.java	2006-02-14 00:22:32.000000000 -0500
@@ -0,0 +1,1039 @@
+package org.tekkotsu.ui.editor;
+
+/**
+ * @author asangpet
+ */
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.io.BufferedOutputStream;
+import java.io.File;
+import java.io.FileOutputStream;
+import java.io.StringReader;
+import java.io.StringWriter;
+import java.util.ArrayList;
+import java.util.HashMap;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.core.runtime.IProgressMonitor;
+import org.eclipse.core.runtime.Path;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.ContextMenuProvider;
+import org.eclipse.gef.DefaultEditDomain;
+import org.eclipse.gef.EditDomain;
+import org.eclipse.gef.EditPart;
+import org.eclipse.gef.EditPolicy;
+import org.eclipse.gef.GraphicalViewer;
+import org.eclipse.gef.commands.CommandStack;
+import org.eclipse.gef.palette.CreationToolEntry;
+import org.eclipse.gef.palette.MarqueeToolEntry;
+import org.eclipse.gef.palette.PaletteDrawer;
+import org.eclipse.gef.palette.PaletteGroup;
+import org.eclipse.gef.palette.PaletteRoot;
+import org.eclipse.gef.palette.SelectionToolEntry;
+import org.eclipse.gef.palette.ToolEntry;
+import org.eclipse.gef.requests.CreateRequest;
+import org.eclipse.gef.requests.SimpleFactory;
+import org.eclipse.gef.ui.actions.ActionRegistry;
+import org.eclipse.gef.ui.parts.ScrollingGraphicalViewer;
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.jface.resource.ImageDescriptor;
+import org.eclipse.jface.viewers.ISelection;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.custom.SashForm;
+import org.eclipse.swt.events.FocusAdapter;
+import org.eclipse.swt.events.FocusEvent;
+import org.eclipse.swt.events.SelectionAdapter;
+import org.eclipse.swt.events.SelectionEvent;
+import org.eclipse.swt.layout.FillLayout;
+import org.eclipse.swt.layout.GridData;
+import org.eclipse.swt.layout.GridLayout;
+import org.eclipse.swt.widgets.Button;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.FileDialog;
+import org.eclipse.swt.widgets.Label;
+import org.eclipse.swt.widgets.Shell;
+import org.eclipse.swt.widgets.Text;
+import org.eclipse.ui.IEditorDescriptor;
+import org.eclipse.ui.IEditorInput;
+import org.eclipse.ui.IEditorRegistry;
+import org.eclipse.ui.IEditorSite;
+import org.eclipse.ui.IPathEditorInput;
+import org.eclipse.ui.IPersistableElement;
+import org.eclipse.ui.IWorkbench;
+import org.eclipse.ui.IWorkbenchPage;
+import org.eclipse.ui.IWorkbenchPart;
+import org.eclipse.ui.PartInitException;
+import org.eclipse.ui.PlatformUI;
+import org.jdom.Document;
+import org.jdom.Element;
+import org.jdom.input.SAXBuilder;
+import org.jdom.output.Format;
+import org.jdom.output.XMLOutputter;
+import org.tekkotsu.ui.editor.editparts.MyEditPartFactory;
+import org.tekkotsu.ui.editor.editparts.ViewEditPart;
+import org.tekkotsu.ui.editor.editpolicies.MyXYLayoutEditPolicy;
+import org.tekkotsu.ui.editor.icons.IconDummy;
+import org.tekkotsu.ui.editor.model.AbstractModel;
+import org.tekkotsu.ui.editor.model.SourceModel;
+import org.tekkotsu.ui.editor.model.SourceNodeModel;
+import org.tekkotsu.ui.editor.model.SourceTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * @author asangpet
+ */
+public class StateMachineEditor extends MultiPageGraphicalEditorWithPalette
+		implements PropertyChangeListener {
+
+	static final int PAGE_PREVIEW = 0;
+	static final int PAGE_EDITOR = 1;
+	static final int PAGE_SOURCE_MODEL = 2;
+	static final int PAGE_SOURCE_LAYOUT = 3;
+
+	private Text modelText, modelSourceText, modelPreviewText;
+	private Button pauseButton;
+	
+	private Text viewSourceText;
+
+	private ViewModel viewModel;
+
+	private MyXYLayoutEditPolicy editPolicy;
+
+	private ScrollingGraphicalViewer testViewer;
+
+	ModelConnector modelConnector = null;
+
+	private PropertyChangeEvent event;
+	private boolean dirty_flag = false;
+
+	public StateMachineEditor() {
+		setEditDomain(new DefaultEditDomain(this));
+		initModelConnector();
+		editPolicy = new MyXYLayoutEditPolicy();
+	}
+
+	public void setDirty() {
+		dirty_flag = true;
+		firePropertyChange(PROP_DIRTY);
+	}
+	
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals(ModelConnector.EVENT_DATA_UPDATE)) {
+			this.event = evt;
+			modelPreviewText.getDisplay().syncExec(new Runnable() {
+				public void run() {
+					modelPreviewText.append(event.getNewValue()+"\r\n");
+				}
+			});
+			modelSourceText.getDisplay().syncExec(new Runnable() {
+				public void run() {
+					modelSourceText.append(event.getNewValue() + "\r\n");
+				}
+			});
+		} else if (evt.getPropertyName().equals(
+				ModelConnector.EVENT_MODEL_UPDATE)) {
+			String buf = (String) evt.getNewValue();
+			Debugger.printDebug(Debugger.DEBUG_ALL,buf);
+			viewModel.getSourceModel().setSourceInput(new StringReader(buf));
+			modelPreviewText.getDisplay().syncExec(new Runnable() {
+				public void run() {
+					viewModelSource();
+					createModelActions(viewModel);
+					viewModel.verifySource();
+					if (viewModel.getPartChildren().size()==0) {						
+						if (MessageDialog.openQuestion(testViewer.getControl().getShell(),"New Layout","Would you like the state machine layout to be automatically generated?")) {
+							CreateLayoutAction action = new CreateLayoutAction(viewModel.getSourceModel());
+							action.run();							
+						}
+					}
+				}
+			});
+		} else {
+			// forward change to ViewModel
+			final PropertyChangeEvent ev = evt;
+			testViewer.getControl().getDisplay().syncExec(new Runnable() {
+				public void run() {
+					viewModel.propertyChange(ev);
+				}
+			});
+		}
+	}
+
+	protected void configureGraphicalViewer() {
+		super.configureGraphicalViewer();
+		GraphicalViewer viewer = getGraphicalViewer();
+		viewer.setEditPartFactory(new MyEditPartFactory());
+
+		// configure the context menu provider
+		ContextMenuProvider cmProvider = new StateMachineEditorContextMenuProvider(
+				viewer, getActionRegistry());
+		viewer.setContextMenu(cmProvider);
+		getSite().registerContextMenu(cmProvider, viewer);
+	}
+
+	public class CreateNodeAction extends Action {
+		private SourceNodeModel model;
+
+		private CreateRequest request;
+
+		public CreateNodeAction(SourceNodeModel model) {
+			super(model.getId(), Action.AS_CHECK_BOX);
+			this.model = model;
+			request = new CreateRequest();
+		}
+
+		public SourceNodeModel getModel() {
+			return model;
+		}
+
+		public CreateRequest getRequest() {
+			return request;
+		}
+
+		public void run() {
+			EditDomain domain = getEditDomain();
+			CommandStack stack = domain.getCommandStack();
+			GraphicalViewer view = getGraphicalViewer();
+			request.setFactory(model.getFactory());
+			stack.execute(view.getContents().getEditPolicy(
+					EditPolicy.LAYOUT_ROLE).getCommand(request));
+			setDirty();
+		}
+	}
+
+	public class CreateTransitionAction extends Action {
+		private SourceTransitionModel model;
+
+		private CreateRequest request;
+
+		public CreateTransitionAction(SourceTransitionModel model) {
+			super(model.getId(), Action.AS_CHECK_BOX);
+			this.model = model;
+			request = new CreateRequest();
+		}
+
+		public SourceTransitionModel getModel() {
+			return model;
+		}
+
+		public CreateRequest getRequest() {
+			return request;
+		}
+
+		/**
+		 * generate source/target node for single pair transition model
+		 */
+		private void createSourceTarget() {
+			SourceModel src = viewModel.getSourceModel();
+			CreateNodeAction createSrc = new CreateNodeAction(
+					(SourceNodeModel) src.getChild(model.getSourceNodes()
+							.get(0).toString()));
+			CreateNodeAction createDest = new CreateNodeAction(
+					(SourceNodeModel) src.getChild(model.getDestNodes().get(0)
+							.toString()));
+			createSrc.getRequest().setLocation(request.getLocation());
+			createDest.getRequest().setLocation(
+					(new Point(request.getLocation())).translate(40, 40));
+			createSrc.run();
+			createDest.run();
+			HashMap data = new HashMap();
+			data.put("_source", viewModel.getPartChild(model.getSourceNodes()
+					.get(0).toString()));
+			data.put("_target", viewModel.getPartChild(model.getDestNodes()
+					.get(0).toString()));
+			request.setExtendedData(data);
+		}
+
+		public void run() {
+			EditDomain domain = getEditDomain();
+			CommandStack stack = domain.getCommandStack();
+			GraphicalViewer view = getGraphicalViewer();
+			request.setFactory(model.getFactory((ViewModel) view.getContents()
+					.getModel()));
+			Debugger.printDebug(Debugger.DEBUG_ALL,
+					"Create transition action runned: "
+							+ request.getNewObjectType());
+			if (!model.isMultiTransition()) {
+				createSourceTarget();
+			}
+			stack.execute(view.getContents().getEditPolicy(
+					EditPolicy.LAYOUT_ROLE).getCommand(request));
+			setDirty();
+		}
+	}
+
+	/**
+	 * This action automatically generate layout for all node and transition
+	 */
+	public class CreateLayoutAction extends Action {
+		private SourceModel model;
+
+		private CreateRequest request;
+
+		public CreateLayoutAction(SourceModel model) {
+			super("Generate layout");
+			this.model = model;
+			request = new CreateRequest();
+		}
+
+		public SourceModel getModel() {
+			return model;
+		}
+
+		public CreateRequest getRequest() {
+			return request;
+		}
+
+		private void createLayout() {
+			// create nodes
+			List nodeList = model.getNodes();
+			Iterator iter = nodeList.iterator();
+			Point curPoint = request.getLocation();
+			
+			int radius = 1000;
+			int wmin = getContainer().getBounds().width/2;
+			int hmin = getContainer().getBounds().height/2;
+			if (wmin<hmin) radius = wmin-60; else radius = hmin-60;
+			curPoint = new Point(radius+60,getContainer().getBounds().height/2-30);
+
+			int count = 0;
+			while (iter.hasNext()) {
+				SourceNodeModel node = (SourceNodeModel)iter.next();
+				CreateNodeAction genNode = new CreateNodeAction(node);
+				int dx = (int)Math.round(radius*Math.cos(2*Math.PI/(nodeList.size())*count));
+				int dy = (int)Math.round(radius*Math.sin(2*Math.PI/(nodeList.size())*count));
+				genNode.getRequest().setLocation(curPoint.getTranslated(dx,dy));
+				//HashMap extendedData = new HashMap();
+				//extendedData.put(IDTag.XML_common_color, java.awt.Color.getHSBColor((float)(count/nodeList.size()),.99f,.8f));
+				//genNode.getRequest().setExtendedData(extendedData);
+				genNode.run();
+				count++;
+			}
+			
+			//create transitions
+			List transList = model.getTransitions();
+			iter = transList.iterator();
+			while (iter.hasNext()) {
+				SourceTransitionModel trans = (SourceTransitionModel)iter.next();
+				CreateTransitionAction genTrans = new CreateTransitionAction(trans);
+				genTrans.getRequest().setLocation(curPoint);
+				curPoint.translate(40,0);
+				genTrans.run();
+			}			
+		}
+
+		public void run() {
+			EditDomain domain = getEditDomain();
+			CommandStack stack = domain.getCommandStack();
+			GraphicalViewer view = getGraphicalViewer();
+			
+			try {
+			SourceNodeModel nodeModel = (SourceNodeModel)model.getNodes().get(0);
+			request.setFactory(nodeModel.getFactory());
+
+			Debugger.printDebug(Debugger.DEBUG_ALL,
+					"Generate entire layout.");
+			createLayout();
+			setDirty();
+			} catch (Exception e) {
+				MessageDialog msgDialog = new MessageDialog(
+						view.getControl().getShell(),"Error",null,"No model loaded, you must pick an existing model or upload a new one.",SWT.ICON_ERROR,new String[] {"OK"},0);
+				msgDialog.open();
+			}
+		}
+	}
+	
+	private void createModelActions(ViewModel viewModel) {
+		ActionRegistry actionRegistry = this.getActionRegistry();
+		Iterator iter = actionRegistry.getActions();
+		List keyList = new ArrayList();
+		while (iter.hasNext()) {
+			keyList.add(((Action) iter.next()));
+		}
+		iter = keyList.iterator();
+		while (iter.hasNext()) {
+			actionRegistry.removeAction((Action) iter.next());
+		}
+		// actionRegistry.dispose();
+		// actionRegistry = new ActionRegistry();
+
+		super.createActions();
+
+		// generate actions for adding state and transition
+		iter = viewModel.getSourceModel().getNodes().iterator();
+		while (iter.hasNext()) {
+			SourceNodeModel model = (SourceNodeModel) iter.next();
+			Action testAction = new CreateNodeAction(model);
+			testAction.setId(IDTag.ACTION_add_state + model.getId());
+			actionRegistry.registerAction(testAction);
+		}
+		iter = viewModel.getSourceModel().getTransitions().iterator();
+		while (iter.hasNext()) {
+			SourceTransitionModel model = (SourceTransitionModel) iter.next();
+			Action testAction = new CreateTransitionAction(model);
+			testAction.setId(IDTag.ACTION_add_transition + model.getId());
+			actionRegistry.registerAction(testAction);
+		}
+		Action layoutAction = new CreateLayoutAction(viewModel.getSourceModel());
+		layoutAction.setId(IDTag.ACTION_add_all);
+		actionRegistry.registerAction(layoutAction);
+	}
+
+	/**
+	 * @see org.eclipse.ui.IWorkbenchPart#createPartControl(org.eclipse.swt.widgets.Composite)
+	 */
+	public void createLayoutEditorPage() {
+		Composite parent = this.getContainer();
+		/*
+		 * Splitter splitter = new Splitter(parent, SWT.HORIZONTAL);
+		 * createPaletteViewer(splitter); createGraphicalViewer(splitter);
+		 * 
+		 * splitter.maintainSize(getPaletteViewer().getControl());
+		 * splitter.setFixedSize(getInitialPaletteSize());
+		 * splitter.addFixedSizeChangeListener(new PropertyChangeListener() {
+		 * public void propertyChange(PropertyChangeEvent evt) {
+		 * handlePaletteResized(((Splitter)evt.getSource()).getFixedSize()); }
+		 * });
+		 */
+		createGraphicalViewer(parent);
+
+		// int index = addPage(splitter);
+		createModelActions(viewModel);
+
+		//
+		//int index = addPage(getGraphicalViewer().getControl());
+		//setPageText(index, "Layout");
+	}
+
+	protected void createPages() {
+		// initialize editor first
+		createLayoutEditorPage();
+
+		createPreviewPage();
+		
+		// add editor page to tab
+		int index = addPage(getGraphicalViewer().getControl());
+		setPageText(index, "Layout");
+
+		createModelEditorPage();
+		createSourceEditorPage();
+	}
+
+	void initModelConnector() {
+		modelConnector = new ModelConnector();
+		modelConnector.addPropertyChangeListener(this);
+	}
+
+	public void createModelEditorPage() {
+		if (modelConnector == null)
+			initModelConnector();
+		Composite composite = new Composite(getContainer(), SWT.NONE);
+		GridLayout layout = new GridLayout();
+		composite.setLayout(layout);
+		layout.numColumns = 6;
+
+		GridData gd = new GridData();
+		gd.horizontalSpan = 1;
+		Label modelLabel = new Label(composite, SWT.NONE);
+		modelLabel.setText("Model source:");
+		modelLabel.setLayoutData(gd);
+
+		gd = new GridData(GridData.FILL_HORIZONTAL);
+		gd.horizontalSpan = 3;
+		modelText = new Text(composite, SWT.BORDER);
+		modelText.setLayoutData(gd);
+		modelText.setText(viewModel.getSourceModel().getSourcePath()+"");
+		modelText.setEditable(false);
+
+		gd = new GridData();
+		gd.horizontalSpan = 1;
+		Button modelButton = new Button(composite, SWT.NONE);
+		modelButton.setLayoutData(gd);
+		modelButton.setText("Browse...");
+
+		modelButton.addSelectionListener(new SelectionAdapter() {
+			public void widgetSelected(SelectionEvent event) {
+				String[] filterExtensions = { "*.tsm", "*.*" };
+				FileDialog fileDialog = new FileDialog(getContainer()
+						.getShell(), SWT.OPEN);
+				fileDialog.setText("Model source");
+				fileDialog.setFilterExtensions(filterExtensions);
+				viewModel.setModelSource(fileDialog.open());
+				createModelActions(viewModel);
+				modelText.setText(viewModel.getSourceModel().getSourcePath().toString());
+				viewModelSource();
+			}
+		});
+
+		gd = new GridData();
+		gd.horizontalSpan = 1;
+		Button saveButton = new Button(composite, SWT.NONE);
+		saveButton.setText("Save");
+		saveButton.setLayoutData(gd);
+		saveButton.addSelectionListener(new SelectionAdapter() {
+			public void widgetSelected(SelectionEvent event) {
+				viewModel.getSourceModel().doSave();
+			}
+		});
+
+		gd = new GridData(GridData.FILL_BOTH);
+		gd.horizontalSpan = 6;
+		modelSourceText = new Text(composite, SWT.H_SCROLL | SWT.V_SCROLL);
+		modelSourceText.setEditable(false);
+		modelSourceText.setLayoutData(gd);
+
+		int index = addPage(composite);
+		setPageText(index, "Model Source");
+
+	}
+
+	public void setModelSource(String path) {
+		viewModel.setModelSource(path);
+		createModelActions(viewModel);
+		modelText.setText(viewModel.getSourceModel().getSourcePath().toString());
+		viewModelSource();		
+	}
+	
+	public void createSourceEditorPage() {
+		Composite composite = new Composite(getContainer(), SWT.NONE);
+		FillLayout layout = new FillLayout();
+		composite.setLayout(layout);
+		viewSourceText = new Text(composite, SWT.H_SCROLL | SWT.V_SCROLL);
+		viewSourceText.setEditable(false);
+
+		int index = addPage(composite);
+		// setPageText(index, getEditorInput().getName());
+		setPageText(index, "Layout Source");
+	}
+
+	public void createPreviewPage() {
+		SashForm splitter = new SashForm(getContainer(), SWT.HORIZONTAL);
+		testViewer = new ScrollingGraphicalViewer();
+		testViewer.createControl(splitter);
+
+		viewModel.setPreview(true);
+		testViewer.setEditPartFactory(new MyEditPartFactory());
+		testViewer.setContents(viewModel);
+		final ImageDescriptor iconPause = ImageDescriptor.createFromFile(IconDummy.class, "pause_icon.gif");
+		final ImageDescriptor iconResume = ImageDescriptor.createFromFile(IconDummy.class, "resume_icon.gif");
+
+		Composite controlComposite = new Composite(splitter, SWT.NORMAL);
+
+		GridLayout layout = new GridLayout();
+		controlComposite.setLayout(layout);
+		layout.numColumns = 8;
+
+		GridData gd = new GridData();
+		gd.horizontalSpan = 1;
+		Label label = new Label(controlComposite, SWT.NONE);
+		label.setText("Host");
+		label.setLayoutData(gd);
+
+		gd = new GridData(SWT.FILL, SWT.FILL, true, false);
+		gd.horizontalSpan = 4;
+		Text hostText = new Text(controlComposite, SWT.BORDER);
+		hostText.setLayoutData(gd);
+		hostText.setText(modelConnector.getHostName());
+		hostText.addFocusListener(new FocusAdapter() {
+			public void focusLost(FocusEvent e) {
+				modelConnector.setHostName(((Text) e.getSource()).getText());
+			}
+		});
+
+		gd = new GridData();
+		gd.horizontalSpan = 1;
+		label = new Label(controlComposite, SWT.NONE);
+		label.setText("Port");
+
+		gd = new GridData(SWT.FILL, SWT.FILL, true, false);
+		gd.horizontalSpan = 2;
+		Text portText = new Text(controlComposite, SWT.BORDER);
+		portText.setLayoutData(gd);
+		portText.setText("" + modelConnector.getHostPort());
+		portText.addFocusListener(new FocusAdapter() {
+			public void focusLost(FocusEvent e) {
+				modelConnector.setHostPort(Integer.parseInt(((Text) e
+						.getSource()).getText()));
+			}
+		});
+
+		gd = new GridData();
+		gd.horizontalSpan = 1;
+		Label labelmach = new Label(controlComposite, SWT.NONE);
+		labelmach.setText("Name");
+		gd.horizontalAlignment = SWT.RIGHT;
+		labelmach.setLayoutData(gd);
+
+		gd = new GridData(GridData.FILL_HORIZONTAL);
+		gd.horizontalSpan = 7;
+		Text machText = new Text(controlComposite, SWT.BORDER);
+		machText.setLayoutData(gd);
+		machText.setText(modelConnector.getMachineName());
+		machText.addFocusListener(new FocusAdapter() {
+			public void focusLost(FocusEvent e) {
+				modelConnector.setMachineName(((Text) e.getSource()).getText());
+			}
+		});
+
+		gd = new GridData(GridData.FILL_HORIZONTAL);
+		gd.horizontalSpan = 3;
+		final Button loadModelButton = new Button(controlComposite, SWT.NONE);
+		loadModelButton.setText("Download Model");
+		loadModelButton.setToolTipText("Download Model");
+		loadModelButton.setLayoutData(gd);
+		loadModelButton.addSelectionListener(new SelectionAdapter() {
+			public void widgetSelected(SelectionEvent event) {
+				// start up client loop
+				modelConnector.execute("spider");
+			}
+		});
+
+		gd = new GridData(SWT.FILL, SWT.FILL, true, false);
+		gd.horizontalSpan = 3;
+		final Button updateButton = new Button(controlComposite, SWT.NONE);
+		updateButton.setText("New Trace");
+		updateButton.setToolTipText("New Trace");
+		updateButton.setLayoutData(gd);
+		updateButton.addSelectionListener(new SelectionAdapter() {
+			public void widgetSelected(SelectionEvent event) {
+				// start up client loop				
+				modelConnector.firePropertyChange(ModelConnector.EVENT_TRACE_CLEAR, null, null);
+				modelConnector.firePropertyChange(ModelConnector.EVENT_TRACE_MODE_ENTER, null, null);
+				modelConnector.newTrace();
+				//modelConnector.execute("listen");
+				pauseButton.setToolTipText("Pause");
+				pauseButton.setImage(iconPause.createImage());
+			}
+		});
+
+		gd = new GridData(SWT.FILL, SWT.FILL, true, false);
+		gd.horizontalSpan = 1;
+		pauseButton = new Button(controlComposite, SWT.NONE);
+		
+		pauseButton.setImage(iconResume.createImage());
+		pauseButton.setImage(iconPause.createImage());	
+		
+		pauseButton.setToolTipText("Pause");
+		pauseButton.setLayoutData(gd);
+		pauseButton.addSelectionListener(new SelectionAdapter() {
+			public void widgetSelected(SelectionEvent event) {
+				if (!modelConnector.isStop()) {
+					modelConnector.firePropertyChange(ModelConnector.EVENT_TRACE_MODE_EXIT, null, null);
+					modelConnector.stop();
+					pauseButton.setToolTipText("Resume");
+					pauseButton.setImage(iconResume.createImage());
+				} else {
+					modelConnector.firePropertyChange(ModelConnector.EVENT_TRACE_MODE_ENTER, null, null);
+					modelConnector.resume();
+					pauseButton.setToolTipText("Pause");
+					pauseButton.setImage(iconPause.createImage());
+				}
+			}
+		});
+
+		gd = new GridData(SWT.FILL, SWT.FILL, true, false);
+		gd.horizontalSpan = 1;
+		Button reconnectButton = new Button(controlComposite, SWT.NONE);
+		//reconnectButton.setText("Reconnect");
+		ImageDescriptor iconReconn = ImageDescriptor.createFromFile(IconDummy.class, "chasingarrows.gif");
+		reconnectButton.setImage(iconReconn.createImage());
+		reconnectButton.setToolTipText("Reconnect");
+		reconnectButton.setLayoutData(gd);
+		reconnectButton.addSelectionListener(new SelectionAdapter() {
+			public void widgetSelected(SelectionEvent event) {
+				modelConnector.stop();
+				modelConnector.disconnect();
+				modelConnector.connect();
+			}
+		});
+		
+		gd = new GridData(SWT.FILL, SWT.FILL, true, true);
+		gd.horizontalSpan = 8;
+		modelPreviewText = new Text(controlComposite, SWT.H_SCROLL
+				| SWT.V_SCROLL);
+		modelPreviewText.setLayoutData(gd);
+
+		splitter.setWeights(new int[] { 60, 40 });
+		int index = addPage(splitter);
+		setPageText(index, "Monitor");
+	}
+
+	private void doSaveOutput(String outputPath) {
+		try {
+			GraphicalViewer viewer = getGraphicalViewer();
+			EditPart content = viewer.getContents();
+			AbstractModel rootModel = (AbstractModel) content.getModel();
+
+			Document doc = new Document();
+			doc.addContent(rootModel.getXML());
+
+			XMLOutputter outputter = new XMLOutputter(Format.getPrettyFormat());
+			BufferedOutputStream ostream = new BufferedOutputStream(
+					new FileOutputStream(outputPath));
+			outputter.output(doc, ostream);
+			ostream.close();
+
+			Debugger.printDebug(Debugger.DEBUG_ALL,getEditorInput().getName());
+			Debugger.printDebug(Debugger.DEBUG_ALL,outputter.outputString(doc));
+			
+			getEditDomain().getCommandStack().markSaveLocation();
+			
+			// save model (always) vs if in model page
+			// if (this.getActivePage() == PAGE_SOURCE_MODEL)
+			viewModel.getSourceModel().doSave();
+			
+			dirty_flag = false;
+			firePropertyChange(PROP_DIRTY);
+		} catch (Exception e) {
+			e.printStackTrace();
+		}
+	}
+
+	public void doSave(IProgressMonitor monitor) {
+		if (getEditorInput().getName().indexOf("noname")>-1) {
+			doSaveAs();
+		} else {
+			doSaveOutput(getEditorInput().getName());
+		}
+	}
+
+	private IEditorInput createEditorInput(File file) {
+		IPath location = new Path(file.getAbsolutePath());
+		PathEditorInput input = new PathEditorInput(location);
+		return input;
+	}
+
+	private String getEditorId(File file) {
+		IWorkbench workbench= getEditorSite().getWorkbenchWindow().getWorkbench();
+		IEditorRegistry editorRegistry= workbench.getEditorRegistry();
+		IEditorDescriptor descriptor= editorRegistry.getDefaultEditor(file.getName());
+		if (descriptor != null)
+			return descriptor.getId();
+		return "org.tekkotsu.ui.rcp.editors.SimpleEditor"; //$NON-NLS-1$
+	}
+
+	public void doSaveAs() {
+		String[] filterExtensions = { "*.tsl" };
+		FileDialog fileDialog = new FileDialog(getContainer().getShell(),
+				SWT.SAVE);
+		fileDialog.setText("Save As");
+		fileDialog.setFilterExtensions(filterExtensions);
+		String filename = fileDialog.open();
+		if (filename!=null) {
+			String namefix = filename;
+			if (!filename.endsWith(".tsl")) {
+				namefix=filename;
+				filename+=".tsl";
+			} else namefix = filename.substring(0,filename.length()-4);
+			// optionally save model file
+			if (viewModel.getSourceModel().getSourcePath().toString().indexOf("noname")>-1) {
+				viewModel.getSourceModel().doSave(new Path(namefix+".tsm"));
+				viewModel.setModelSource(namefix+".tsm");
+			};
+			
+			doSaveOutput(filename);
+
+			// open/close editor
+			File file = new File(filename);
+			IEditorInput input= createEditorInput(file);
+			String editorId= getEditorId(file);			
+			IWorkbenchPage page= getEditorSite().getWorkbenchWindow().getActivePage();
+			page.closeEditor(page.getActiveEditor(),false);
+			try {				
+				page.openEditor(input, editorId);				
+			} catch (PartInitException e) {
+				//e.printStackTrace();
+			}
+		}
+	}
+
+	/**
+	 * Generate the layout model from XML document
+	 * 
+	 * @param document
+	 *            view layout file
+	 * @return generated layout model for GraphicalViewer
+	 */
+	private ViewModel generateModel(IEditorSite site, Document document, IPath path) {
+		Element root = document.getRootElement();
+		Debugger.printDebug(Debugger.DEBUG_ALL,root.getName());		
+
+		if ("view".equals(root.getName())) {								
+			return new ViewModel(site, root,path);
+		} else
+			return new ViewModel(path);
+	}
+
+	protected PaletteRoot getPaletteRoot() {
+		PaletteRoot root = new PaletteRoot();
+		PaletteGroup toolGroup = new PaletteGroup("Tool");
+
+		// Add SelectionTool entry
+		ToolEntry tool = new SelectionToolEntry();
+		toolGroup.add(tool);
+		root.setDefaultEntry(tool);
+
+		// Add MarqueeTool entry
+		tool = new MarqueeToolEntry();
+		toolGroup.add(tool);
+
+		PaletteDrawer drawer = new PaletteDrawer("Object");
+		ImageDescriptor descriptor = ImageDescriptor.createFromFile(
+				StateMachineEditor.class, "icons/newModel.gif");
+		CreationToolEntry creationEntry = new CreationToolEntry("State node",
+				"Create a new state", new SimpleFactory(StateNodeModel.class),
+				descriptor, descriptor);
+		drawer.add(creationEntry);
+
+		/*
+		 * descriptor = ImageDescriptor.createFromFile(StateMachineEditor.class,
+		 * "icons/arrowConnection.gif"); CreationToolEntry
+		 * arrowConnxCreationEntry = new
+		 * ConnectionCreationToolEntry("Transition","Create a new
+		 * transition",new
+		 * SimpleFactory(TransitionModel.class),descriptor,descriptor);
+		 * drawer.add(arrowConnxCreationEntry);
+		 */
+
+		root.add(toolGroup);
+		root.add(drawer);
+		return root;
+	}
+
+	public void init(IEditorSite site, IEditorInput input)
+			throws PartInitException {
+		super.init(site, input);
+		this.setPartName(input.getName());
+		String pathName = ((IPathEditorInput) input).getPath().toOSString();
+		Debugger.printDebug(Debugger.DEBUG_ALL,pathName);
+				
+		// read state information from file and construct the model
+		try {
+			SAXBuilder builder = new SAXBuilder();
+			Document document = builder.build(new File(pathName));
+			viewModel = generateModel(site, document,((IPathEditorInput)input).getPath().makeAbsolute());						
+			
+			getEditDomain().getCommandStack().markSaveLocation();
+		} catch (Exception e) {
+			// This is just an example. All exceptions caught here.
+			// e.printStackTrace();
+			// Initialize a simple model
+			ViewModel parent = new ViewModel(((IPathEditorInput)input).getPath().makeAbsolute());
+
+			//StateNodeModel state1 = new StateNodeModel();
+			//state1.setConstraint(new Rectangle(0, 0, -1, -1));
+			//parent.addChild(state1);
+
+			viewModel = parent;
+		}
+		viewModel.setEditor(this);
+	}
+
+	protected void initializeGraphicalViewer() {
+		GraphicalViewer viewer = getGraphicalViewer();
+		viewer.setContents(viewModel);
+	}
+
+	public boolean isDirty() {
+		return dirty_flag;
+		//return getEditDomain().getCommandStack().isDirty();
+	}
+
+	public boolean isSaveAsAllowed() {
+		return true;
+	}
+	
+	protected void pageChange(int newPageIndex) {
+		super.pageChange(newPageIndex);
+		setDirty();
+		if (newPageIndex == PAGE_EDITOR) {
+			viewModel.setPreview(false);
+			getSite().getPage().removeSelectionListener(this);
+		} else if (newPageIndex == PAGE_SOURCE_MODEL) {
+			viewModelSource();
+		} else if (newPageIndex == PAGE_SOURCE_LAYOUT) {
+			viewSource();
+		} else if (newPageIndex == PAGE_PREVIEW) {
+			viewModel.setPreview(true);
+			testViewer.setEditPartFactory(new MyEditPartFactory());
+			testViewer.setContents(viewModel);
+			getSite().getPage().addSelectionListener(this);
+		}
+	}
+
+	public void selectionChanged(IWorkbenchPart part, ISelection selection) {
+		if (part.getSite().getWorkbenchWindow().getActivePage() == null)
+			return;
+		Debugger.printDebug(Debugger.DEBUG_ALL,"Selection change receive " + selection);
+
+		super.selectionChanged(part, selection);
+	}
+
+	// display model source on the model source page
+	private void viewModelSource() {
+		SourceModel sourceModel = viewModel.getSourceModel();
+		modelText.setText(sourceModel.getSourcePath().toString());
+		try {
+			Document doc = new Document();
+			doc.addContent(sourceModel.getXML());
+
+			XMLOutputter outputter = new XMLOutputter(Format.getPrettyFormat());
+			StringWriter displayText = new StringWriter();
+			outputter.output(doc, displayText);
+			modelSourceText.setText(displayText.toString());
+		} catch (Exception e) {
+			e.printStackTrace();
+		}
+	}
+
+	private void viewSource() {
+		try {
+			GraphicalViewer viewer = getGraphicalViewer();
+			EditPart content = viewer.getContents();
+			AbstractModel rootModel = (AbstractModel) content.getModel();
+
+			Document doc = new Document();
+			doc.addContent(rootModel.getXML());
+
+			XMLOutputter outputter = new XMLOutputter(Format.getPrettyFormat());
+			StringWriter displayText = new StringWriter();
+			outputter.output(doc, displayText);
+
+			if (Debugger.getDebugLevel() == Debugger.DEBUG_ALL) {
+				ViewEditPart viewContent = (ViewEditPart) content;
+				displayText.write("\r\nCommand stack size:"
+						+ this.getCommandStack().getCommands().length);
+				Object[] cmds = this.getCommandStack().getCommands();
+				for (int i = 0; i < cmds.length; i++)
+					displayText.write("\r\n" + cmds[i]);
+
+				displayText.write("\r\nViewEditPart list size : "
+						+ viewContent.getChildren().size() + " ");
+				Iterator iter = viewContent.getChildren().iterator();
+				while (iter.hasNext()) {
+					displayText.write("\r\n" + iter.next());
+				}
+
+				ViewModel viewModel = (ViewModel) content.getModel();
+				displayText.write("\r\nViewModel list size : "
+						+ viewModel.getPartChildren().size() + " ");
+				iter = viewModel.getPartChildren().iterator();
+				while (iter.hasNext()) {
+					displayText.write("\r\n" + iter.next());
+				}
+
+			}
+
+			viewSourceText.setText(displayText.toString());
+		} catch (Exception e) {
+			e.printStackTrace();
+		}
+	}
+
+	/**
+	 * @return Returns the viewModel.
+	 */
+	public ViewModel getViewModel() {
+		return viewModel;
+	}
+
+	/**
+	 * @return Returns the modelConnector.
+	 */
+	public ModelConnector getModelConnector() {
+		return modelConnector;
+	}
+}
+
+class PathEditorInput implements IPathEditorInput {
+	private IPath fPath;
+	
+	/**
+	 * Creates an editor input based of the given file resource.
+	 *
+	 * @param path the file
+	 */
+	public PathEditorInput(IPath path) {
+		if (path == null) {
+			throw new IllegalArgumentException();
+		}
+		this.fPath = path;
+	}
+	
+	/*
+	 * @see java.lang.Object#hashCode()
+	 */
+	public int hashCode() {
+		return fPath.hashCode();
+	}
+	
+	/*
+	 * @see java.lang.Object#equals(java.lang.Object)
+	 */
+	public boolean equals(Object obj) {
+		if (this == obj)
+			return true;
+		if (!(obj instanceof PathEditorInput))
+			return false;
+		PathEditorInput other = (PathEditorInput) obj;
+		return fPath.equals(other.fPath);
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#exists()
+	 */
+	public boolean exists() {
+		return fPath.toFile().exists();
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getImageDescriptor()
+	 */
+	public ImageDescriptor getImageDescriptor() {
+		return PlatformUI.getWorkbench().getEditorRegistry().getImageDescriptor(fPath.toString());
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getName()
+	 */
+	public String getName() {
+		return fPath.toString();
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getToolTipText()
+	 */
+	public String getToolTipText() {
+		return fPath.makeRelative().toString();
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IPathEditorInput#getPath()
+	 */
+	public IPath getPath() {
+		return fPath;
+	}
+
+	/*
+	 * @see org.eclipse.core.runtime.IAdaptable#getAdapter(java.lang.Class)
+	 */
+	public Object getAdapter(Class adapter) {
+		return null;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getPersistable()
+	 */
+	public IPersistableElement getPersistable() {
+		// no persistence
+		return null;
+	}
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditorContextMenuProvider.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditorContextMenuProvider.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditorContextMenuProvider.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/StateMachineEditorContextMenuProvider.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,135 @@
+/*
+ * Created on Oct 6, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.ContextMenuProvider;
+import org.eclipse.gef.EditPart;
+import org.eclipse.gef.EditPartViewer;
+import org.eclipse.gef.ui.actions.ActionRegistry;
+import org.eclipse.gef.ui.actions.GEFActionConstants;
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.IAction;
+import org.eclipse.jface.action.IMenuManager;
+import org.eclipse.jface.action.MenuManager;
+import org.eclipse.swt.events.MouseEvent;
+import org.eclipse.swt.events.MouseMoveListener;
+import org.eclipse.ui.actions.ActionFactory;
+import org.tekkotsu.ui.editor.editparts.StateNodeEditPart;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * Provide context menu for state machine edit parts
+ * @author asangpet
+ */
+public class StateMachineEditorContextMenuProvider extends ContextMenuProvider {
+	/** The editor's action registry. */
+	private ActionRegistry actionRegistry;
+	private int mousex, mousey;
+	
+	class MouseLocationTrack implements MouseMoveListener {
+		public void mouseMove(MouseEvent e) {
+			mousex = e.x; mousey = e.y;
+		}
+	}
+	
+	/**
+	 * Instantiate a new menu context provider for the specified EditPartViewer 
+	 * and ActionRegistry.
+	 * @param viewer	the editor's graphical viewer
+	 * @param registry	the editor's action registry
+	 * @throws IllegalArgumentException if registry is <tt>null</tt>. 
+	 */
+	public StateMachineEditorContextMenuProvider(EditPartViewer viewer, ActionRegistry registry) {
+		super(viewer);
+		if (registry == null) {
+			throw new IllegalArgumentException();
+		}
+		getViewer().getControl().addMouseMoveListener(new MouseLocationTrack());
+		actionRegistry = registry;
+	}
+
+	/**
+	 * Called when the context menu is about to show. Actions, 
+	 * whose state is enabled, will appear in the context menu.
+	 * @see org.eclipse.gef.ContextMenuProvider#buildContextMenu(org.eclipse.jface.action.IMenuManager)
+	 */
+	public void buildContextMenu(IMenuManager menu) {		
+		// Add standard action groups to the menu
+		GEFActionConstants.addStandardActionGroups(menu);
+		// Add actions to the menu
+		menu.appendToGroup(
+				GEFActionConstants.GROUP_UNDO, // target group id
+				getAction(ActionFactory.UNDO.getId())); // action to add
+		menu.appendToGroup(
+				GEFActionConstants.GROUP_UNDO, 
+				getAction(ActionFactory.REDO.getId()));
+		menu.appendToGroup(
+				GEFActionConstants.GROUP_EDIT,
+				getAction(ActionFactory.DELETE.getId()));		
+
+		menu.add(actionRegistry.getAction(IDTag.ACTION_add_all));
+		// declare menu options based on selected objects
+		List selectedParts = getViewer().getSelectedEditParts();
+		if ((selectedParts.size()==1) && (((EditPart)selectedParts.get(0)) instanceof StateNodeEditPart)) {
+			// add transition menu			
+			menu.add(getTransitionMenu((EditPart)selectedParts.get(0)));			
+		} else {			
+			menu.add(getStateMenu());
+			Debugger.printDebug(Debugger.DEBUG_ALL,"Mouse location: ("+mousex+","+mousey+")");
+			menu.add(getTransitionMenu(null));
+		}
+	}
+	
+	private MenuManager getStateMenu() {
+		MenuManager statesubmenu = new MenuManager("Add &State");
+		ViewModel view = (ViewModel)this.getViewer().getContents().getModel();		
+		
+		Iterator iter = actionRegistry.getActions();
+		while (iter.hasNext()) {
+			Action action = (Action)iter.next();
+			if (action instanceof StateMachineEditor.CreateNodeAction) {
+				StateMachineEditor.CreateNodeAction act = (StateMachineEditor.CreateNodeAction)action;				
+				action.setChecked(view.getPartChild(act.getModel().getId()) != null);
+				action.setEnabled(!action.isChecked());
+				act.getRequest().setLocation(new Point(mousex,mousey));				
+				statesubmenu.add(action);
+			}
+		}		
+		return statesubmenu;
+	}
+	
+	private MenuManager getTransitionMenu(EditPart part) {
+		MenuManager transmenu = new MenuManager("Add &Transition");
+		// set checked / display only related node
+		Iterator iter = actionRegistry.getActions();
+		ViewModel view = (ViewModel)this.getViewer().getContents().getModel();
+		while (iter.hasNext()) {
+			Action action = (Action)iter.next();
+			if (action instanceof StateMachineEditor.CreateTransitionAction) {
+				StateMachineEditor.CreateTransitionAction transAct = (StateMachineEditor.CreateTransitionAction) action;
+				action.setChecked((view.getPartChild(transAct.getModel().getId()) != null));
+				action.setEnabled(!action.isChecked());
+				transAct.getRequest().setLocation(new Point(mousex,mousey));
+				if ((part == null) || (transAct.getModel().getDestNodes().contains(((StateNodeModel)part.getModel()).getId())) ||
+					(transAct.getModel().getSourceNodes().contains(((StateNodeModel)part.getModel()).getId()))) {					
+					transmenu.add(action);							
+				}
+				
+			}			
+		}
+		return transmenu;
+	}
+
+	private IAction getAction(String actionId) {
+		return actionRegistry.getAction(actionId);
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/TransitionConnection.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/TransitionConnection.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/TransitionConnection.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/TransitionConnection.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,16 @@
+/*
+ * Created on Dec 22, 2004
+ */
+package org.tekkotsu.ui.editor;
+
+import org.eclipse.draw2d.Connection;
+import org.eclipse.draw2d.RotatableDecoration;
+
+/**
+ * @author asangpet
+ *
+ */
+public interface TransitionConnection extends Connection {
+	public void setLineWidth(int w);
+	public void setTargetDecoration(RotatableDecoration dec);
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/TestResource.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/TestResource.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/TestResource.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/TestResource.java	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,5 @@
+package org.tekkotsu.ui.editor.debug;
+
+public class TestResource {
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace.tse ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace.tse	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,74 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="302429" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="302430" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="310856" />
+    <statestop id="Waiting" time="310859" />
+    <statestart id="Image" time="310860" />
+  </event>
+  <event type="image" sid="Image" time="310886">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="310923" />
+    <statestop id="Image" time="310924" />
+    <statestart id="Waiting" time="310924" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="320628" />
+    <statestop id="Waiting" time="320630" />
+    <statestart id="Webcam" time="320632" />
+  </event>
+  <event type="webcam" sid="Webcam" time="320632" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="320643" />
+    <statestop id="Webcam" time="320645" />
+    <statestart id="Waiting" time="320645" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="327596" />
+    <statestop id="Waiting" time="327598" />
+    <statestart id="Message" time="327602" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="327603">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="327604" />
+    <statestop id="Message" time="327605" />
+    <statestart id="Waiting" time="327605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="338412" />
+    <statestop id="Waiting" time="338416" />
+    <statestart id="Message" time="338418" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="338419">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="338420" />
+    <statestop id="Message" time="338421" />
+    <statestart id="Waiting" time="338421" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="347770" />
+    <statestop id="Waiting" time="347773" />
+    <statestart id="Image" time="347774" />
+  </event>
+
+  <event type="image" sid="Image" time="347800">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="347829" />
+    <statestop id="Image" time="347835" />
+    <statestart id="Waiting" time="347835" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="359629" />
+  </event>
+ 
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace2.tse ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace2.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace2.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace2.tse	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,173 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="563157" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="563158" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="569397" />
+    <statestop id="Waiting" time="569401" />
+    <statestart id="Image" time="569402" />
+  </event>
+  <event type="image" sid="Image" time="569428">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="569461" />
+    <statestop id="Image" time="569466" />
+    <statestart id="Waiting" time="569466" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="575116" />
+    <statestop id="Waiting" time="575118" />
+    <statestart id="Message" time="575122" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="575123">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="575124" />
+    <statestop id="Message" time="575125" />
+    <statestart id="Waiting" time="575125" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="582707" />
+    <statestop id="Waiting" time="582709" />
+    <statestart id="Webcam" time="582710" />
+  </event>
+  <event type="webcam" sid="Webcam" time="582710" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="582722" />
+    <statestop id="Webcam" time="582724" />
+    <statestart id="Waiting" time="582725" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="589467" />
+    <statestop id="Waiting" time="589469" />
+    <statestart id="Message" time="589470" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="589470">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="589474" />
+    <statestop id="Message" time="589482" />
+    <statestart id="Waiting" time="589482" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="605276" />
+    <statestop id="Waiting" time="605278" />
+    <statestart id="Image" time="605281" />
+  </event>
+  <event type="image" sid="Image" time="605307">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="605336" />
+    <statestop id="Image" time="605340" />
+    <statestart id="Waiting" time="605340" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="611514" />
+    <statestop id="Waiting" time="611516" />
+    <statestart id="Message" time="611517" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="611517">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="611523" />
+    <statestop id="Message" time="611528" />
+    <statestart id="Waiting" time="611528" />
+  </event>
+  <event>
+    <statestart id="Logging Test" time="672565" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="672566" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="677042" />
+    <statestop id="Waiting" time="677044" />
+    <statestart id="Message" time="677045" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="677045">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="677058" />
+    <statestop id="Message" time="677060" />
+    <statestart id="Waiting" time="677060" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="680995" />
+    <statestop id="Waiting" time="680998" />
+    <statestart id="Image" time="681001" />
+  </event>
+  <event type="image" sid="Image" time="681024">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="681053" />
+    <statestop id="Image" time="681062" />
+    <statestart id="Waiting" time="681064" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="691594" />
+    <statestop id="Waiting" time="691596" />
+    <statestart id="Webcam" time="691597" />
+  </event>
+  <event type="webcam" sid="Webcam" time="691597" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="691602" />
+    <statestop id="Webcam" time="691604" />
+    <statestart id="Waiting" time="691605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="694821" />
+    <statestop id="Waiting" time="694824" />
+    <statestart id="Message" time="694826" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="694827">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="694834" />
+    <statestop id="Message" time="694837" />
+    <statestart id="Waiting" time="694837" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="700540" />
+    <statestop id="Waiting" time="700544" />
+    <statestart id="Message" time="700546" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="700547">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="700549" />
+    <statestop id="Message" time="700550" />
+    <statestart id="Waiting" time="700550" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="704699" />
+    <statestop id="Waiting" time="704702" />
+    <statestart id="Image" time="704705" />
+  </event>
+  <event type="image" sid="Image" time="704731">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="704760" />
+    <statestop id="Image" time="704765" />
+    <statestart id="Waiting" time="704765" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="710315" />
+    <statestop id="Waiting" time="710317" />
+    <statestart id="Webcam" time="710318" />
+  </event>
+  <event type="webcam" sid="Webcam" time="710318" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="710323" />
+    <statestop id="Webcam" time="710325" />
+    <statestart id="Waiting" time="710325" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="717389" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="717394" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace3.tse ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace3.tse
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace3.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt-trace3.tse	2005-10-11 06:11:15.000000000 -0400
@@ -0,0 +1,163 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="302429" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="302430" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="310856" />
+    <statestop id="Waiting" time="310859" />
+    <statestart id="Image" time="310860" />
+  </event>
+  <event type="image" sid="Image" time="310886">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="310923" />
+    <statestop id="Image" time="310924" />
+    <statestart id="Waiting" time="310924" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="320628" />
+    <statestop id="Waiting" time="320630" />
+    <statestart id="Webcam" time="320632" />
+  </event>
+  <event type="webcam" sid="Webcam" time="320632" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="320643" />
+    <statestop id="Webcam" time="320645" />
+    <statestart id="Waiting" time="320645" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="327596" />
+    <statestop id="Waiting" time="327598" />
+    <statestart id="Message" time="327602" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="327603">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="327604" />
+    <statestop id="Message" time="327605" />
+    <statestart id="Waiting" time="327605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="338412" />
+    <statestop id="Waiting" time="338416" />
+    <statestart id="Message" time="338418" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="338419">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="338420" />
+    <statestop id="Message" time="338421" />
+    <statestart id="Waiting" time="338421" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="347770" />
+    <statestop id="Waiting" time="347773" />
+    <statestart id="Image" time="347774" />
+  </event>
+
+  <event type="image" sid="Image" time="347800">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="347829" />
+    <statestop id="Image" time="347835" />
+    <statestart id="Waiting" time="347835" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="359629" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="359635" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="1963930" />
+    <statestop id="Waiting" time="1963932" />
+    <statestart id="Message" time="1963933" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="1963934">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="1963938" />
+    <statestop id="Message" time="1963942" />
+    <statestart id="Waiting" time="1963942" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="1976619" />
+    <statestop id="Waiting" time="1976621" />
+    <statestart id="Webcam" time="1976622" />
+  </event>
+  <event type="webcam" sid="Webcam" time="1976622" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="1976626" />
+    <statestop id="Webcam" time="1976629" />
+    <statestart id="Waiting" time="1976629" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="1983795" />
+    <statestop id="Waiting" time="1983798" />
+    <statestart id="Image" time="1983801" />
+  </event>
+  <event type="image" sid="Image" time="1983828">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="1983861" />
+    <statestop id="Image" time="1983866" />
+    <statestart id="Waiting" time="1983866" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="1987644" />
+    <statestop id="Waiting" time="1987648" />
+    <statestart id="Message" time="1987650" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="1987651">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="1987653" />
+    <statestop id="Message" time="1987654" />
+    <statestart id="Waiting" time="1987654" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="1992740" />
+    <statestop id="Waiting" time="1992742" />
+    <statestart id="Webcam" time="1992746" />
+  </event>
+  <event type="webcam" sid="Webcam" time="1992746" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="1992753" />
+    <statestop id="Webcam" time="1992757" />
+    <statestart id="Waiting" time="1992757" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="1996067" />
+    <statestop id="Waiting" time="1996070" />
+    <statestart id="Image" time="1996072" />
+  </event>
+  <event type="image" sid="Image" time="1996096">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="1996125" />
+    <statestop id="Image" time="1996133" />
+    <statestart id="Waiting" time="1996133" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="2000747" />
+    <statestop id="Waiting" time="2000749" />
+    <statestart id="Message" time="2000750" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="2000750">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="2000754" />
+    <statestop id="Message" time="2000757" />
+    <statestart id="Waiting" time="2000757" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="2004811" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="2004813" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsl ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsl
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsl	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,15 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="lt.tsm">
+  <state id="Logging Test" label="Logging Test" color="#ffc400" top="17" left="67" width="171" height="20" shape="Rectangle" />
+  <state id="Waiting" label="Waiting" color="#00ff00" top="165" left="150" width="50" height="20" shape="Rectangle" />
+  <state id="Image" label="Image" color="#00ffff" top="136" left="76" width="50" height="20" shape="Rectangle" />
+  <state id="Message" label="Message" color="#60ff60" top="93" left="111" width="50" height="20" shape="Rectangle" />
+  <state id="Webcam" label="Webcam" color="#ff0000" top="56" left="160" width="50" height="20" shape="Rectangle" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans" label="transition9" color="#000000" top="130" left="136" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans" label="transition13" color="#000000" top="118" left="160" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans" label="transition17" color="#000000" top="109" left="181" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition21" color="#000000" top="168" left="120" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition25" color="#000000" top="138" left="126" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition29" color="#000000" top="111" left="141" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsm ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsm
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/debug/lt.tsm	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,33 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Logging Test" class="LogTestMachine" />
+  <state id="Waiting" class="StateNode" />
+  <state id="Image" class="ImageLogTestNode" />
+  <state id="Message" class="MessageLogTestNode" />
+  <state id="Webcam" class="WebcamLogTestNode" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Image</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Message</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Webcam</destination>
+  </transition>
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Image</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Message</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Webcam</source>
+    <destination>Waiting</destination>
+  </transition>
+</model>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/EditPartWithListener.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/EditPartWithListener.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/EditPartWithListener.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/EditPartWithListener.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,28 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.editparts;
+
+import java.beans.PropertyChangeListener;
+
+import org.eclipse.gef.editparts.AbstractGraphicalEditPart;
+import org.tekkotsu.ui.editor.model.AbstractModel;
+
+/**
+ * EditPart component extension with properties listener.
+ * @author asangpet
+ */
+abstract public class EditPartWithListener
+	extends AbstractGraphicalEditPart 
+	implements PropertyChangeListener {
+	
+	public void activate() {
+		super.activate();
+		((AbstractModel)getModel()).addPropertyChangeListener(this);
+	}
+	
+	public void deactivate() {
+		super.deactivate();
+		((AbstractModel)getModel()).removePropertyChangeListener(this);		
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MultiTransitionEditPart.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MultiTransitionEditPart.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MultiTransitionEditPart.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MultiTransitionEditPart.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,180 @@
+/*
+ * Created on Oct 12, 2004
+ */
+package org.tekkotsu.ui.editor.editparts;
+
+import java.beans.PropertyChangeEvent;
+import java.util.HashMap;
+import java.util.Iterator;
+import java.util.List;
+import java.util.Map;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.ConnectionAnchor;
+import org.eclipse.draw2d.Ellipse;
+import org.eclipse.draw2d.EllipseAnchor;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Label;
+import org.eclipse.draw2d.PositionConstants;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.gef.ConnectionEditPart;
+import org.eclipse.gef.EditPart;
+import org.eclipse.gef.GraphicalEditPart;
+import org.eclipse.gef.Request;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.SourceTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.SubConnectionModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+/**
+ * @author asangpet
+ */
+public class MultiTransitionEditPart extends StateNodeEditPart {		
+	public ConnectionAnchor getSourceConnectionAnchor(ConnectionEditPart connection) {
+		return new EllipseAnchor(shape);
+	}
+	
+	public ConnectionAnchor getTargetConnectionAnchor(ConnectionEditPart connection) {
+		return new EllipseAnchor(shape);
+	}
+	
+	public ConnectionAnchor getSourceConnectionAnchor(Request request) {
+		return new EllipseAnchor(shape);
+	}
+	
+	public ConnectionAnchor getTargetConnectionAnchor(Request request) {
+		return new EllipseAnchor(shape);
+	}
+
+	private Map getModelToEditPart() {
+		ViewEditPart viewer = (ViewEditPart)this.getParent();		
+		Map mapModelToEditPart = new HashMap();
+		List parts = viewer.getChildren();
+		for (int i = 0; i < parts.size(); i++) {
+			EditPart editPart = (EditPart)parts.get(i);
+			mapModelToEditPart.put(editPart.getModel(), editPart);
+		}		
+		return mapModelToEditPart;
+	}
+	
+	/**
+	 * Return default label location for the transition (midpoint)
+	 * @return reference point for default label location
+	 */
+	private Point getDefaultLocation() {
+		ViewModel view = (ViewModel)(((MultiTransitionModel)getModel()).getParent());
+		SourceTransitionModel srcModel = (SourceTransitionModel)((MultiTransitionModel)this.getModel()).getSource();
+		
+		StateNodeModel source = (StateNodeModel)view.getPartChild((String)srcModel.getSourceNodes().get(0));
+		StateNodeModel target = (StateNodeModel)view.getPartChild((String)srcModel.getDestNodes().get(0));
+		
+		Map model2part = getModelToEditPart();
+		StateNodeEditPart srcState = (StateNodeEditPart)model2part.get(source);
+		StateNodeEditPart dstState = (StateNodeEditPart)model2part.get(target);
+				
+		Point srcPoint = srcState.getSourceConnectionAnchor((ConnectionEditPart)null).getLocation(new Point(0,0));
+		Point destPoint = dstState.getSourceConnectionAnchor((ConnectionEditPart)null).getLocation(new Point(0,0));
+
+		int dx = destPoint.x-srcPoint.x;
+		int dy = destPoint.y-srcPoint.y;
+		float ds = (int)Math.sqrt(dx*dx+dy*dy);
+		Point mid = new Point((srcPoint.x+destPoint.x)/2,(srcPoint.y+destPoint.y)/2);
+		int du = 20;
+		return mid.translate(Math.round(-dy*du/ds),Math.round(dx*du/ds));
+	}
+	
+	private Rectangle getDefaultBound() {
+		//Rectangle result = new Rectangle();
+		//result.setLocation(getDefaultLocation());
+		//String label = ((MultiTransitionModel)getModel()).getLabel();
+		//if (label==null) result.setSize(20,20);
+		//else result.setSize(label.length()*10,20);
+		//return result;
+		
+		return new Rectangle(600,600,2,2);
+	}
+	
+	protected IFigure createFigure() {
+		MultiTransitionModel model = (MultiTransitionModel)getModel();		
+		holder = new Figure();		
+		shape = new Ellipse();
+		label = new Label();	
+
+		if (model.isSingleTransition()) {
+			org.eclipse.swt.graphics.Rectangle dummy = getViewer().getControl().getBounds();
+			holder.setBounds(new Rectangle(dummy.width+1, dummy.height+1,1,1));
+			return holder;
+			//SubConnectionModel selector = (SubConnectionModel)model.getSubConnectionList().get(0);
+			//Debugger.printDebug(Debugger.DEBUG_ALL,"Accessing "+this.getParent().getChildren()+" from "+model.getSubConnectionList());
+		}
+		
+		if (model.getConstraint()==null) model.setConstraint(getDefaultBound());
+		
+		if (((ViewModel)(getParent().getModel())).isPreview()) {
+			shape.setBackgroundColor(model.getPreviewColor());
+			shape.setBounds(model.getConstraint());	
+			shape.setForegroundColor(ColorConstants.lightGray);
+			label.setForegroundColor(ColorConstants.lightGray);
+		} else {
+			shape.setBackgroundColor(model.getColor());
+			shape.setBounds(model.getConstraint());			
+			shape.setForegroundColor(ColorConstants.black);
+			label.setForegroundColor(ColorConstants.black);
+		}
+		
+		label.setText(model.getLabel());
+		label.setTextAlignment(PositionConstants.RIGHT);
+		label.setLabelAlignment(PositionConstants.RIGHT);
+		holder.add(shape);
+		holder.add(label);
+		holder.setBounds(model.getConstraint());
+		return holder;				
+	}
+	
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals(MultiTransitionModel.P_LINEWIDTH)) {
+			Iterator iter = ((MultiTransitionModel)getModel()).getSubConnectionList().iterator();
+			while (iter.hasNext()) {
+				SubConnectionModel model = (SubConnectionModel)iter.next();
+				model.setLineWidth(((MultiTransitionModel)getModel()).getLineWidth());
+			}
+		} else super.propertyChange(evt); 
+	}	
+	
+	/**
+	 * Adjust label color according to background color of the figure
+	 */
+	protected void setLabelColor() {
+		if (((MultiTransitionModel)getModel()).isPreview()) {
+			label.setForegroundColor(ColorConstants.lightGray);
+		} else {
+			label.setForegroundColor(ColorConstants.black);
+		}
+	}
+	
+	protected Rectangle getShapeConstraint(Rectangle constraint) {
+		Rectangle shapeConstraint = new Rectangle(constraint);
+		shapeConstraint.setSize(shapeConstraint.height>>1, shapeConstraint.height>>1);
+		shapeConstraint.setLocation(shapeConstraint.getLeft());
+		return shapeConstraint;
+	}
+	
+	protected void refreshVisuals() {
+		MultiTransitionModel model = (MultiTransitionModel)getModel();
+		//Rectangle constraint = ((StateNodeModel)getModel()).getConstraint();
+		Rectangle constraint = model.getConstraint();		
+		
+		if (model.getSubConnectionList().size() == 1) {
+			constraint.setLocation(getDefaultLocation());			
+		}
+		
+		if (!model.isSingleTransition()) {
+			((GraphicalEditPart)getParent()).setLayoutConstraint(this, getFigure(), constraint);
+			holder.setBounds(constraint);
+			shape.setBounds(getShapeConstraint(constraint));
+			label.setBounds(constraint);
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyAbstractConnectionEditPart.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyAbstractConnectionEditPart.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyAbstractConnectionEditPart.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyAbstractConnectionEditPart.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,70 @@
+/*
+ * Created on Sep 18, 2004
+ */
+package org.tekkotsu.ui.editor.editparts;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.util.ArrayList;
+import java.util.List;
+
+import org.eclipse.draw2d.AbsoluteBendpoint;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.EditPolicy;
+import org.eclipse.gef.editparts.AbstractConnectionEditPart;
+import org.tekkotsu.ui.editor.editpolicies.MyBendpointEditPolicy;
+import org.tekkotsu.ui.editor.editpolicies.MyConnectionEditPolicy;
+import org.tekkotsu.ui.editor.editpolicies.MyConnectionEndpointEditPolicy;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+
+/**
+ * @author asangpet
+ */
+public abstract class MyAbstractConnectionEditPart extends
+		AbstractConnectionEditPart implements PropertyChangeListener {
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.gef.editparts.AbstractEditPart#createEditPolicies()
+	 */
+	protected void createEditPolicies() {
+		installEditPolicy(EditPolicy.CONNECTION_ROLE,
+				new MyConnectionEditPolicy());
+		installEditPolicy(EditPolicy.CONNECTION_ENDPOINTS_ROLE,
+				new MyConnectionEndpointEditPolicy());
+		installEditPolicy(EditPolicy.CONNECTION_BENDPOINTS_ROLE,
+				new MyBendpointEditPolicy());
+	}
+
+	public void activate() {
+		super.activate();
+		((AbstractConnectionModel) getModel()).addPropertyChangeListener(this);
+	}
+
+	public void deactivate() {
+		super.deactivate();
+		((AbstractConnectionModel) getModel())
+				.removePropertyChangeListener(this);
+	}
+
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals(AbstractConnectionModel.P_BEND_POINT))
+			refreshBendpoints();
+	}
+
+	protected void refreshBendpoints() {
+		List bendpoints = ((AbstractConnectionModel) getModel())
+				.getBendpoints();
+		List constraint = new ArrayList();
+
+		for (int i = 0; i < bendpoints.size(); i++) {
+			constraint.add(new AbsoluteBendpoint((Point) bendpoints.get(i)));
+		}
+		getConnectionFigure().setRoutingConstraint(constraint);
+	}
+
+	protected void refreshVisuals() {
+		refreshBendpoints();
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyEditPartFactory.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyEditPartFactory.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyEditPartFactory.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/MyEditPartFactory.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,35 @@
+/*
+ * Created on Sep 11, 2004
+ */
+package org.tekkotsu.ui.editor.editparts;
+
+/**
+ * @author asangpet
+ *
+ */
+import org.eclipse.gef.EditPart;
+import org.eclipse.gef.EditPartFactory;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.SubConnectionModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+
+public class MyEditPartFactory implements EditPartFactory {
+	public EditPart createEditPart(EditPart context, Object model) {
+		EditPart part = null;
+		
+		if (model instanceof ViewModel)
+			part = new ViewEditPart();
+		else if (model instanceof MultiTransitionModel)
+			part = new MultiTransitionEditPart();
+		else if (model instanceof StateNodeModel)
+			part = new StateNodeEditPart();
+		//else if (model instanceof TransitionModel)
+		//	part = new TransitionEditPart();
+		else if (model instanceof SubConnectionModel)
+			part = new SubConnectionEditPart();
+		
+		part.setModel(model);
+		return part;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/StateNodeEditPart.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/StateNodeEditPart.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/StateNodeEditPart.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/StateNodeEditPart.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,222 @@
+package org.tekkotsu.ui.editor.editparts;
+
+/**
+ * @author asangpet
+ */
+
+import java.beans.PropertyChangeEvent;
+import java.util.List;
+
+import org.eclipse.draw2d.ChopboxAnchor;
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.ConnectionAnchor;
+import org.eclipse.draw2d.Ellipse;
+import org.eclipse.draw2d.*;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Label;
+import org.eclipse.draw2d.RectangleFigure;
+import org.eclipse.draw2d.RoundedRectangle;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.gef.ConnectionEditPart;
+import org.eclipse.gef.EditPolicy;
+import org.eclipse.gef.GraphicalEditPart;
+import org.eclipse.gef.NodeEditPart;
+import org.eclipse.gef.Request;
+import org.eclipse.swt.graphics.Color;
+import org.eclipse.swt.graphics.RGB;
+import org.tekkotsu.ui.editor.editpolicies.MyComponentEditPolicy;
+import org.tekkotsu.ui.editor.model.*;
+import org.tekkotsu.ui.editor.resources.ConvexPolygon;
+import org.tekkotsu.ui.editor.resources.Debugger;
+
+public class StateNodeEditPart 
+	extends EditPartWithListener 
+	implements NodeEditPart {
+
+	protected IFigure shape, holder;
+	protected Label label;
+	boolean isSrc = true;
+
+	private ConnectionAnchor getAnchor() {
+		StateNodeModel model = (StateNodeModel)getModel();
+		if (model.getShape().equals(StateNodeModel.P_SHAPE_STYLE_ELLIPSE)) {
+			return new EllipseAnchor(getFigure());
+		} else return new ChopboxAnchor(getFigure());
+	}
+	
+	public ConnectionAnchor getSourceConnectionAnchor(ConnectionEditPart connection) {
+		return getAnchor();
+	}
+	
+	public ConnectionAnchor getTargetConnectionAnchor(ConnectionEditPart connection) {
+		return getAnchor();
+	}
+	
+	public ConnectionAnchor getSourceConnectionAnchor(Request request) {
+		return getAnchor();
+	}
+	
+	public ConnectionAnchor getTargetConnectionAnchor(Request request) {
+		return getAnchor();
+	}
+	
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals(StateNodeModel.P_ACTIVATE)) {
+			try {
+				shape.setBackgroundColor(((StateNodeModel)getModel()).getColor());
+				setLabelColor(true);
+			} catch (Exception e) {
+				e.printStackTrace();
+			}
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_DEACTIVATE)) {
+			try {
+				shape.setBackgroundColor(((StateNodeModel)getModel()).getPreviewColor());
+				setLabelColor(false);
+			} catch (Exception e) {
+				
+			}			
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_CONSTRAINT)) {
+			Debugger.printDebug(Debugger.DEBUG_ALL, this.toString()+"\n\tP_CONSTRAINT change to "+evt.getNewValue());			
+			refreshVisuals();
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_LABEL)) {
+			label.setText((String)evt.getNewValue());
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_COLOR)) {
+			shape.setBackgroundColor((Color)evt.getNewValue());
+			setLabelColor();
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_SOURCE_CONNECTION)) {
+			refreshSourceConnections();
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_TARGET_CONNECTION)) {
+			refreshTargetConnections();
+		} else if (evt.getPropertyName().equals(StateNodeModel.P_SHAPE)) {
+			resetShape(evt.getNewValue().toString());
+		} else if (evt.getPropertyName().equals(ViewModel.P_SOURCE_EXIST)) {
+			isSrc = ((Boolean)evt.getNewValue()).booleanValue();
+			setPreviewColor();
+		} 
+	}
+
+	private void setPreviewColor() {
+		StateNodeModel model = (StateNodeModel)getModel();		
+		if (!isSrc) {
+			shape.setBackgroundColor(model.getPreviewColor());
+			shape.setForegroundColor(ColorConstants.lightGray);
+		} else {
+			shape.setBackgroundColor(model.getColor());
+			shape.setForegroundColor(ColorConstants.black);			
+		}
+		
+		setLabelColor();
+	}
+	
+	protected IFigure createCustomFigure(IFigure shapeFigure) {
+		StateNodeModel model = (StateNodeModel)getModel();
+		holder = new Figure();
+		
+		shape = shapeFigure;
+		if (((ViewModel)(getParent().getModel())).isPreview() || (!isSrc)) {
+			shape.setBackgroundColor(model.getPreviewColor());
+			shape.setBounds(model.getConstraint());			
+		} else {
+			shape.setBackgroundColor(model.getColor());
+			shape.setBounds(model.getConstraint());			
+		}
+		
+		label = new Label();
+		label.setText(model.getLabel());
+		label.setBounds(model.getConstraint());		
+		setLabelColor();
+		
+		holder.add(shape);
+		holder.add(label);
+		holder.setBounds(model.getConstraint());		
+		return holder;		
+	}
+	
+	private void resetShape(String shapeType) {
+		IFigure shapeFigure = null;
+		if (shapeType.equals(StateNodeModel.P_SHAPE_STYLE_RECTANGLE)) {
+			shapeFigure = new RectangleFigure();
+		} else if (shapeType.equals(StateNodeModel.P_SHAPE_STYLE_ELLIPSE)){
+			shapeFigure = new Ellipse();
+		} else if (shapeType.equals(StateNodeModel.P_SHAPE_STYLE_ROUNDED_RECTANGLE)) {
+			shapeFigure = new RoundedRectangle();
+		} else if (shapeType.equals(StateNodeModel.P_SHAPE_STYLE_HEXAGON)) {
+			shapeFigure = new ConvexPolygon();
+		}
+		shapeFigure.setBackgroundColor(shape.getBackgroundColor());
+		shapeFigure.setBounds(shape.getBounds());
+				
+		if (((ViewModel)(getParent().getModel())).isPreview() || !isSrc) {
+			((Shape)shapeFigure).setForegroundColor(ColorConstants.lightGray);			
+		} else {
+			((Shape)shapeFigure).setForegroundColor(ColorConstants.black);			
+		}
+		
+		holder.remove(shape);
+		holder.remove(label);
+		shape = shapeFigure;
+		holder.add(shape);
+		holder.add(label);
+	}
+	
+	protected IFigure createFigure() {
+		createCustomFigure(new RectangleFigure());
+		resetShape(((StateNodeModel)getModel()).getShape());
+		return holder;
+	}
+	
+	/**
+	 * Adjust label color according to background color of the figure
+	 */
+	protected void setLabelColor(boolean isActive) {
+		try {
+			RGB bgcolor = (shape.getBackgroundColor().getRGB());
+			if (bgcolor.green+bgcolor.red-bgcolor.blue < 250) label.setForegroundColor(ColorConstants.white);
+			else {
+			    // TODO check this again
+				
+			    if (!isActive) {// || !isSrc) {
+					label.setForegroundColor(ColorConstants.lightGray);
+				} else {
+					label.setForegroundColor(ColorConstants.black);
+				}
+			}
+		} catch (Exception e) {
+			label.setForegroundColor(ColorConstants.black);
+		}
+	}
+	
+	protected void setLabelColor() {
+	    //setLabelColor(((StateNodeModel)getModel()).getParent()).isPreview());
+	    setLabelColor(!(((ViewModel)(((StateNodeModel)getModel())).getParent())).isPreview());
+	}
+	
+	protected void createEditPolicies() {
+		installEditPolicy(EditPolicy.COMPONENT_ROLE, new MyComponentEditPolicy());
+		//installEditPolicy(EditPolicy.GRAPHICAL_NODE_ROLE, new MyGraphicalNodeEditPolicy());
+	}
+	
+	protected void refreshVisuals() {
+		Rectangle constraint = ((StateNodeModel)getModel()).getConstraint();
+		((GraphicalEditPart)getParent()).setLayoutConstraint(this, getFigure(), constraint);
+		holder.setBounds(constraint);
+		shape.setBounds(constraint);
+		label.setBounds(constraint);				
+	}
+	
+	protected List getModelSourceConnections() {
+		return ((StateNodeModel)getModel()).getModelSourceConnections();
+	}
+	
+	protected List getModelTargetConnections() {
+		return ((StateNodeModel)getModel()).getModelTargetConnections();
+	}
+	
+	public String toString() {
+		String result = getClass().getName().toString() + ":" + ((StateNodeModel)getModel()).getId() + 
+			":\n\tsrc:" + getSourceConnections() + 
+			":\n\tdest:" + getTargetConnections();			
+		return result;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/SubConnectionEditPart.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/SubConnectionEditPart.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/SubConnectionEditPart.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/SubConnectionEditPart.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,99 @@
+/*
+ * Created on Oct 26, 2004
+ */
+package org.tekkotsu.ui.editor.editparts;
+
+import java.beans.PropertyChangeEvent;
+
+import org.eclipse.draw2d.BendpointConnectionRouter;
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.PolygonDecoration;
+import org.eclipse.swt.graphics.Color;
+import org.eclipse.ui.views.properties.IPropertyDescriptor;
+import org.eclipse.ui.views.properties.IPropertySource;
+import org.tekkotsu.ui.editor.BezierCurveConnection;
+import org.tekkotsu.ui.editor.TransitionConnection;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.SubConnectionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class SubConnectionEditPart extends MyAbstractConnectionEditPart implements IPropertySource {
+	//private BezierCurveConnection connection; // transition figure
+	private TransitionConnection connection; // transition figure
+	private PolygonDecoration arrowHead;
+	private Color color = null;
+	
+	protected IFigure createFigure() {		
+		SubConnectionModel model = (SubConnectionModel)this.getModel();
+		connection = new BezierCurveConnection();
+		//connection = new MyPolylineConnection();
+		connection.setConnectionRouter(new BendpointConnectionRouter());
+		connection.setLineWidth(model.getLineWidth());
+		if (SubConnectionModel.ARROW_ARROWHEAD.equals(model.getArrowType())) {
+			arrowHead = new PolygonDecoration();		
+			connection.setTargetDecoration(arrowHead);
+		}
+		
+		if (color==null) {
+			if (((SubConnectionModel)getModel()).isPreview()) {
+				connection.setForegroundColor(ColorConstants.lightGray);
+			} else {
+				connection.setForegroundColor(ColorConstants.black);
+			}
+		} else connection.setForegroundColor(color);
+		
+		return connection;
+	}
+	
+	/* (non-Javadoc)
+	 * @see java.beans.PropertyChangeListener#propertyChange(java.beans.PropertyChangeEvent)
+	 */
+	public void propertyChange(PropertyChangeEvent evt) {		
+		if (evt.getPropertyName().equals(SubConnectionModel.P_ARROWHEAD)) {
+			Object newVal = evt.getNewValue();
+			if (newVal.equals(SubConnectionModel.ARROW_NOHEAD)) {
+				connection.setTargetDecoration(null);
+			} else if (newVal.equals(SubConnectionModel.ARROW_ARROWHEAD)){
+				arrowHead = new PolygonDecoration();
+				connection.setTargetDecoration(arrowHead);
+			}
+		} else if (evt.getPropertyName().equals(SubConnectionModel.P_LINEWIDTH)) {
+			SubConnectionModel model = (SubConnectionModel)getModel();
+			connection.setLineWidth(model.getLineWidth());
+		} else if (evt.getPropertyName().equals(MultiTransitionModel.P_COLOR)) {
+			connection.setForegroundColor((Color)evt.getNewValue());
+			color = (Color)evt.getNewValue();
+		} else {
+			super.propertyChange(evt);
+		}
+	}
+	
+	public Object getEditableValue() {
+		return ((SubConnectionModel)getModel()).getParent().getEditableValue();
+	}
+	
+	public IPropertyDescriptor[] getPropertyDescriptors() {
+		return ((SubConnectionModel)getModel()).getParent().getPropertyDescriptors();		
+	}
+	
+	public Object getPropertyValue(Object id) {
+		return ((SubConnectionModel)getModel()).getParent().getPropertyValue(id);
+	}
+	
+	public boolean isPropertySet(Object id) {
+		return ((SubConnectionModel)getModel()).getParent().isPropertySet(id);		
+	}
+	
+	public void resetPropertyValue(Object id) {
+		((SubConnectionModel)getModel()).getParent().resetPropertyValue(id);
+	}
+	public void setPropertyValue(Object id, Object value) {
+		((SubConnectionModel)getModel()).getParent().setPropertyValue(id,value);
+	}
+
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/ViewEditPart.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/ViewEditPart.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/ViewEditPart.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editparts/ViewEditPart.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,41 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.editparts;
+
+/**
+ * @author asangpet
+ */
+
+import java.beans.PropertyChangeEvent;
+import java.util.List;
+
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Layer;
+import org.eclipse.draw2d.XYLayout;
+import org.eclipse.gef.EditPolicy;
+import org.tekkotsu.ui.editor.editpolicies.MyXYLayoutEditPolicy;
+import org.tekkotsu.ui.editor.model.ViewModel;
+
+public class ViewEditPart extends EditPartWithListener {
+	protected IFigure createFigure() {
+		Layer figure = new Layer();
+		figure.setLayoutManager(new XYLayout());
+		return figure;
+	}
+	
+	protected List getModelChildren() {
+		return ((ViewModel)getModel()).getPartChildrenNode();
+	}
+
+	protected void createEditPolicies() {
+		installEditPolicy(EditPolicy.LAYOUT_ROLE, new MyXYLayoutEditPolicy());
+	}
+	
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals(ViewModel.P_CHILDREN))
+			refreshChildren();
+		else if (evt.getPropertyName().equals(ViewModel.P_MODELSOURCE))
+			refreshVisuals();			
+	}	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyBendpointEditPolicy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyBendpointEditPolicy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyBendpointEditPolicy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyBendpointEditPolicy.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,68 @@
+/*
+ * Created on Dec 22, 2004
+ */
+package org.tekkotsu.ui.editor.editpolicies;
+
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.commands.Command;
+import org.eclipse.gef.editpolicies.BendpointEditPolicy;
+import org.eclipse.gef.requests.BendpointRequest;
+import org.tekkotsu.ui.editor.model.commands.CreateBendpointCommand;
+import org.tekkotsu.ui.editor.model.commands.DeleteBendpointCommand;
+import org.tekkotsu.ui.editor.model.commands.MoveBendpointCommand;
+import org.tekkotsu.ui.editor.resources.Debugger;
+
+/**
+ * @author asangpet
+ * 
+ */
+public class MyBendpointEditPolicy extends BendpointEditPolicy {
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.gef.editpolicies.BendpointEditPolicy#getCreateBendpointCommand(org.eclipse.gef.requests.BendpointRequest)
+	 */
+	protected Command getCreateBendpointCommand(BendpointRequest request) {
+		Point point = request.getLocation();
+		getConnection().translateToRelative(point);
+
+		CreateBendpointCommand command = new CreateBendpointCommand();
+		command.setLocation(point);
+		command.setConnection(getHost().getModel());
+		command.setIndex(request.getIndex());
+		Debugger.printDebug(Debugger.DEBUG_ALL,"create BEND POINT: "+getHost().getModel());
+
+		return command;
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.gef.editpolicies.BendpointEditPolicy#getDeleteBendpointCommand(org.eclipse.gef.requests.BendpointRequest)
+	 */
+	protected Command getDeleteBendpointCommand(BendpointRequest request) {
+	    DeleteBendpointCommand command = new DeleteBendpointCommand();
+	    command.setConnectionModel(getHost().getModel());
+	    command.setIndex(request.getIndex());
+	    return command;		
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.gef.editpolicies.BendpointEditPolicy#getMoveBendpointCommand(org.eclipse.gef.requests.BendpointRequest)
+	 */
+	protected Command getMoveBendpointCommand(BendpointRequest request) {
+		Point location = request.getLocation();
+		getConnection().translateToRelative(location);
+
+		MoveBendpointCommand command = new MoveBendpointCommand();
+		command.setConnectionModel(getHost().getModel());
+		command.setIndex(request.getIndex());
+		command.setNewLocation(location);
+
+		return command;
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyComponentEditPolicy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyComponentEditPolicy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyComponentEditPolicy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyComponentEditPolicy.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,22 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.editpolicies;
+
+import org.eclipse.gef.commands.Command;
+import org.eclipse.gef.editpolicies.ComponentEditPolicy;
+import org.eclipse.gef.requests.GroupRequest;
+import org.tekkotsu.ui.editor.model.commands.DeleteCommand;
+
+/**
+ * @author asangpet
+ */
+
+public class MyComponentEditPolicy extends ComponentEditPolicy {
+	protected Command createDeleteCommand(GroupRequest deleteReqeust) {
+		DeleteCommand command = new DeleteCommand();
+		command.setContentsModel(getHost().getParent().getModel());
+		command.setStateNodeModel(getHost().getModel());
+		return command;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEditPolicy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEditPolicy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEditPolicy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEditPolicy.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,24 @@
+/*
+ * Created on Sep 19, 2004
+ */
+package org.tekkotsu.ui.editor.editpolicies;
+
+import org.eclipse.gef.commands.Command;
+import org.eclipse.gef.editpolicies.ConnectionEditPolicy;
+import org.eclipse.gef.requests.GroupRequest;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+import org.tekkotsu.ui.editor.model.commands.DeleteConnectionCommand;
+/**
+ * @author asangpet
+ *
+ */
+public class MyConnectionEditPolicy extends ConnectionEditPolicy {
+
+	protected Command getDeleteCommand(GroupRequest request) {
+		DeleteConnectionCommand command = new DeleteConnectionCommand();
+		command.setConnectionModel(getHost().getModel());			
+		command.setContentsModel(((AbstractConnectionModel)(getHost().getModel())).getParent());
+		return command;
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEndpointEditPolicy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEndpointEditPolicy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEndpointEditPolicy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyConnectionEndpointEditPolicy.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,14 @@
+/*
+ * Created on Sep 19, 2004
+ */
+package org.tekkotsu.ui.editor.editpolicies;
+
+import org.eclipse.gef.editpolicies.ConnectionEndpointEditPolicy;
+
+/**
+ * @author asangpet
+ */
+public class MyConnectionEndpointEditPolicy extends
+		ConnectionEndpointEditPolicy {
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyGraphicalNodeEditPolicy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyGraphicalNodeEditPolicy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyGraphicalNodeEditPolicy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyGraphicalNodeEditPolicy.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,63 @@
+/*
+ * Created on Sep 18, 2004
+ */
+package org.tekkotsu.ui.editor.editpolicies;
+
+
+import org.eclipse.gef.commands.Command;
+import org.eclipse.gef.editpolicies.GraphicalNodeEditPolicy;
+import org.eclipse.gef.requests.CreateConnectionRequest;
+import org.eclipse.gef.requests.ReconnectRequest;
+import org.tekkotsu.ui.editor.model.commands.CreateConnectionCommand;
+import org.tekkotsu.ui.editor.model.commands.ReconnectConnectionCommand;
+import org.tekkotsu.ui.editor.resources.Debugger;
+/**
+ * @author asangpet
+ */
+public class MyGraphicalNodeEditPolicy extends GraphicalNodeEditPolicy {
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.gef.editpolicies.GraphicalNodeEditPolicy#getConnectionCompleteCommand(org.eclipse.gef.requests.CreateConnectionRequest)
+	 */
+	protected Command getConnectionCompleteCommand(
+			CreateConnectionRequest request) {
+		CreateConnectionCommand command =
+			(CreateConnectionCommand) request.getStartCommand();
+		command.setTarget(getHost().getModel());
+		command.setContentsModel(getHost().getParent().getModel());
+		Debugger.printDebug(Debugger.DEBUG_ALL,getHost().getParent().toString());
+		return command;
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.gef.editpolicies.GraphicalNodeEditPolicy#getConnectionCreateCommand(org.eclipse.gef.requests.CreateConnectionRequest)
+	 */
+	protected Command getConnectionCreateCommand(CreateConnectionRequest request) {
+		CreateConnectionCommand command = new CreateConnectionCommand();
+		command.setConnection(request.getNewObject());
+		command.setSource(getHost().getModel());		
+		request.setStartCommand(command);
+		return command;
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.gef.editpolicies.GraphicalNodeEditPolicy#getReconnectTargetCommand(org.eclipse.gef.requests.ReconnectRequest)
+	 */
+	protected Command getReconnectTargetCommand(ReconnectRequest request) {
+		ReconnectConnectionCommand command = new ReconnectConnectionCommand();
+		command.setConnectionModel(request.getConnectionEditPart().getModel());
+		command.setNewTarget(getHost().getModel());
+		return command;
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.gef.editpolicies.GraphicalNodeEditPolicy#getReconnectSourceCommand(org.eclipse.gef.requests.ReconnectRequest)
+	 */
+	protected Command getReconnectSourceCommand(ReconnectRequest request) {
+		ReconnectConnectionCommand command = new ReconnectConnectionCommand();
+		command.setConnectionModel(request.getConnectionEditPart().getModel());
+		command.setNewSource(getHost().getModel());
+		return command;		
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyXYLayoutEditPolicy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyXYLayoutEditPolicy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyXYLayoutEditPolicy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/editpolicies/MyXYLayoutEditPolicy.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,90 @@
+package org.tekkotsu.ui.editor.editpolicies;
+
+/**
+ * @author asangpet
+ */
+
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.gef.EditPart;
+import org.eclipse.gef.Request;
+import org.eclipse.gef.commands.Command;
+import org.eclipse.gef.editpolicies.XYLayoutEditPolicy;
+import org.eclipse.gef.requests.CreateRequest;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.editor.model.commands.ChangeConstraintCommand;
+import org.tekkotsu.ui.editor.model.commands.CreateCommand;
+import org.tekkotsu.ui.editor.model.commands.CreateMultiTransitionCommand;
+import org.tekkotsu.ui.editor.resources.Debugger;
+
+public class MyXYLayoutEditPolicy extends XYLayoutEditPolicy{
+	
+	public Command getCommand(Request request) {
+		Debugger.printDebug(Debugger.DEBUG_ALL, "XYLayoutEditPolicy getCommand() : "+request.getType());			
+		return super.getCommand(request);
+	}
+
+	protected Command createAddCommand(EditPart child, Object constraint) {
+		return null;
+	}
+
+	protected Command createChangeConstraintCommand(EditPart child, Object constraint) {
+		ChangeConstraintCommand command = new ChangeConstraintCommand();
+		command.setModel(child.getModel());
+		command.setConstraint((Rectangle) constraint);
+		
+		return command;
+	}
+	
+	protected Command getCreateCommand(CreateRequest request) {		
+		Debugger.printDebug(Debugger.DEBUG_ALL, "XYLayoutEditPolicy getCreateCommand() : "+request.getNewObjectType());
+		if (request.getNewObjectType().equals(StateNodeModel.class)) {
+			CreateCommand command = new CreateCommand();
+			Rectangle constraint = new Rectangle(0,0,50,20);
+			try {
+				constraint.setLocation(request.getLocation());
+				//constraint = (Rectangle) getConstraintFor(request);		
+			} catch (Exception e) {}
+			StateNodeModel model = (StateNodeModel)request.getNewObject();
+		
+			// check if the node is already present
+			if (((ViewModel)getHost().getModel()).getPartChild(model.getId()) != null) return null;			
+			
+			model.setConstraint(constraint);			
+			command.setContentsModel(getHost().getModel());
+			command.setStateNodeModel(model);			
+			return command;
+		} /* else if (request.getNewObjectType().equals(TransitionModel.class)){
+			CreateConnectionCommand command = new CreateConnectionCommand();
+			TransitionModel model = (TransitionModel)request.getNewObject();
+			if (((ViewModel)getHost().getModel()).getPartChild(model.getId()) != null) return null;									
+			command.setContentsModel(getHost().getModel());
+			command.setConnection(model);
+			command.setSource(request.getExtendedData().get("_source"));
+			//model.getSource());
+			command.setTarget(request.getExtendedData().get("_target"));
+			//model.getTarget());	
+			return command;
+		} */ else if (request.getNewObjectType().equals(MultiTransitionModel.class)) {			
+			CreateMultiTransitionCommand command = new CreateMultiTransitionCommand();
+			Rectangle constraint = new Rectangle(0,0,50,20);
+			try {
+				constraint.setLocation(request.getLocation());		
+			} catch (Exception e) {}
+			MultiTransitionModel model = (MultiTransitionModel)request.getNewObject();
+		
+			// check if the transition node is already present
+			if (((ViewModel)getHost().getModel()).getPartChild(model.getId()) != null) return null;			
+			model.setConstraint(constraint);			
+			command.setContentsModel(getHost().getModel());
+			command.setMultiTransitionModel(model);			
+			Debugger.printDebug(Debugger.DEBUG_ALL, "XYLayoutEditPolicy getCreateCommand() : CreateMultiTransitionCommand : "+command);
+			return command;			
+		} else return null;		
+	}
+	
+	protected Command getDeleteDependantCommand(Request request) {
+		return null;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/.cvsignore ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/.cvsignore
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/.cvsignore	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/.cvsignore	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1 @@
+Thumbs.db
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/IconDummy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/IconDummy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/IconDummy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/IconDummy.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,5 @@
+package org.tekkotsu.ui.editor.icons;
+
+public class IconDummy {
+
+}
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/arrowConnection.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/arrowConnection.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/chasingarrows.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/chasingarrows.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/editor.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/editor.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/newModel.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/newModel.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/pause_icon.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/pause_icon.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/resume_icon.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/resume_icon.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_media-pause.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_media-pause.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_media-pause.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_media-pause.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_reload.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_reload.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_shuffle.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_shuffle.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_shuffle.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/icons/stock_shuffle.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractConnectionModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractConnectionModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractConnectionModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractConnectionModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,84 @@
+/*
+ * Created on Sep 18, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import org.eclipse.draw2d.geometry.Point;
+
+/**
+ * @author asangpet
+ * 
+ */
+
+public abstract class AbstractConnectionModel extends AbstractModel {
+	private StateNodeModel source, target;
+
+	private List bendpoints = new ArrayList();
+
+	public static final String P_BEND_POINT = "_bend_point";
+
+	public void addBendpoint(int index, Point point) {
+		bendpoints.add(index, point);
+		firePropertyChange(P_BEND_POINT, null, null);
+	}
+
+	public List getBendpoints() {
+		return bendpoints;
+	}
+
+	public void removeBendpoint(int index) {
+		bendpoints.remove(index);
+		firePropertyChange(P_BEND_POINT, null, null);
+	}
+
+	public void replaceBendpoint(int index, Point point) {
+		bendpoints.set(index, point);
+		firePropertyChange(P_BEND_POINT, null, null);
+	}
+
+	public boolean isPreview() {
+		try {
+			return getParent().isPreview();
+		} catch (Exception e) {
+			return false;
+		}
+	}
+
+	public void attachSource() {
+		if (!source.getModelSourceConnections().contains(this))
+			source.addSourceConnection(this);
+	}
+
+	public void attachTarget() {
+		if (!target.getModelTargetConnections().contains(this))
+			target.addTargetConnection(this);
+	}
+
+	public void detachSource() {
+		source.removeSourceConnection(this);
+	}
+
+	public void detachTarget() {
+		target.removeTargetConnection(this);
+	}
+
+	public StateNodeModel getSource() {
+		return source;
+	}
+
+	public StateNodeModel getTarget() {
+		return target;
+	}
+
+	public void setSource(StateNodeModel model) {
+		source = model;
+	}
+
+	public void setTarget(StateNodeModel model) {
+		target = model;
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/AbstractModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,68 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+/**
+ * AbstractModel containing property control methods
+ * @author asangpet
+ */
+
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeSupport;
+
+import org.eclipse.ui.views.properties.IPropertyDescriptor;
+import org.eclipse.ui.views.properties.IPropertySource;
+import org.jdom.Content;
+
+abstract public class AbstractModel implements IPropertySource {
+	private PropertyChangeSupport listeners = new PropertyChangeSupport(this);
+	private AbstractModel parent;
+	
+	public void setParent(AbstractModel parent) {
+		this.parent = parent;
+	}
+	
+	public AbstractModel getParent() {
+		return parent;
+	}
+	
+	public void addPropertyChangeListener(PropertyChangeListener listener) {
+		listeners.addPropertyChangeListener(listener);
+	}
+	
+	public void firePropertyChange(String propName, Object oldValue, Object newValue) {
+		listeners.firePropertyChange(propName,oldValue,newValue);
+	}
+	
+	public void removePropertyChangeListener(PropertyChangeListener listener) {
+		listeners.removePropertyChangeListener(listener);
+	}
+	
+	public Object getEditableValue() {
+		return this;
+	}
+	
+	public IPropertyDescriptor[] getPropertyDescriptors() {
+		return new IPropertyDescriptor[0];
+	}
+	
+	public Object getPropertyValue(Object id) {
+		return null;
+	}
+	
+	public boolean isPropertySet(Object id) {
+		return false;
+	}
+	
+	abstract public boolean isPreview();
+	
+	public void resetPropertyValue(Object id) {}
+	public void setPropertyValue(Object id, Object value) {}
+	
+	/**
+	 * Generate XML code representation of this model
+	 * @return
+	 */
+	abstract public Content getXML();	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/MultiTransitionModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/MultiTransitionModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/MultiTransitionModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/MultiTransitionModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,276 @@
+/*
+ * Created on Oct 12, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.swt.graphics.RGB;
+import org.eclipse.ui.views.properties.IPropertyDescriptor;
+import org.eclipse.ui.views.properties.TextPropertyDescriptor;
+import org.jdom.Content;
+import org.jdom.Element;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * Multi-transition model, which actually looks like a node.
+ * 
+ * @author asangpet
+ */
+public class MultiTransitionModel extends StateNodeModel {
+	public static final String P_LINEWIDTH = "_linewidth";
+
+	protected int lineWidth = 1;
+
+	List subConnectionList = new ArrayList();
+
+	private MultiTransitionModel() {
+		super();
+		Debugger.printDebug(Debugger.DEBUG_ALL,
+				"execute MultiTransitionModel()");
+		setId("transition" + Integer.toString(stateID++));
+		setLabel(getId());
+		setShape(StateNodeModel.P_SHAPE_STYLE_ELLIPSE);
+		setColor(new RGB(0, 0, 0));
+	}
+
+	/* (non-Javadoc)
+	 * @see org.tekkotsu.ui.editor.model.StateNodeModel#setColor(org.eclipse.swt.graphics.RGB)
+	 */
+	public void setColor(RGB color) {		
+		super.setColor(color);
+		Iterator iter = subConnectionList.iterator();
+		while (iter.hasNext()) {
+			SubConnectionModel sub = (SubConnectionModel)iter.next();
+			sub.setColor(getColor());
+		}
+	}
+	
+	public MultiTransitionModel(Element xml, ViewModel parent) {
+		this();
+		Debugger.printDebug(Debugger.DEBUG_ALL, "execute MultiTransitionModel("
+				+ xml + "," + parent + ")");
+		if (IDTag.XML_transition_tag.equals(xml.getName())) {
+			try {
+				super.initModelConfig(xml, parent);
+				setId(xml.getAttributeValue(IDTag.XML_transition_id));
+				setLabel(xml.getAttributeValue(IDTag.XML_common_label));
+				SourceTransitionModel model = parent.getSourceModel()
+						.getTransition(this.getId());
+				setLineWidth(Integer.parseInt(xml
+						.getAttributeValue(IDTag.XML_transition_linewidth)));
+				initModel(model, parent);
+			} catch (Exception e) {
+				e.printStackTrace();
+			}
+		}
+	}
+
+	/**
+	 * A constructor which were used when user add transition to the layout
+	 * 
+	 * @param source
+	 *            Model source for this transition
+	 * @param parent
+	 *            View model which will contain this transition
+	 */
+	public MultiTransitionModel(SourceTransitionModel source, ViewModel parent) {
+		this();
+		Debugger.printDebug(Debugger.DEBUG_ALL, "execute MultiTransitionModel("
+				+ source + "," + parent + ")");
+		initModel(source, parent);
+	}
+
+	/**
+	 * Perform initial action after created the transition node. Attach all
+	 * available connection from source to transition node and from transition
+	 * node to destination
+	 */
+public void doPostAdd() {
+		doPreDelete((ViewModel) (this.getParent()));
+		/* Connect associate transition to multitransition node */
+		SourceTransitionModel source = (SourceTransitionModel) getSource();
+		ViewModel parent = (ViewModel) getParent();
+		subConnectionList = new ArrayList();
+
+		
+		if ((source.getSourceNodes().size() == 1) &&
+		  (source.getDestNodes().size()==1)) {
+			StateNodeModel sourceNode = (StateNodeModel) parent.getPartChild((String)source.getSourceNodes().get(0));
+			StateNodeModel destNode = (StateNodeModel)parent.getPartChild((String)source.getDestNodes().get(0));
+			SubConnectionModel connx = new SubConnectionModel(this, sourceNode,destNode, SubConnectionModel.ARROW_ARROWHEAD, lineWidth);
+			subConnectionList.add(connx);
+			if (!isPreview()) connx.setColor(this.getColor());
+			else connx.setColor(this.getPreviewColor());
+			return;
+		}
+		 
+
+		// generate src/target set.
+
+		// connect source node
+		Iterator iter = source.getSourceNodes().iterator();
+		while (iter.hasNext()) {
+			String srcId = (String) iter.next();
+			StateNodeModel sourceNode = (StateNodeModel) parent
+					.getPartChild(srcId);
+			if (sourceNode != null) {
+				SubConnectionModel inConnx = new SubConnectionModel(this,
+						sourceNode, this, SubConnectionModel.ARROW_NOHEAD,
+						lineWidth);
+				subConnectionList.add(inConnx);
+				// parent.addChild(inConnx);
+				if (!isPreview()) inConnx.setColor(this.getColor());
+				else inConnx.setColor(this.getPreviewColor());
+			}
+		}
+
+		// connect destination node
+		iter = source.getDestNodes().iterator();
+		while (iter.hasNext()) {
+			String srcId = (String) iter.next();
+			StateNodeModel destNode = (StateNodeModel) parent
+					.getPartChild(srcId);
+			if (destNode != null) {
+				SubConnectionModel outConnx = new SubConnectionModel(this,
+						this, destNode, lineWidth);
+				subConnectionList.add(outConnx);
+				// parent.addChild(outConnx);
+				if (!isPreview()) outConnx.setColor(this.getColor());
+				else outConnx.setColor(this.getPreviewColor());
+			}
+		}
+		// }
+	}
+	/**
+	 * Perform finalize action before removal of transition node. (Detach all
+	 * available connections from the content)
+	 * 
+	 * @param contents
+	 */
+	public void doPreDelete(ViewModel contents) {
+		List subConn = new ArrayList();
+		subConn.addAll(subConnectionList);
+		for (Iterator iter = subConn.iterator(); iter.hasNext();) {
+			SubConnectionModel model = (SubConnectionModel) iter.next();
+			Debugger.printDebug(Debugger.DEBUG_ALL, ("Detach " + model));
+			model.detachSource();
+			model.detachTarget();
+			// contents.removeChild(model);
+		}
+	}
+	
+	public void removeSubConnection(SubConnectionModel model) {
+		subConnectionList.remove(model);		
+	}
+
+	/**
+	 * @return Returns the lineWidth.
+	 */
+	public int getLineWidth() {
+		return lineWidth;
+	}
+
+	public IPropertyDescriptor[] getPropertyDescriptors() {
+		IPropertyDescriptor[] parentDesc = super.getPropertyDescriptors();
+		ArrayList list = new ArrayList();
+		for (int i = 0; i < parentDesc.length; i++)
+			list.add(parentDesc[i]);
+		list.add(new TextPropertyDescriptor(P_LINEWIDTH, "Line width"));
+		return (IPropertyDescriptor[]) list.toArray(new IPropertyDescriptor[1]);
+	}
+
+	public Object getPropertyValue(Object id) {
+		if (id.equals(P_LINEWIDTH)) {
+			return String.valueOf(getLineWidth());
+		} else
+			return super.getPropertyValue(id);
+	}
+
+	/**
+	 * @return Returns the subConnectionList.
+	 */
+	public List getSubConnectionList() {
+		return subConnectionList;
+	}
+
+	public Content getXML() {
+		Element content = new Element(IDTag.XML_transition_tag);
+		content.setAttribute(IDTag.XML_state_id, getId());
+		if (getSource().getClassName() != null)
+			content.setAttribute(IDTag.XML_state_class, getSource()
+					.getClassName());
+		content.setAttribute(IDTag.XML_state_label, getLabel());
+		content.setAttribute(IDTag.XML_state_color, IDTag.RGB2Tag(getRGB()));
+		Rectangle rect = getConstraint();
+		content.setAttribute(IDTag.XML_state_top, "" + rect.y);
+		content.setAttribute(IDTag.XML_state_left, "" + rect.x);
+		content.setAttribute(IDTag.XML_state_width, "" + rect.width);
+		content.setAttribute(IDTag.XML_state_height, "" + rect.height);
+		content.setAttribute(IDTag.XML_state_shape, getShape());
+		content.setAttribute(IDTag.XML_transition_linewidth, "" + lineWidth);
+		return content;
+	}
+
+	public void initModel(SourceTransitionModel source, ViewModel parent) {
+		setShape(StateNodeModel.P_SHAPE_STYLE_ELLIPSE);
+		setId(source.getId());
+		//setLabel(source.getId());
+
+		super.setSource(source);
+		Debugger.printDebug(Debugger.DEBUG_ALL, "src:"
+				+ source.getSourceNodes());
+		Debugger
+				.printDebug(Debugger.DEBUG_ALL, "dest:" + source.getDestNodes());
+
+		// setConstraint(new Rectangle(0,0,0,0));
+	}
+
+	public boolean isPropertySet(Object id) {
+		return id.equals(P_LINEWIDTH) || super.isPropertySet(id);
+	}
+
+	/**
+	 * @param lineWidth
+	 *            The lineWidth to set.
+	 */
+	public void setLineWidth(int lineWidth) {
+		this.lineWidth = lineWidth;
+		firePropertyChange(P_LINEWIDTH, null, new Integer(lineWidth));
+	}
+
+	public void setPropertyValue(Object id, Object value) {
+		if (id.equals(P_LINEWIDTH)) {
+			setLineWidth(Integer.parseInt(value.toString()));
+		} else
+			super.setPropertyValue(id, value);
+	}
+
+	public boolean isSingleTransition() {
+		SourceTransitionModel source = (SourceTransitionModel) getSource();
+		return source.getSourceNodes().size() == 1
+				&& source.getDestNodes().size() == 1;
+	}
+	
+	public void activate() {
+		super.activate();
+		Iterator iter = subConnectionList.iterator();
+		while (iter.hasNext()) {
+			SubConnectionModel sub = (SubConnectionModel)iter.next();
+			sub.firePropertyChange(MultiTransitionModel.P_COLOR,null,this.getColor());
+		}				
+	}
+
+	public void deactivate() {
+		super.deactivate();
+		Iterator iter = subConnectionList.iterator();
+		while (iter.hasNext()) {
+			SubConnectionModel sub = (SubConnectionModel)iter.next();
+			sub.firePropertyChange(MultiTransitionModel.P_COLOR,null,this.getPreviewColor());
+		}						
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceModel.java	2005-09-29 22:01:27.000000000 -0400
@@ -0,0 +1,169 @@
+/*
+ * Created on Oct 4, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import java.io.BufferedOutputStream;
+import java.io.File;
+import java.io.FileOutputStream;
+import java.io.Reader;
+import java.util.ArrayList;
+import java.util.HashMap;
+import java.util.Iterator;
+import java.util.List;
+import java.util.Map;
+
+import org.eclipse.core.runtime.IPath;
+import org.jdom.Document;
+import org.jdom.Element;
+import org.jdom.input.SAXBuilder;
+import org.jdom.output.Format;
+import org.jdom.output.XMLOutputter;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * This class represents the organization of model file
+ * @author asangpet
+ */
+public class SourceModel {
+	List nodes = new ArrayList();
+	List transitions = new ArrayList();
+	
+	Map nodeMap = new HashMap();
+	Map transitionMap = new HashMap();
+	
+	IPath sourcePath = null;
+	
+	public SourceModel(IPath sourceFile) {
+		setSourcePath(sourceFile);
+	}
+	
+	public SourceModel() {}
+	
+	public void createModel(Element xml) {
+		try {
+			nodeMap = new HashMap();
+			transitionMap = new HashMap();
+			nodes = new ArrayList();
+			transitions = new ArrayList();
+			if ("model".equals(xml.getName())) {
+				Iterator iter = xml.getDescendants();
+				while (iter.hasNext()) {					
+					Object next = iter.next();					
+					if (next instanceof Element) {
+						Element child = (Element) next;
+						if (IDTag.XML_state_tag.equals(child.getName())) {							
+							SourceNodeModel temp = new SourceNodeModel(child,this);
+							nodes.add(temp);
+							nodeMap.put(temp.getId(),temp);
+						} else if (IDTag.XML_transition_tag.equals(child.getName())) {
+							SourceTransitionModel temp = new SourceTransitionModel(child);
+							transitions.add(new SourceTransitionModel(child));				
+							transitionMap.put(temp.getId(),temp);
+						}
+					}
+				}
+			}
+		} catch (Exception e) {
+			e.printStackTrace();
+		}		
+	}
+	
+	public SourceNodeModel getNode(String id) {
+		return (SourceNodeModel)nodeMap.get(id);
+	}
+	
+	public SourceTransitionModel getTransition(String id) {
+		return (SourceTransitionModel)transitionMap.get(id);
+	}
+	
+	public SourceObjectModel getChild(String id) {
+		SourceObjectModel result = (SourceObjectModel)nodeMap.get(id);
+		if (nodeMap.get(id)!=null) return result;
+		else return (SourceObjectModel)transitionMap.get(id);
+	}
+	
+	public List getNodes() {
+		return nodes;
+	}
+	
+	public List getTransitions() {
+		return transitions;
+	}
+	/**
+	 * @return Returns the sourcePath.
+	 */
+	public IPath getSourcePath() {
+		return sourcePath;
+	}
+	
+	public boolean setSourcePath(IPath path) {
+		this.sourcePath = path;
+		
+		SAXBuilder builder = new SAXBuilder();
+		try {
+			Document sourcedoc = builder.build(path.toFile());
+			createModel(sourcedoc.getRootElement());
+			return true;
+		} catch (Exception e) {
+		    // attempt to create new model file
+		    this.doSave();
+			// error reading input file
+			//e.printStackTrace();
+		}		
+		return false;
+	}
+
+	public void setSourceInput(Reader reader) {
+		SAXBuilder builder = new SAXBuilder();
+		try {
+			Document sourcedoc = builder.build(reader);
+			createModel(sourcedoc.getRootElement());	
+		} catch (Exception e) {
+			// error reading input file
+			e.printStackTrace();
+		}				
+	}
+	
+	public void doSave(IPath outputPath) {
+		try {
+			Document doc = new Document();			
+			doc.addContent(getXML());
+		
+			XMLOutputter outputter = new XMLOutputter(Format.getPrettyFormat());
+			Debugger.printDebug(Debugger.DEBUG_ALL,"Attempting to create "+outputPath);
+			BufferedOutputStream ostream = new BufferedOutputStream(new FileOutputStream(outputPath.toOSString()));
+			outputter.output(doc,ostream);
+
+			ostream.close();
+		} catch (Exception e) {
+			//e.printStackTrace();
+		}
+	}
+	
+	public void doSave() {
+		doSave(this.getSourcePath());
+	}
+	
+	public Element getXML() {
+		Element content = new Element("model");
+		
+		List nodes = getNodes();
+		List transitions = getTransitions();
+
+		Iterator iter = nodes.iterator();
+		while (iter.hasNext()) {
+			SourceNodeModel nodeModel = (SourceNodeModel)iter.next();
+			content.addContent(nodeModel.getXML());
+		}
+		
+		iter = transitions.iterator();
+		while (iter.hasNext()) {
+			SourceTransitionModel transModel = (SourceTransitionModel)iter.next();
+			content.addContent(transModel.getXML());
+		}
+		return content;
+	}
+	
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceNodeModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceNodeModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceNodeModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceNodeModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,53 @@
+/*
+ * Created on Oct 11, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import org.eclipse.gef.requests.CreationFactory;
+import org.jdom.Element;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * @author asangpet
+ */
+public class SourceNodeModel extends SourceObjectModel {
+	SourceModel parent;
+	
+	public SourceNodeModel(Element xml, SourceModel parent) {
+		if (IDTag.XML_state_tag.equals(xml.getName())) {
+			String idTag = xml.getAttributeValue(IDTag.XML_state_id); 
+			if (!((idTag == null) || (idTag.equals("")))) setId(idTag);			
+			setClassName(xml.getAttributeValue(IDTag.XML_state_class));
+			this.parent = parent;
+		}		
+	}
+		
+	public CreationFactory getFactory() {
+		return new SourceNodeCreationFactory(this);
+	}
+	
+	public Element getXML() {
+		Element content = new Element("state");
+		content.setAttribute("id",this.getId());
+		content.setAttribute("class",this.getClassName());
+		return content;
+	}
+	
+	public SourceModel getParentModel() {
+		return parent;
+	}
+}
+
+class SourceNodeCreationFactory implements CreationFactory {
+	private SourceNodeModel model;
+	
+	public SourceNodeCreationFactory(SourceNodeModel model) {
+		this.model = model;
+	}
+	public Object getNewObject() {
+		return new StateNodeModel(model);
+	}
+	public Object getObjectType() {
+		return StateNodeModel.class;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceObjectModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceObjectModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceObjectModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceObjectModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,44 @@
+/*
+ * Created on Oct 11, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+/**
+ * @author asangpet
+ */
+public class SourceObjectModel {
+	private String id;
+	private String className;
+	
+	public SourceObjectModel() {}
+	
+	public SourceObjectModel(String id, String className) {
+		setClassName(className);
+		setId(id);
+	}
+	
+	/**
+	 * @return Returns the className.
+	 */
+	public String getClassName() {
+		return className;
+	}
+	/**
+	 * @param className The className to set.
+	 */
+	public void setClassName(String className) {
+		this.className = className;
+	}
+	/**
+	 * @return Returns the id.
+	 */
+	public String getId() {
+		return id;
+	}
+	/**
+	 * @param id The id to set.
+	 */
+	public void setId(String id) {
+		this.id = id;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceTransitionModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceTransitionModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceTransitionModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SourceTransitionModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,134 @@
+/*
+ * Created on Oct 11, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.gef.requests.CreationFactory;
+import org.jdom.Element;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * This is the source model for associated MultiTransitionModel
+ * @author asangpet
+ */
+public class SourceTransitionModel extends SourceObjectModel {
+	String type;
+	List sourceNodes = new ArrayList();
+	List destNodes = new ArrayList();
+	
+	public SourceTransitionModel(Element xml) {
+		if (IDTag.XML_transition_tag.equals(xml.getName())) {
+			try {
+				setId(xml.getAttributeValue(IDTag.XML_transition_id));
+				setType(xml.getAttributeValue(IDTag.XML_transition_type));
+				setClassName(xml.getAttributeValue(IDTag.XML_transition_class));
+				
+				// iterate through children to get source/dest nodes
+				Iterator iter = xml.getChildren().iterator();
+				while (iter.hasNext()) {
+					Element child = (Element)(iter.next());
+					if (child.getName().equals(IDTag.XML_transition_source)) {
+						sourceNodes.add(child.getTextTrim());						
+					} else if (child.getName().equals(IDTag.XML_transition_dest)) {
+						destNodes.add(child.getTextTrim());
+					}
+				}
+			} catch (Exception e) {
+				e.printStackTrace();
+			}
+		}	
+	}
+	
+	
+	/**
+	 * @return true if the transition is multi-transition, otherwise, return false
+	 */
+	public boolean isMultiTransition() {
+		return (sourceNodes.size()>1) || (destNodes.size()>1);
+	}
+
+	/**
+	 * @return Returns the destNodes.
+	 */
+	public List getDestNodes() {
+		return destNodes;
+	}
+	/**
+	 * @return Returns the sourceNodes.
+	 */
+	public List getSourceNodes() {
+		return sourceNodes;
+	}
+
+	/**
+	 * @return Returns the type.
+	 */
+	public String getType() {
+		return type;
+	}
+	
+	/**
+	 * @param type The type to set.
+	 */
+	public void setType(String type) {
+		this.type = type;
+	}
+	
+	public CreationFactory getFactory(ViewModel viewmodel) {
+		return new SourceTransitionCreationFactory(this, viewmodel);
+	}
+
+	public Element getXML() {
+		Element content = new Element(IDTag.XML_transition_tag);
+		content.setAttribute(IDTag.XML_common_id,this.getId());
+		content.setAttribute(IDTag.XML_common_class,this.getClassName());
+		
+		Iterator iter = getSourceNodes().iterator();
+		while (iter.hasNext()) {
+			Element node = new Element(IDTag.XML_transition_source);
+			node.setText((String)iter.next());	
+			content.addContent(node);
+		}
+		iter = getDestNodes().iterator();
+		while (iter.hasNext()) {
+			Element node = new Element(IDTag.XML_transition_dest);
+			node.setText((String)iter.next());		
+			content.addContent(node);
+		}
+		
+		return content;
+	}	
+}
+
+
+class SourceTransitionCreationFactory implements CreationFactory {
+	private SourceTransitionModel model;
+	private ViewModel viewModel;
+	
+	public SourceTransitionCreationFactory(SourceTransitionModel model, ViewModel viewModel) {
+		this.model = model;
+		this.viewModel = viewModel;
+	}
+	public Object getNewObject() {
+		return new MultiTransitionModel(model,viewModel);
+		/*
+		if ((model.sourceNodes.size()>1) || (model.destNodes.size()>1))
+			return new MultiTransitionModel(model,viewModel);
+		else
+			return new TransitionModel(model,viewModel);
+		*/	
+	}
+	public Object getObjectType() {
+		return MultiTransitionModel.class;
+		/*
+		if ((model.sourceNodes.size()>1) || (model.destNodes.size()>1))		
+			return MultiTransitionModel.class;
+		else
+			return TransitionModel.class;
+		*/
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/StateNodeModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/StateNodeModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/StateNodeModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/StateNodeModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,475 @@
+package org.tekkotsu.ui.editor.model;
+
+/**
+ * @author asangpet
+ */
+
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ColorRegistry;
+import org.eclipse.swt.graphics.Color;
+import org.eclipse.swt.graphics.RGB;
+import org.eclipse.ui.views.properties.ColorPropertyDescriptor;
+import org.eclipse.ui.views.properties.ComboBoxPropertyDescriptor;
+import org.eclipse.ui.views.properties.IPropertyDescriptor;
+import org.eclipse.ui.views.properties.TextPropertyDescriptor;
+import org.jdom.Content;
+import org.jdom.Element;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+public class StateNodeModel extends AbstractModel
+{
+    public static final String P_CLASS = "_class";
+
+    public static final String P_COLOR = "_color";
+
+    public static final String P_BLEND_COLOR = "_blend_color";
+
+    public static final String P_CONSTRAINT = "_constraint";
+
+    public static final String P_ID = "_id";
+
+    public static final String P_INTRANS = "_intrans";
+
+    public static final String P_OUTTRANS = "_outtrans";
+
+    public static final String P_LABEL = "_label";
+
+    public static final String P_SHAPE = "_shape";
+
+    public static final String P_SHAPE_STYLE_ELLIPSE = "Ellipse";
+
+    public static final String P_SHAPE_STYLE_RECTANGLE = "Rectangle";
+
+    public static final String P_SHAPE_STYLE_ROUNDED_RECTANGLE = "Rounded Rectangle";
+
+    public static final String P_SHAPE_STYLE_HEXAGON = "Hexagon";
+
+    public static final String P_SOURCE_CONNECTION = "_source_connection";
+
+    public static final String P_TARGET_CONNECTION = "_target_connection";
+
+    public static final String P_ACTIVATE = "_state_activate";
+
+    public static final String P_DEACTIVATE = "_state_deactivate";
+
+    private static final String[] shapeValues = { P_SHAPE_STYLE_RECTANGLE,
+            P_SHAPE_STYLE_ELLIPSE, P_SHAPE_STYLE_ROUNDED_RECTANGLE,
+            P_SHAPE_STYLE_HEXAGON };
+
+    public static int stateID = 1;
+
+    private ColorRegistry colorRegistry = new ColorRegistry();
+
+    private Rectangle constraint;
+
+    private String id = "State";
+
+    private String label = "State";
+
+    private String shape = P_SHAPE_STYLE_RECTANGLE;
+
+    private int shapeIndex = 0;
+
+    private SourceObjectModel source;
+
+    protected List sourceConnections = new ArrayList();
+
+    protected List targetConnections = new ArrayList();
+
+    public StateNodeModel()
+    {
+        super();
+        Debugger.printDebug(Debugger.DEBUG_ALL, "execute StateNodeModel()");
+        setId("state" + Integer.toString(stateID++));
+        setLabel(getId());
+    }
+
+    public StateNodeModel(Element xml, ViewModel parent)
+    {
+        this();
+        Debugger.printDebug(Debugger.DEBUG_ALL, "execute StateNodeModel(" + xml
+                + "," + "parent)");
+        if (IDTag.XML_state_tag.equals(xml.getName()))
+        {
+            initModelConfig(xml, parent);
+        }
+    }
+
+    private static final Color[] colorArray = { ColorConstants.red,
+            ColorConstants.blue, ColorConstants.orange, ColorConstants.green,              
+            ColorConstants.cyan, ColorConstants.lightGreen };
+
+    public StateNodeModel(SourceNodeModel source)
+    {
+        this();
+        Debugger.printDebug(Debugger.DEBUG_ALL, "execute StateNodeModel("
+                + source + ")");
+        setId(source.getId());
+        setLabel(source.getId());
+        setSource(source);
+
+        SourceModel parent = source.getParentModel();
+        int numState = parent.getNodes().size();
+        //java.awt.Color color =
+        // java.awt.Color.getHSBColor((float)((1.0*stateID %
+        // numState)/numState),.99f,.8f);
+        Color color = colorArray[stateID % colorArray.length];
+        RGB rgb = new RGB(color.getRed(), color.getGreen(), color.getBlue());
+        colorRegistry.put("Color" + stateID, rgb);
+        setColor(colorRegistry.getRGB("Color" + stateID));
+        //setColor(ColorConstants.yellow.getRGB());
+    }
+
+    public void verifySource(SourceModel src)
+    {
+        Debugger.printDebug(Debugger.DEBUG_ALL, "Verify src:" + id + ":"
+                + src.getNode(id));
+        if (src.getChild(id) == null)
+        {
+            this.firePropertyChange(ViewModel.P_SOURCE_EXIST, null,
+                    new Boolean(false));
+        }
+        else
+        {
+            this.firePropertyChange(ViewModel.P_SOURCE_EXIST, null,
+                    new Boolean(true));
+        }
+    }
+
+    public void doPostAdd()
+    {
+        ViewModel parent = (ViewModel) getParent();
+        List children = new ArrayList();
+        children.addAll(parent.getPartChildren());
+        Iterator iter = children.iterator();
+        while (iter.hasNext())
+        {
+            AbstractModel model = (AbstractModel) (iter.next());
+            if (model instanceof MultiTransitionModel)
+            {
+                ((MultiTransitionModel) model).doPostAdd();
+            }
+        }
+    }
+
+    public boolean isPreview()
+    {
+        return ((ViewModel) getParent()).isPreview();
+    }
+
+    public void addSourceConnection(Object connx)
+    {
+        sourceConnections.add(connx);
+        firePropertyChange(P_SOURCE_CONNECTION, null, null);
+    }
+
+    public void addTargetConnection(Object connx)
+    {
+        targetConnections.add(connx);
+        firePropertyChange(P_TARGET_CONNECTION, null, null);
+    }
+
+    public Color getColor()
+    {
+        return colorRegistry.get(P_COLOR);
+    }
+
+    public Color getPreviewColor()
+    {
+        return colorRegistry.get(P_BLEND_COLOR);
+    }
+
+    public Rectangle getConstraint()
+    {
+        return constraint;
+    }
+
+    /**
+     * @return Returns the id.
+     */
+    public String getId()
+    {
+        return id;
+    }
+
+    public String getLabel()
+    {
+        return label;
+    }
+
+    public List getModelSourceConnections()
+    {
+        return sourceConnections;
+    }
+
+    public List getModelTargetConnections()
+    {
+        return targetConnections;
+    }
+
+    public IPropertyDescriptor[] getPropertyDescriptors()
+    {
+        TextPropertyDescriptor idProp = new TextPropertyDescriptor(P_ID, "ID");
+        TextPropertyDescriptor classProp = new TextPropertyDescriptor(P_CLASS,
+                "Class");
+        TextPropertyDescriptor intransProp = new TextPropertyDescriptor(
+                P_INTRANS, "InTrans");
+        TextPropertyDescriptor outtransProp = new TextPropertyDescriptor(
+                P_OUTTRANS, "OutTrans");
+
+        String modelCat = "Info";
+        idProp.setCategory(modelCat);
+        classProp.setCategory(modelCat);
+        intransProp.setCategory(modelCat);
+        outtransProp.setCategory(modelCat);
+
+        IPropertyDescriptor[] descriptors = new IPropertyDescriptor[] { idProp,
+                classProp, intransProp, outtransProp,
+                new TextPropertyDescriptor(P_LABEL, "Label"),
+                new ColorPropertyDescriptor(P_COLOR, "Color"),
+                new ComboBoxPropertyDescriptor(P_SHAPE, "Shape", shapeValues) };
+        return descriptors;
+    }
+
+    public Object getPropertyValue(Object id)
+    {
+        if (id.equals(P_ID))
+        {
+            return getId();
+        }
+        else if (id.equals(P_CLASS))
+        {
+            if (getSource() != null) return getSource().getClassName();
+        }
+        else if (id.equals(P_LABEL))
+        {
+            return getLabel();
+        }
+        else if (id.equals(P_COLOR))
+        {
+            return getRGB();
+        }
+        else if (id.equals(P_SHAPE))
+        {
+            return new Integer(shapeIndex);
+        }
+        else if (id.equals(P_OUTTRANS))
+        {
+            return sourceConnections.toString();
+        }
+        else if (id.equals(P_INTRANS)) { return targetConnections.toString(); }
+        return null;
+    }
+
+    public RGB getRGB()
+    {
+        return colorRegistry.getRGB(P_COLOR);
+    }
+
+    /**
+     * @return Returns the shape.
+     */
+    public String getShape()
+    {
+        return shape;
+    }
+
+    /**
+     * @return Returns the source.
+     */
+    public SourceObjectModel getSource()
+    {
+        return source;
+    }
+
+    public Content getXML()
+    {
+        Element content = new Element(IDTag.XML_state_tag);
+        content.setAttribute(IDTag.XML_state_id, getId());
+        //content.setAttribute(IDTag.XML_state_class,getSource().getClassName());
+        content.setAttribute(IDTag.XML_state_label, getLabel());
+        content.setAttribute(IDTag.XML_state_color, IDTag.RGB2Tag(getRGB()));
+        Rectangle rect = getConstraint();
+        content.setAttribute(IDTag.XML_state_top, "" + rect.y);
+        content.setAttribute(IDTag.XML_state_left, "" + rect.x);
+        content.setAttribute(IDTag.XML_state_width, "" + rect.width);
+        content.setAttribute(IDTag.XML_state_height, "" + rect.height);
+        content.setAttribute(IDTag.XML_state_shape, getShape());
+
+        return content;
+    }
+
+    protected void initModelConfig(Element xml, ViewModel parent)
+    {
+        String idTag = xml.getAttributeValue(IDTag.XML_common_id);
+        if (!((idTag == null) || (idTag.equals("")))) setId(idTag);
+        setSource(parent.getSourceModel().getChild(idTag));
+
+        if (xml.getAttributeValue(IDTag.XML_common_label) == null)
+            setLabel(getId());
+        else
+            setLabel(xml.getAttributeValue(IDTag.XML_common_label));
+
+        RGB color = IDTag
+                .Tag2RGB(xml.getAttributeValue(IDTag.XML_common_color));
+        setColor(color);
+        try
+        {
+            int y = xml.getAttribute(IDTag.XML_common_top).getIntValue();
+            int x = xml.getAttribute(IDTag.XML_common_left).getIntValue();
+            int width = xml.getAttribute(IDTag.XML_common_width).getIntValue();
+            int height = xml.getAttribute(IDTag.XML_common_height)
+                    .getIntValue();
+
+            constraint = new Rectangle(x, y, width, height);
+            setConstraint(constraint);
+        }
+        catch (Exception e)
+        {
+            e.printStackTrace();
+        }
+        try
+        {
+            setShape(xml.getAttributeValue(IDTag.XML_state_shape));
+        }
+        catch (Exception e)
+        {
+        }
+    }
+
+    public boolean isPropertySet(Object id)
+    {
+        if (id.equals(P_LABEL) || id.equals(P_COLOR) || id.equals(P_SHAPE))
+                return true;
+        return false;
+    }
+
+    public void removeSourceConnection(Object connx)
+    {
+        sourceConnections.remove(connx);
+        firePropertyChange(P_SOURCE_CONNECTION, null, null);
+    }
+
+    public void removeTargetConnection(Object connx)
+    {
+        targetConnections.remove(connx);
+        firePropertyChange(P_TARGET_CONNECTION, null, null);
+    }
+
+    private int getBlendColor(int oldValue)
+    {
+        int newCol = (int) Math.round((double) oldValue * 0.2) + 200;
+        return (newCol > 255) ? 255 : newCol;
+    }
+
+    public void setColor(RGB color)
+    {
+        colorRegistry.put(P_COLOR, color);
+        colorRegistry.put(P_BLEND_COLOR, new RGB(getBlendColor(color.red),
+                getBlendColor(color.green), getBlendColor(color.blue)));
+        firePropertyChange(P_COLOR, null, getColor());
+    }
+
+    public void setConstraint(Rectangle rect)
+    {
+        constraint = rect;
+        firePropertyChange(P_CONSTRAINT, null, constraint);
+    }
+
+    public void setId(String text)
+    {
+        this.id = text;
+    }
+
+    public void setLabel(String text)
+    {
+        this.label = text;
+        firePropertyChange(P_LABEL, null, text);
+    }
+
+    public void setPropertyValue(Object id, Object value)
+    {
+        if (id.equals(P_ID))
+        {
+            setId((String) value);
+        }
+        else if (id.equals(P_CLASS))
+        {
+            //setClassName((String)value);
+        }
+        else if (id.equals(P_LABEL))
+        {
+            setLabel((String) value);
+        }
+        else if (id.equals(P_COLOR))
+        {
+            setColor((RGB) value);
+            Debugger
+                    .printDebug(Debugger.DEBUG_ALL, value.getClass().toString());
+        }
+        else if (id.equals(P_SHAPE))
+        {
+            setShapeIndex(((Integer) value).intValue());
+        }
+    }
+
+    /**
+     * @param shape
+     *            The shape to set.
+     */
+    public void setShape(String shape)
+    {
+        // verify shape style
+        if (!shape.equals(shapeValues[shapeIndex]))
+        {
+            for (int i = 0; i < shapeValues.length; i++)
+                if (shapeValues[i].equals(shape))
+                {
+                    shapeIndex = i;
+                    break;
+                }
+        }
+        if (!shape.equals(shapeValues[shapeIndex])) return;
+
+        this.shape = shape;
+        firePropertyChange(P_SHAPE, null, shape);
+    }
+
+    public void setShapeIndex(int index)
+    {
+        shapeIndex = index;
+        setShape(shapeValues[index]);
+    }
+
+    /**
+     * @param source
+     *            The source to set.
+     */
+    public void setSource(SourceObjectModel source)
+    {
+        this.source = source;
+    }
+
+    public String toString()
+    {
+        //return getClass().getSimpleName() + ":" + this.getId();
+        return this.getId();
+    }
+
+    public void activate()
+    {
+        this.firePropertyChange(StateNodeModel.P_ACTIVATE, null, null);
+    }
+
+    public void deactivate()
+    {
+        this.firePropertyChange(StateNodeModel.P_DEACTIVATE, null, null);
+    }
+
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SubConnectionModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SubConnectionModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SubConnectionModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/SubConnectionModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,79 @@
+/*
+ * Created on Oct 26, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import org.eclipse.swt.graphics.Color;
+import org.jdom.Content;
+
+/**
+ * @author asangpet
+ *
+ */
+public class SubConnectionModel extends AbstractConnectionModel {
+	public static final String P_ARROWHEAD = "_arrowhead";
+	public static final String P_LINEWIDTH = "_linewidth";
+	public static final String ARROW_ARROWHEAD = "_arrow_head";
+	public static final String ARROW_NOHEAD = "_arrow_nohead";	
+	
+	private String arrowType;
+	private int lineWidth;
+	
+	
+	public SubConnectionModel(AbstractModel parent, StateNodeModel source, StateNodeModel dest) {
+		this(parent ,source, dest, ARROW_ARROWHEAD, 1);		
+	}
+
+	public SubConnectionModel(AbstractModel parent, StateNodeModel source, StateNodeModel dest, int lineWidth) {
+		this(parent ,source, dest, ARROW_ARROWHEAD, lineWidth);		
+	}
+
+	public SubConnectionModel(AbstractModel parent, StateNodeModel source, StateNodeModel dest, String arrowType, int lineWidth) {
+		setParent(parent);
+		this.arrowType = arrowType;
+		this.lineWidth = lineWidth;
+		setSource(source);
+		setTarget(dest);
+		attachSource();
+		attachTarget();
+	}
+	
+	/* (non-Javadoc)
+	 * @see org.tekkotsu.ui.editor.model.AbstractModel#getXML()
+	 */
+	public Content getXML() {
+		return null;
+	}
+
+	/**
+	 * @return Returns the arrowType.
+	 */
+	public String getArrowType() {
+		return arrowType;
+	}
+	/**
+	 * @param arrowType The arrowType to set.
+	 */
+	public void setArrowType(String arrowType) {
+		this.arrowType = arrowType;
+		firePropertyChange(P_ARROWHEAD, null, arrowType);
+	}
+	
+	public void setLineWidth(int width) {
+		lineWidth = width;
+		firePropertyChange(P_LINEWIDTH, null, new Integer(width));
+	}
+	
+	public int getLineWidth() {
+		return lineWidth;
+	}
+	
+	public String toString() {
+		//return "SubConnectionModel<"+this.getSource()+","+this.getTarget()+">";
+		return this.getSource()+"->"+this.getTarget();
+	}
+	
+	public void setColor(Color color) {
+		firePropertyChange(MultiTransitionModel.P_COLOR,null,color);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/TransitionModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/TransitionModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/TransitionModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/TransitionModel.java	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,228 @@
+/*
+ * Created on Sep 18, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import org.eclipse.ui.views.properties.ComboBoxPropertyDescriptor;
+import org.eclipse.ui.views.properties.IPropertyDescriptor;
+import org.eclipse.ui.views.properties.TextPropertyDescriptor;
+import org.jdom.Content;
+import org.jdom.Element;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * This model currently represent a single link between nodes.
+ * However, actual transition is a state node with associated connection model connect to it.
+ * The model is implemented in MultiTransitionModel.
+ * @author asangpet
+ */
+public class TransitionModel extends AbstractConnectionModel {
+	public static final String P_ID = "_tid";
+	public static final String P_LABEL = "_label";
+	public static final String P_VISIBLE = "_visible";
+	public static final String P_CLASS = "_class";
+	public static final String P_LINEWIDTH = "_linewidth";
+	
+	private String id = "", label = "";
+	private boolean visible = true;
+	private static int transitionID = 1;
+	private int lineWidth = 1;
+	private SourceObjectModel sourceModel = null;
+	
+	public TransitionModel() {
+		super();				
+		this.id = "trans"+Integer.toString(transitionID++);
+	}
+	
+	public TransitionModel(SourceTransitionModel source, ViewModel parent) {
+		super();
+		this.setId(source.getId());
+		this.setVisible(true);
+		StateNodeModel sourceNode = (StateNodeModel)parent.getPartChild((String)source.getSourceNodes().get(0));
+		StateNodeModel destNode = (StateNodeModel)parent.getPartChild((String)source.getDestNodes().get(0));
+		setSourceModel(source);
+		setSource(sourceNode);
+		setTarget(destNode);
+		attachSource();
+		attachTarget();
+	}
+	
+	public TransitionModel(StateNodeModel source, StateNodeModel dest, String id) {
+		this.setId(id);
+		this.setVisible(true);
+		setSource(source);
+		setTarget(dest);
+		attachSource();
+		attachTarget();		
+	}
+
+	public TransitionModel(Element xml, ViewModel parent) {
+		this();		
+		if (IDTag.XML_transition_tag.equals(xml.getName())) {			
+			try {
+				setId(xml.getAttributeValue(IDTag.XML_common_id));
+				SourceTransitionModel model = parent.getSourceModel().getTransition(this.getId());
+				StateNodeModel source = (StateNodeModel)parent.getPartChild((String)model.getSourceNodes().get(0));
+				StateNodeModel dest = (StateNodeModel)parent.getPartChild((String)model.getDestNodes().get(0));
+				setLabel(xml.getAttributeValue(IDTag.XML_common_label));				
+				
+				try {
+					setLineWidth(Integer.parseInt(xml.getAttributeValue(IDTag.XML_transition_linewidth)));
+				} catch (NumberFormatException e) {}
+				
+				setSourceModel(model);
+				setSource(source);
+				setTarget(dest);
+				attachSource();
+				attachTarget();
+				if ("false".equals(xml.getAttributeValue(IDTag.XML_transition_visible))) setVisible(false);
+			} catch (Exception e) {
+				e.printStackTrace();		
+			}			
+		}
+	}
+	
+	public String getId() { 
+		return id;
+	}
+	
+	public void setId(String name) {
+		this.id = name;
+		firePropertyChange(P_ID, null, name);
+	}
+
+	public void verifySource(SourceModel src) {
+		Debugger.printDebug(Debugger.DEBUG_ALL,"Verify src:"+id+":"+src.getNode(id));
+		if (src.getChild(id)==null) {
+			this.firePropertyChange(ViewModel.P_SOURCE_EXIST,null,new Boolean(false));
+		} else {
+			this.firePropertyChange(ViewModel.P_SOURCE_EXIST,null,new Boolean(true));
+		}
+	}
+	
+	public IPropertyDescriptor[] getPropertyDescriptors() {
+		TextPropertyDescriptor idProp = new TextPropertyDescriptor(P_ID,"ID");
+		TextPropertyDescriptor classProp = new TextPropertyDescriptor(P_CLASS,"Class");
+		String modelCat = "Info";
+		idProp.setCategory(modelCat);
+		classProp.setCategory(modelCat);
+
+		String[] visibleValues = {"True","False"};
+		
+		IPropertyDescriptor[] descriptors =
+			new IPropertyDescriptor[] {
+				idProp,
+				classProp,
+				new TextPropertyDescriptor(P_LABEL,"Label"),
+				new TextPropertyDescriptor(P_LINEWIDTH,"Line width"),
+				new ComboBoxPropertyDescriptor(P_VISIBLE,"Visible",visibleValues)};
+		return descriptors;
+	}
+	
+	public Object getPropertyValue(Object id) {
+		if (id.equals(P_ID)) {
+			return getId();
+		} else if (id.equals(P_VISIBLE)) {
+			if (visible) return new Integer(0);
+			else return new Integer(1);
+		} else if (id.equals(P_CLASS)) {
+			try {
+				return getSourceModel().getClassName();
+			} catch (Exception e) { return ""; }
+		} else if (id.equals(P_LABEL)) {
+			return getLabel();
+		} else if (id.equals(P_LINEWIDTH)) {
+			return String.valueOf(getLineWidth());
+		}
+		return null;
+	}
+	
+	public boolean isPropertySet(Object id) {
+		if (id.equals(P_VISIBLE) || id.equals(P_LABEL) || id.equals(P_LINEWIDTH))
+			return true;		
+		return false;
+	}
+	
+	public void setPropertyValue(Object id, Object value) {
+		if (id.equals(P_VISIBLE)) {
+			if (value.equals(new Integer(0)))
+				setVisible(true);
+			else
+				setVisible(false);
+		} else if (id.equals(P_LABEL)) {
+			setLabel(value.toString());
+		} else if (id.equals(P_LINEWIDTH)) {
+			setLineWidth(Integer.parseInt(value.toString()));
+		}
+	}
+	
+	public Content getXML() {
+		try {
+			Element content = new Element(IDTag.XML_transition_tag);
+			content.setAttribute(IDTag.XML_transition_id,getId());
+			content.setAttribute(IDTag.XML_transition_visible,Boolean.toString(isVisible()));
+			content.setAttribute(IDTag.XML_common_label,getLabel());
+			content.setAttribute(IDTag.XML_transition_linewidth,Integer.toString(getLineWidth()));
+			return content;
+		} catch (Exception e) {
+			return null;
+		}
+	}
+	/**
+	 * @return Returns the visibility property.
+	 */
+	public boolean isVisible() {
+		return visible;
+	}
+	/**
+	 * @param visible Set visibility value.
+	 */
+	public void setVisible(boolean visible) {
+		this.visible = visible;
+		firePropertyChange(P_VISIBLE,null,Boolean.valueOf(visible));
+	}
+	/**
+	 * @return Returns the sourceModel of this transition.
+	 */
+	public SourceObjectModel getSourceModel() {
+		return sourceModel;
+	}
+	/**
+	 * @param sourceModel set sourceModel for this transition.
+	 */
+	public void setSourceModel(SourceObjectModel sourceModel) {
+		this.sourceModel = sourceModel;
+	}
+	/**
+	 * @return Returns the label.
+	 */
+	public String getLabel() {
+		return label;
+	}
+	/**
+	 * @param label The label to set.
+	 */
+	public void setLabel(String label) {
+		if (label == null) this.label="";
+		else this.label = label;
+		firePropertyChange(P_LABEL,null,this.label);
+	}
+	/**
+	 * @return Returns the lineWidth.
+	 */
+	public int getLineWidth() {
+		return lineWidth;
+	}
+	/**
+	 * @param lineWidth The lineWidth to set.
+	 */
+	public void setLineWidth(int lineWidth) {
+		this.lineWidth = lineWidth;
+		firePropertyChange(P_LINEWIDTH, null, new Integer(lineWidth));
+	}
+	
+	public String toString() {
+		return this.getClass().toString() + ":" + getId();
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/ViewModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/ViewModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/ViewModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/ViewModel.java	2006-02-14 00:22:32.000000000 -0500
@@ -0,0 +1,399 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.model;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.io.File;
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.core.runtime.Path;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.widgets.FileDialog;
+import org.eclipse.ui.IEditorSite;
+import org.eclipse.ui.IWorkbench;
+import org.eclipse.ui.views.properties.IPropertyDescriptor;
+import org.eclipse.ui.views.properties.TextPropertyDescriptor;
+import org.jdom.Content;
+import org.jdom.Document;
+import org.jdom.Element;
+import org.tekkotsu.ui.editor.StateMachineEditor;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.editor.resources.IDTag;
+
+/**
+ * Parent model for all contents, representing the view
+ * 
+ * @author asangpet
+ */
+
+public class ViewModel extends AbstractModel implements PropertyChangeListener {
+	public static final String P_CHILDREN = "_children";
+
+	public static final String P_EXECUTION_TRACE = "_trace";
+
+	public static final String P_MODELSOURCE = "_source";
+
+	public static final String P_SOURCE_EXIST = "_view_source_exist";
+
+	public static final String P_ACTIVATE_CHANGE = "_activation_change";
+
+	public static final String P_EDITING_MODE = "_editing_mode";
+
+	// this list contains all edit part children
+	// (state+transition+subconnection)
+	private List editPartChildren = new ArrayList();
+
+	private boolean previewMode = false;
+
+	private SourceModel sourceModel;
+
+	private String tracePath = null;
+
+	private IPath path = null;
+	private StateMachineEditor editor = null;
+	
+	public ViewModel(IPath path) {
+		super();
+		this.setPath(path);
+	}
+	
+	public void setEditor(StateMachineEditor editor) {
+		this.editor = editor;
+	}
+	
+	public void setPreview(boolean preview) {
+		previewMode = preview;
+		// reactivate all nodes
+		if (!previewMode) {
+			// activate new nodes
+			List value = this.getPartChildrenNode();
+			Iterator iter = value.iterator();
+			Debugger.printDebug(Debugger.DEBUG_ALL,"Activate(for editing) " + value);
+			while (iter.hasNext()) {
+				Object child = this.getPartChild(iter.next().toString());
+				if (child instanceof StateNodeModel) {
+					StateNodeModel state = (StateNodeModel) child;
+					state.activate();
+				}
+			}
+		}
+	}
+
+	public boolean isPreview() {
+		return previewMode;
+	}
+	
+	public ViewModel(IEditorSite site, Element xml, IPath path) {
+		super();
+		setPath(path);
+		try {
+			if ("view".equals(xml.getName())) {
+				String sourcePath = xml
+						.getAttributeValue(IDTag.XML_view_modelsource);
+				if (sourcePath != null) {				
+					Path modelPath = new Path(sourcePath);
+					File file = modelPath.toFile();//new File((getAbsolutePath(path, sourcePath)).toOSString());								
+					while (!file.exists()) {
+						// file not found, ask for source path						
+						String[] filterExtensions = { "*.tsm", "*.*" };
+						FileDialog fileDialog = new FileDialog(site.getShell(), SWT.OPEN);
+						fileDialog.setText("Cannot find model source");
+						fileDialog.setFilterExtensions(filterExtensions);
+						sourcePath = fileDialog.open();					
+						modelPath = new Path(sourcePath);
+						file = modelPath.toFile();
+					}
+					this.setModelSource(sourcePath);
+					//this.sourceModel = new SourceModel(); //getRelativePath(sourcePath));
+					//this.sourceModel.setSourcePath(modelPath); //getRelativePath(sourcePath));					
+				}
+				
+				Iterator iter = xml.getDescendants();
+				while (iter.hasNext()) {
+					Object next = iter.next();
+					if (next instanceof Element) {
+						Element child = (Element) next;
+						if (IDTag.XML_state_tag.equals(child.getName())) {
+							if (sourceModel.getNode(child
+									.getAttributeValue(IDTag.XML_common_id)) != null)
+								this.addChild(new StateNodeModel(child, this));
+						} else if (IDTag.XML_transition_tag.equals(child
+								.getName())) {
+							try {
+								String transId = child
+										.getAttributeValue(IDTag.XML_transition_id);
+								MultiTransitionModel multiNode = new MultiTransitionModel(
+										child, this);
+								this.addChild(multiNode);
+								multiNode.doPostAdd();
+								/*
+								 * if
+								 * (sourceModel.getTransition(transId).isMultiTransition() ) {
+								 * MultiTransitionModel multiNode = new
+								 * MultiTransitionModel(child, this);
+								 * this.addChild(multiNode);
+								 * multiNode.doPostAdd(); //this.addChild(new
+								 * MultiTransitionModel(child,this)); } else {
+								 * this.addChild(new
+								 * TransitionModel(child,this)); }
+								 */
+							} catch (Exception e) {
+								System.err
+										.println("Found incompatible view :"
+												+ child
+														.getAttributeValue(IDTag.XML_transition_id));
+							}
+						}
+					}
+				}
+			}
+		} catch (Exception e) {
+			//e.printStackTrace();
+		}
+	}
+
+	public void verifySource() {
+		List children = this.getPartChildren();
+		Iterator iter = children.iterator();
+		SourceModel source = this.getSourceModel();
+		while (iter.hasNext()) {
+			Object next = iter.next();
+			if (next instanceof StateNodeModel) {
+				((StateNodeModel) next).verifySource(source);
+			} 
+		}
+	}
+
+	public void addChild(Object child) {
+		((AbstractModel) child).setParent(this);
+		editPartChildren.add(child);
+		firePropertyChange(P_CHILDREN, null, null);
+	}
+
+	public List getPartChildren() {
+		return editPartChildren;
+	}
+
+	public List getPartChildrenNode() {
+		List nodes = new ArrayList();
+		Iterator iter = editPartChildren.iterator();
+		while (iter.hasNext()) {
+			Object next = iter.next();
+			if (next instanceof StateNodeModel) {
+				nodes.add(next);
+			}
+		}
+		return nodes;
+	}
+
+	/**
+	 * Search for a specific child model
+	 * 
+	 * @param id
+	 *            String identification of the model
+	 * @return Return a child model of this content
+	 */
+	public Object getPartChild(String id) {
+		Iterator iter = getPartChildren().iterator();
+		while (iter.hasNext()) {
+			Object nextModel = iter.next();
+			if (nextModel instanceof StateNodeModel) {
+				StateNodeModel model = (StateNodeModel) nextModel;
+				if (id.equals(model.getId()))
+					return model;
+			} /*
+				 * else if (nextModel instanceof TransitionModel) {
+				 * TransitionModel model = (TransitionModel)nextModel; if
+				 * (id.equals(model.getId())) return model; }
+				 */
+		}
+		return null;
+	}
+
+	public void removeChild(Object child) {
+		editPartChildren.remove(child);
+		firePropertyChange(P_CHILDREN, null, null);
+	}
+
+	/*
+	public static IPath getAbsolutePath(IPath refPath, String inPath) {
+	    IPath viewPath = refPath.removeLastSegments(1);
+	    Path path = new Path(inPath);
+	    if ((path.getDevice()!=null) && (!viewPath.getDevice().equals(path.getDevice()))) {
+	        return path.makeAbsolute();
+	    }
+	    int match = path.matchingFirstSegments(viewPath);
+	    IPath result = viewPath.append(path.removeFirstSegments(match)).makeAbsolute();
+	    return result;		
+	}
+	
+	public static IPath getRelativePath(IPath refPath, String inPath) {
+	    Path path = new Path(inPath);
+	    IPath viewPath = refPath.removeLastSegments(1);
+	    String pathDevice = ""+path.getDevice();
+	    String viewPathDevice = ""+viewPath.getDevice();
+	    if (path.isAbsolute() && (pathDevice.equals(viewPathDevice))) {
+	        int match = path.matchingFirstSegments(viewPath);	        
+	        if (match==0) return path;
+	        return path.setDevice(null).removeFirstSegments(match);
+	    } else return path;		
+	}
+	
+	public IPath getRelativePath(String inPath) {
+		return getRelativePath(this.getPath(), inPath);
+	}
+	*/
+	
+	public Content getXML() {
+		Element content = new Element(IDTag.XML_view_tag);
+		if (this.sourceModel == null)
+			content.setAttribute(IDTag.XML_view_modelsource, "");
+		else {
+			content.setAttribute(IDTag.XML_view_modelsource, this.sourceModel.getSourcePath().toString());//getRelativePath(this.sourceModel.getSourcePath().toString()).toString());
+		}
+		List children = getPartChildren();
+		List transitions = new ArrayList();
+
+		Iterator iter = children.iterator();
+		while (iter.hasNext()) {
+			AbstractModel childModel = (AbstractModel) iter.next();
+			if (childModel instanceof MultiTransitionModel) {
+				transitions.add(childModel);
+			} else {
+				Content child = childModel.getXML();
+				if (child != null)
+					content.addContent(child);
+			}
+		}
+
+		iter = transitions.iterator();
+		while (iter.hasNext()) {
+			AbstractModel childModel = (AbstractModel) iter.next();
+			Content child = childModel.getXML();
+			if (child != null)
+				content.addContent(child);
+		}
+		return content;
+	}
+
+	/**
+	 * @return Returns model source.
+	 */
+	public SourceModel getSourceModel() {
+		if (sourceModel == null) {
+			sourceModel = new SourceModel();
+		}
+		return sourceModel;
+	}
+
+	/**
+	 * @param modelSource
+	 *            File name of model source to set.
+	 */
+	public void setModelSource(String modelSource) {
+	    IPath path = new Path(modelSource);
+		if (sourceModel == null)
+			this.sourceModel = new SourceModel(path);
+		this.sourceModel.setSourcePath(path);
+		
+		firePropertyChange(P_MODELSOURCE, null, sourceModel.getSourcePath());
+	}
+
+	public void setTracePath(String tracePath) {
+		this.tracePath = tracePath;
+		firePropertyChange(P_EXECUTION_TRACE, null, tracePath);
+	}
+
+	public void setModelSource(SourceModel modelSource) {
+		this.sourceModel = modelSource;
+	}
+
+	public IPropertyDescriptor[] getPropertyDescriptors() {
+		IPropertyDescriptor[] descriptors = new IPropertyDescriptor[] { new TextPropertyDescriptor(
+				P_MODELSOURCE, "Model source") };
+		return descriptors;
+	}
+
+	public Object getPropertyValue(Object id) {
+		if (id.equals(P_MODELSOURCE)) {
+			return sourceModel.getSourcePath();
+		}
+		return null;
+	}
+
+	public void setPropertyValue(Object id, Object value) {
+		if (id.equals(P_MODELSOURCE))
+			setModelSource((String) value);
+	}
+
+	public boolean isPropertySet(Object id) {
+		if (id.equals(P_MODELSOURCE))
+			return true;
+		else
+			return false;
+	}
+
+	/**
+	 * @return Returns the tracePath.
+	 */
+	public String getTracePath() {
+		return tracePath;
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see java.beans.PropertyChangeListener#propertyChange(java.beans.PropertyChangeEvent)
+	 */
+	public void propertyChange(PropertyChangeEvent evt) {		
+		if (evt.getPropertyName().equals(ViewModel.P_ACTIVATE_CHANGE)) {
+			if (this.isPreview()) {
+				// deactivate nodes
+				Iterator iter = this.getPartChildrenNode().iterator();
+				while (iter.hasNext()) {
+					Object child = iter.next();
+					if (child instanceof StateNodeModel) {
+						StateNodeModel state = (StateNodeModel) child;
+						state.deactivate();
+					}
+				}
+
+				// activate new nodes
+				List value = (List) evt.getNewValue();
+				iter = value.iterator();
+				Debugger.printDebug(Debugger.DEBUG_ALL,"Activate " + value);
+				while (iter.hasNext()) {
+					Object child = this.getPartChild(iter.next().toString());
+					if (child instanceof StateNodeModel) {
+						StateNodeModel state = (StateNodeModel) child;
+						state.activate();
+					}
+				}
+			}
+		} else if (evt.getPropertyName().equals(ViewModel.P_EDITING_MODE)) {
+			// activate new nodes
+			List value = this.getPartChildrenNode();
+			Iterator iter = value.iterator();
+			Debugger.printDebug(Debugger.DEBUG_ALL,"Activate(for editing) " + value);
+			while (iter.hasNext()) {
+				Object child = this.getPartChild(iter.next().toString());
+				if (child instanceof StateNodeModel) {
+					StateNodeModel state = (StateNodeModel) child;
+					state.activate();
+				}
+			}
+		}
+	}
+    public IPath getPath() {
+        return path;
+    }
+    public void setPath(IPath path) {
+        this.path = path;
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ChangeConstraintCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ChangeConstraintCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ChangeConstraintCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ChangeConstraintCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,34 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+
+/**
+ * @author asangpet
+ */
+public class ChangeConstraintCommand extends Command {
+	private StateNodeModel stateModel;
+	private Rectangle constraint;
+	private Rectangle oldConstraint;
+	
+	public void execute() {
+		stateModel.setConstraint(constraint);
+	}
+	
+	public void setConstraint(Rectangle rect) {
+		constraint = rect;
+	}
+	
+	public void setModel(Object model) {
+		stateModel = (StateNodeModel) model;
+		oldConstraint = stateModel.getConstraint();
+	}
+	
+	public void undo() {
+		stateModel.setConstraint(oldConstraint);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateBendpointCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateBendpointCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateBendpointCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateBendpointCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,38 @@
+/*
+ * Created on Dec 22, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class CreateBendpointCommand extends Command {
+	  private AbstractConnectionModel connection;
+	  private Point location;
+	  private int index;
+
+	  public void execute() {
+	    connection.addBendpoint(index, location);
+	  }
+
+	  public void setConnection(Object model) {
+	    connection = (AbstractConnectionModel) model;
+	  }
+
+	  public void setIndex(int i) {
+	    index = i;
+	  }
+
+	  public void setLocation(Point point) {
+	    location = point;
+	  }
+
+	  public void undo() {
+	    connection.removeBendpoint(index);
+	  }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,55 @@
+/*
+ * Created on Sep 13, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+
+/**
+ * @author asangpet
+ */
+public class CreateCommand extends Command {
+	private ViewModel contentsModel;
+	private StateNodeModel stateNodeModel;
+	
+	public void execute() {		
+		contentsModel.addChild(stateNodeModel);		
+		stateNodeModel.doPostAdd();
+	}
+	
+	public void setContentsModel(Object model) {
+		contentsModel = (ViewModel) model;
+	}
+	
+	public void setStateNodeModel(Object model) {
+		stateNodeModel = (StateNodeModel) model;
+	}
+		
+	public void undo() {
+		contentsModel.removeChild(stateNodeModel);
+		List sourceConnections = new ArrayList();
+		List targetConnections = new ArrayList();
+		sourceConnections.addAll(stateNodeModel.getModelSourceConnections());
+		targetConnections.addAll(stateNodeModel.getModelTargetConnections());		
+		for (Iterator iter = sourceConnections.iterator(); iter.hasNext();) {
+			AbstractConnectionModel model = (AbstractConnectionModel)iter.next();
+			model.detachSource();
+			model.detachTarget();
+			contentsModel.removeChild(model);
+		}
+
+		for (Iterator iter = targetConnections.iterator(); iter.hasNext();) {
+			AbstractConnectionModel model = (AbstractConnectionModel)iter.next();
+			model.detachSource();
+			model.detachTarget();
+			contentsModel.removeChild(model);
+		}		
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateConnectionCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateConnectionCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateConnectionCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateConnectionCommand.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,61 @@
+/*
+ * Created on Sep 18, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.editor.resources.Debugger;
+
+/**
+ * @author asangpet
+ */
+public class CreateConnectionCommand extends Command {
+	private StateNodeModel source, target;
+	private AbstractConnectionModel connection;
+	private ViewModel contentsModel;
+	
+	public void setContentsModel(Object model) {
+		contentsModel = (ViewModel) model;
+	}
+	
+	public boolean canExecute() {
+		if (source == null || target == null)
+			return false;
+		if (source.equals(target))
+			return false;
+		return true;
+	}
+	
+	/**
+	 * Attach source/target and connection model to content model
+	 */
+	public void execute() {
+		Debugger.printDebug(Debugger.DEBUG_ALL,"Create connection command executed");
+		connection.attachSource();
+		connection.attachTarget();
+		contentsModel.addChild(connection);
+	}
+	
+	public void setConnection(Object model) {
+		connection = (AbstractConnectionModel) model;
+	}
+	
+	public void setSource(Object model) {
+		source = (StateNodeModel) model;
+		connection.setSource(source);
+	}
+	
+	public void setTarget(Object model) {
+		target = (StateNodeModel) model;
+		connection.setTarget(target);
+	}
+	
+	public void undo() {
+		connection.detachSource();
+		connection.detachTarget();
+		contentsModel.removeChild(connection);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateMultiTransitionCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateMultiTransitionCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateMultiTransitionCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/CreateMultiTransitionCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,40 @@
+/*
+ * Created on Oct 24, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import java.util.ArrayList;
+import java.util.List;
+
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class CreateMultiTransitionCommand extends Command {
+	private ViewModel contentsModel;
+	private MultiTransitionModel model;
+	private List sourceConnections = new ArrayList();
+	private List targetConnections = new ArrayList();
+	
+	public void execute() {		
+		contentsModel.addChild(model);
+		model.doPostAdd();		
+	}
+	
+	public void setContentsModel(Object model) {
+		contentsModel = (ViewModel) model;
+	}
+	
+	public void setMultiTransitionModel(Object model) {
+		this.model = (MultiTransitionModel)model;		
+	}
+		
+	public void undo() {
+		model.doPreDelete(contentsModel);
+		contentsModel.removeChild(model);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteBendpointCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteBendpointCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteBendpointCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteBendpointCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,35 @@
+/*
+ * Created on Dec 22, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class DeleteBendpointCommand extends Command {
+	  private AbstractConnectionModel connection;
+	  private Point oldLocation; 
+	  private int index;
+	  
+	  public void execute() {
+	    oldLocation = (Point) connection.getBendpoints().get(index);
+	    connection.removeBendpoint(index);
+	  }
+
+	  public void setConnectionModel(Object model) {
+	    connection = (AbstractConnectionModel) model;
+	  }
+
+	  public void setIndex(int i) {
+	    index = i;
+	  }
+
+	  public void undo() {
+	    connection.addBendpoint(index, oldLocation);
+	  }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,81 @@
+/*
+ * Created on Sep 12, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+
+/**
+ * @author asangpet
+ */
+
+public class DeleteCommand extends Command {
+	private ViewModel contentsModel;
+	private StateNodeModel stateNodeModel;
+	private List sourceConnections = new ArrayList();
+	private List targetConnections = new ArrayList();
+	
+	public void execute() {
+		if (stateNodeModel instanceof MultiTransitionModel) {
+			((MultiTransitionModel)stateNodeModel).doPreDelete(contentsModel);
+		} else {
+			sourceConnections.addAll(stateNodeModel.getModelSourceConnections());
+			targetConnections.addAll(stateNodeModel.getModelTargetConnections());		
+			for (Iterator iter = sourceConnections.iterator(); iter.hasNext();) {
+				AbstractConnectionModel model = (AbstractConnectionModel)iter.next();
+				DeleteConnectionCommand delComm = new DeleteConnectionCommand();
+				delComm.setConnectionModel(model);
+				delComm.setContentsModel(contentsModel);
+				delComm.execute();
+			}
+
+			for (Iterator iter = targetConnections.iterator(); iter.hasNext();) {
+				AbstractConnectionModel model = (AbstractConnectionModel)iter.next();
+				DeleteConnectionCommand delComm = new DeleteConnectionCommand();
+				delComm.setConnectionModel(model);
+				delComm.setContentsModel(contentsModel);
+				delComm.execute();
+			}
+		}
+		contentsModel.removeChild(stateNodeModel);
+	}
+	
+	public void setContentsModel(Object model) {
+		contentsModel = (ViewModel) model;		
+	}
+	
+	public void setStateNodeModel(Object model) {
+		stateNodeModel = (StateNodeModel) model;
+	}
+	
+	public void undo() {
+		contentsModel.addChild(stateNodeModel);
+
+		if (stateNodeModel instanceof MultiTransitionModel) {
+			((MultiTransitionModel)stateNodeModel).doPostAdd();
+		} else {
+			for (Iterator iter = sourceConnections.iterator(); iter.hasNext();) {
+				AbstractConnectionModel model = (AbstractConnectionModel)iter.next();
+				model.attachSource();
+				model.attachTarget();
+			}
+
+			for (Iterator iter = targetConnections.iterator(); iter.hasNext();) {
+				AbstractConnectionModel model = (AbstractConnectionModel)iter.next();
+				model.attachSource();
+				model.attachTarget();
+			}
+		
+			sourceConnections.clear();
+			targetConnections.clear();
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteConnectionCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteConnectionCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteConnectionCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/DeleteConnectionCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,56 @@
+/*
+ * Created on Sep 19, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.SubConnectionModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+
+/**
+ * @author asangpet
+ */
+public class DeleteConnectionCommand extends Command {
+	private AbstractConnectionModel connection;
+	private ViewModel contentsModel;
+	
+	public void execute() {
+		connection.detachSource();
+		connection.detachTarget();
+		contentsModel.removeChild(connection);
+				
+		if (connection.getParent() instanceof MultiTransitionModel) {			
+			MultiTransitionModel parent = (MultiTransitionModel)connection.getParent();
+			parent.removeSubConnection((SubConnectionModel)connection);
+			if (parent.getSubConnectionList().size()==0) {
+				// no more subconnection, remove multitransition node too
+				contentsModel.removeChild(parent);
+			}
+		}
+	}
+	
+	public void setConnectionModel(Object model) {
+		connection = (AbstractConnectionModel) model;
+	}
+	
+	public void setContentsModel(Object model) {
+		if (model instanceof ViewModel)
+			contentsModel = (ViewModel) model;
+		else if (model instanceof MultiTransitionModel) {
+			contentsModel = (ViewModel) ((MultiTransitionModel)model).getParent();
+		}
+	}
+	
+	public void undo() {
+		MultiTransitionModel parent = (MultiTransitionModel) connection.getParent();
+		if (!contentsModel.getPartChildren().contains(parent)) {
+			contentsModel.addChild(connection.getParent());
+			parent.doPostAdd();
+		}
+		contentsModel.addChild(connection);
+		connection.attachSource();
+		connection.attachTarget();
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/MoveBendpointCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/MoveBendpointCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/MoveBendpointCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/MoveBendpointCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,39 @@
+/*
+ * Created on Dec 22, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class MoveBendpointCommand extends Command {
+	  private AbstractConnectionModel connection;
+	  private Point oldLocation, newLocation;
+	  private int index;
+
+	  public void execute() {
+	    oldLocation = (Point) connection.getBendpoints().get(index);
+	    connection.replaceBendpoint(index, newLocation);
+	  }
+
+	  public void setConnectionModel(Object model) {
+	    connection = (AbstractConnectionModel) model;
+	  }
+
+	  public void setIndex(int i) {
+	    index = i;
+	  }
+
+	  public void setNewLocation(Point point) {
+	    newLocation = point;
+	  }
+
+	  public void undo() {
+	    connection.replaceBendpoint(index, oldLocation);
+	  }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ReconnectConnectionCommand.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ReconnectConnectionCommand.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ReconnectConnectionCommand.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/commands/ReconnectConnectionCommand.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,67 @@
+/*
+ * Created on Sep 21, 2004
+ */
+package org.tekkotsu.ui.editor.model.commands;
+
+import org.eclipse.gef.commands.Command;
+import org.tekkotsu.ui.editor.model.AbstractConnectionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+
+/**
+ * @author asangpet
+ */
+public class ReconnectConnectionCommand extends Command {
+	private AbstractConnectionModel connection;
+
+	private StateNodeModel newSource = null;
+
+	private StateNodeModel newTarget = null;
+
+	private StateNodeModel oldSource = null;
+
+	private StateNodeModel oldTarget = null;
+
+	public void execute() {
+		if (newSource != null) {
+			oldSource = connection.getSource();
+			reconnectSource(newSource);
+		}
+		if (newTarget != null) {
+			oldTarget = connection.getTarget();
+			reconnectTarget(newTarget);
+		}
+	}
+
+	private void reconnectSource(StateNodeModel source) {
+		connection.detachSource();
+		connection.setSource(source);
+		connection.attachSource();
+	}
+
+	private void reconnectTarget(StateNodeModel target) {
+		connection.detachTarget();
+		connection.setTarget(target);
+		connection.attachTarget();
+	}
+
+	public void setConnectionModel(Object model) {
+		connection = (AbstractConnectionModel) model;
+	}
+
+	public void setNewSource(Object model) {
+		newSource = (StateNodeModel) model;
+	}
+
+	public void setNewTarget(Object model) {
+		newTarget = (StateNodeModel) model;
+	}
+
+	public void undo() {
+		if (oldSource != null)
+			reconnectSource(oldSource);
+		if (oldTarget != null)
+			reconnectTarget(oldTarget);
+		oldSource = null;
+		oldTarget = null;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/example.tsm ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/example.tsm
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/example.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/example.tsm	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,57 @@
+WalkToTargetNode (no subnodes) http://tekkotsu.no-ip.org/dox/classWalkToTargetNode.html
+!msg spider  Walk To Target (ball)
+WalkToTargetNode Walk To Target (ball) @ 0x61412450
+
+<model>
+	<state id="Walk To TargetNode (ball) @ 0x61412450" class="WalkToTargetNode" />
+</model>
+----------------------------
+ExploreMachine http://tekkotsu.no-ip.org/dox/ExploreMachine_8cc-source.html#l00011
+!msg Explore State Machine
+ExploreMachine Explore State Machine @ 0x6144c6b8
+ WalkNode Explore State Machine::move @ 0x6144c728
+   Transitions: CompareTrans{Explore State Machine::turn@0x6144c778}
+ WalkNode Explore State Machine::turn @ 0x6144c778
+   Transitions: TimeOutTrans{Explore State Machine::move@0x6144c728}
+
+<model>
+	<state class="ExploreMachine" id="Explore State Machine">
+		<state id="Explore State Machine::move" class="WalkNode" />
+		<state id="Explore State Machine::turn @ 0x6144c778" class="WalkNode" />
+		<transition id="Explore State Machine::move @ 0x6144c728 --- Explore State Machine::move @ 0x6144c778" class="CompareTrans">
+			<source>Explore State Machine::move @ 0x6144c728</source>
+			<dest>Explore State Machine::move @ 0x6144c728</dest>		
+		</transition>
+		<transition id="Explore State Machine::turn @ 0x6144c778 --- Explore State Machine::move @ 0x6144c728">
+			<source>Explore State Machine::turn @ 0x6144c778</source>
+			<dest>Explore State Machine::move @ 0x6144c728</dest>
+		</transition>
+	</state>
+</model>
+----------------------------
+BanditMachine http://tekkotsu.no-ip.org/dox/BanditMachine_8h-source.html#l00044
+!msg Bandit State Machine
+BanditMachine Bandit State Machine @ 0x614a9e20
+ WaitNode Wait @ 0x61450aa0
+   Transitions: TimeOutTrans{Decide@0x61450bd0}
+ PressNode Left @ 0x614a9f98
+   Transitions: CompareTrans{Wait@0x61450aa0}, TimeOutTrans{BadPressLeft@0x61450c90}
+ PressNode Right @ 0x61450b68
+   Transitions: CompareTrans{Wait@0x61450aa0}, TimeOutTrans{BadPressRight@0x61450ce0}
+----------------------------
+PaceTargetsMachine http://tekkotsu.no-ip.org/dox/PaceTargetsMachine_8cc-source.html#l00013
+!msg Pace Targets State Machine
+PaceTargetsMachine Pace Targets State Machine @ 0x6144c728
+ StateNode Pace Targets State Machine::TurnAround @ 0x6144c770
+   Transitions: TimeOutTrans{Pace Targets State Machine::ExplGroup@0x6144c7c0}
+ GroupNode Pace Targets State Machine::ExplGroup @ 0x6144c7c0
+   ExploreMachine Pace Targets State Machine::ExplGroup::Explore @ 0x6144c800
+     WalkNode Pace Targets State Machine::ExplGroup::Explore::move @ 0x61450c90
+       Transitions: CompareTrans{Pace Targets State Machine::ExplGroup::Explore::turn@0x61450ce0}
+     WalkNode Pace Targets State Machine::ExplGroup::Explore::turn @ 0x61450ce0
+       Transitions: TimeOutTrans{Pace Targets State Machine::ExplGroup::Explore::move@0x61450c90}
+   PlayMotionSequenceNode Pace Targets State Machine::ExplGroup::PanHead @ 0x6144c850
+   Transitions: VisualTargetTrans{Pace Targets State Machine::Chase@0x6144c898}
+ WalkToTarget Pace Targets State Machine::Chase @ 0x6144c898
+   Transitions: TimeOutTrans{Pace Targets State Machine::ExplGroup@0x6144c7c0}, VisualTargetCloseTrans{Pace Targets State Machine::TurnAround@0x6144c770}
+----------------------------
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/statemachinedescriptor.dtd ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/statemachinedescriptor.dtd
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/statemachinedescriptor.dtd	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/model/statemachinedescriptor.dtd	2005-09-08 22:03:00.000000000 -0400
@@ -0,0 +1,14 @@
+<!DOCTYPE model [
+
+<!ELEMENT model (state*, transition*)>
+<!ELEMENT state (state*, transition*)>
+<!ELEMENT transition (source+, dest+)>
+<!ELEMENT source (#PCDATA)>
+<!ELEMENT dest (#PCDATA)>
+
+<!ATTLIST state id CDATA #REQUIRED>
+<!ATTLIST state class CDATA #REQUIRED>
+<!ATTLIST transition id CDATA #REQUIRED>
+<!ATTLIST transition class CDATA #REQUIRED>
+
+]>
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConnectionEndpointRelativeLocator.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConnectionEndpointRelativeLocator.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConnectionEndpointRelativeLocator.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConnectionEndpointRelativeLocator.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,25 @@
+/*
+ * Created on Oct 28, 2004
+ */
+package org.tekkotsu.ui.editor.resources;
+
+import org.eclipse.draw2d.Connection;
+import org.eclipse.draw2d.ConnectionEndpointLocator;
+import org.eclipse.draw2d.IFigure;
+
+/**
+ * @author asangpet
+ */
+public class ConnectionEndpointRelativeLocator extends
+		ConnectionEndpointLocator {
+	public ConnectionEndpointRelativeLocator(Connection c, boolean isEnd) {
+		super(c, isEnd);
+	}
+
+	/* (non-Javadoc)
+	 * @see org.eclipse.draw2d.ConnectionEndpointLocator#relocate(org.eclipse.draw2d.IFigure)
+	 */
+	public void relocate(IFigure figure) {
+		
+	}	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConvexPolygon.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConvexPolygon.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConvexPolygon.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/ConvexPolygon.java	2006-02-15 13:19:27.000000000 -0500
@@ -0,0 +1,43 @@
+/*
+ * Created on Oct 28, 2004
+ */
+package org.tekkotsu.ui.editor.resources;
+
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.Polygon;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.PointList;
+import org.eclipse.draw2d.geometry.Rectangle;
+
+public class ConvexPolygon extends Polygon {
+	//private Rectangle polygonBound = new Rectangle();
+	
+	/**
+	 * 
+	 */
+	public ConvexPolygon() {
+		super();
+		setBounds(new Rectangle(0,0,10,10));
+	}
+	
+	/* (non-Javadoc)
+	 * @see org.eclipse.draw2d.Figure#setBounds(org.eclipse.draw2d.geometry.Rectangle)
+	 */
+	public void setBounds(Rectangle rect) {
+
+		PointList plist = new PointList();
+		plist.addPoint(new Point(rect.x+rect.width/6,rect.y));
+		plist.addPoint(new Point(rect.x+5*rect.width/6,rect.y));
+		plist.addPoint(new Point(rect.x+rect.width-1,rect.y+rect.height/2));
+		plist.addPoint(new Point(rect.x+5*rect.width/6,rect.y+rect.height-1));
+		plist.addPoint(new Point(rect.x+rect.width/6,rect.y+rect.height-1));
+		plist.addPoint(new Point(rect.x,rect.y+rect.height/2));
+		this.setPoints(plist);
+	}
+	
+//	@Override
+	public void paintFigure(Graphics g) {
+		g.fillPolygon(this.getPoints());
+		g.drawPolygon(this.getPoints());
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/Debugger.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/Debugger.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/Debugger.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/Debugger.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,24 @@
+/*
+ * Created on Oct 24, 2004
+ */
+package org.tekkotsu.ui.editor.resources;
+
+/**
+ * @author asangpet
+ *
+ */
+public class Debugger {
+	public static int DEBUG_ALL = 4;
+	public static int DEBUG_RELEASE = 3;
+	public static int getDebugLevel() {
+		return DEBUG_RELEASE;
+	}
+	
+	public static void printDebug(int level, String s) {
+		if (level<=getDebugLevel()) System.err.println(s);
+	}
+	
+	public static void printDebug(String s) {
+		System.err.println(s);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/GlobalRegistry.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/GlobalRegistry.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/GlobalRegistry.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/GlobalRegistry.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,14 @@
+package org.tekkotsu.ui.editor.resources;
+
+public class GlobalRegistry {
+    static public class ParamObject {
+		String dogname = "";
+		public void setDogName(String name) {
+			dogname = name;
+		}
+		
+		public String getDogName() {
+			return dogname;
+		}
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/IDTag.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/IDTag.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/IDTag.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/IDTag.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,74 @@
+/*
+ * Created on Sep 18, 2004
+ */
+package org.tekkotsu.ui.editor.resources;
+
+/**
+ * @author asangpet
+ */
+import org.eclipse.swt.graphics.RGB;
+
+public class IDTag {
+	public static final String XML_state_tag	= "state";
+	public static final String XML_state_id	= "id";
+	public static final String XML_state_class	= "class";
+	public static final String XML_state_label	= "label";
+	public static final String XML_state_color	= "color";
+	public static final String XML_state_top	= "top";
+	public static final String XML_state_left	= "left";
+	public static final String XML_state_width	= "width";
+	public static final String XML_state_height = "height";
+	public static final String XML_state_shape = "shape";
+
+	public static final String XML_common_id	= "id";
+	public static final String XML_common_class	= "class";
+	public static final String XML_common_label	= "label";
+	public static final String XML_common_color	= "color";
+	public static final String XML_common_top	= "top";
+	public static final String XML_common_left	= "left";
+	public static final String XML_common_width	= "width";
+	public static final String XML_common_height = "height";	
+	
+	public static final String XML_transition_tag	= "transition";
+	public static final String XML_transition_id	= "id";
+	public static final String XML_transition_source= "source";
+	public static final String XML_transition_dest	= "destination";
+	public static final String XML_transition_visible="visible";
+	public static final String XML_transition_type	= "type";
+	public static final String XML_transition_class = "class";
+	public static final String XML_transition_linewidth = "linewidth";
+	
+	public static final String XML_view_modelsource="model";
+	public static final String XML_view_tag="view";
+	
+	public static final String ACTION_add_state = "_ADD_STATE";
+	public static final String ACTION_add_transition = "_ADD_TRANSITION";
+	public static final String ACTION_add_all = "_ADD_ALL";
+
+	/**
+	 * Convert string color tag format #FFFFFF to RGB
+	 * @param colortag
+	 * @return
+	 */
+	public static RGB Tag2RGB(String colortag) {
+		try {			
+			int red = Integer.parseInt(colortag.substring(1,3),16);
+			int green = Integer.parseInt(colortag.substring(3,5),16);
+			int blue = Integer.parseInt(colortag.substring(5,7),16);
+			return new RGB(red,green,blue);			
+		} catch(Exception e) {
+			return new RGB(255,255,255);
+		}
+	}
+	
+	private static String padZero(String str) {
+		if (str.length()<2) str = "0"+str;
+		return str;
+	}
+	public static String RGB2Tag(RGB rgb) {
+		if (rgb == null) return "#FFFFFF";
+		else return "#"+padZero(Integer.toHexString(rgb.red))+
+				padZero(Integer.toHexString(rgb.green))+
+				padZero(Integer.toHexString(rgb.blue));
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/OpenModelAction.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/OpenModelAction.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/OpenModelAction.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/editor/resources/OpenModelAction.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,85 @@
+/*
+ * Created on Feb 17, 2005
+ */
+package org.tekkotsu.ui.editor.resources;
+
+import java.io.File;
+
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.widgets.FileDialog;
+
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.IAction;
+import org.eclipse.jface.viewers.ISelection;
+
+import org.eclipse.ui.IEditorPart;
+import org.eclipse.ui.IWorkbenchWindow;
+import org.eclipse.ui.IWorkbenchWindowActionDelegate;
+import org.tekkotsu.ui.editor.StateMachineEditor;
+
+public class OpenModelAction extends Action implements
+		IWorkbenchWindowActionDelegate {
+
+	private IWorkbenchWindow fWindow;
+
+	public OpenModelAction() {
+		setEnabled(true);
+	}
+
+	/*
+	 * @see org.eclipse.ui.IWorkbenchWindowActionDelegate#dispose()
+	 */
+	public void dispose() {
+		fWindow = null;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IWorkbenchWindowActionDelegate#init(org.eclipse.ui.IWorkbenchWindow)
+	 */
+	public void init(IWorkbenchWindow window) {
+		fWindow = window;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IActionDelegate#run(org.eclipse.jface.action.IAction)
+	 */
+	public void run(IAction action) {
+		run();
+	}
+
+	/*
+	 * @see org.eclipse.ui.IActionDelegate#selectionChanged(org.eclipse.jface.action.IAction,
+	 *      org.eclipse.jface.viewers.ISelection)
+	 */
+	public void selectionChanged(IAction action, ISelection selection) {
+	}
+
+	private File queryFile() {
+		FileDialog dialog = new FileDialog(fWindow.getShell(), SWT.OPEN);
+		dialog.setText("Open File"); //$NON-NLS-1$
+		String path = dialog.open();
+		if (path != null && path.length() > 0)
+			return new File(path);
+		return null;
+	}
+
+	/*
+	 * @see org.eclipse.jface.action.Action#run()
+	 */
+	public void run() {
+		IEditorPart part = fWindow.getActivePage().getActiveEditor();
+		if (part instanceof StateMachineEditor) {
+			String[] filterExtensions = { "*.tsm", "*.*" };
+			FileDialog fileDialog = new FileDialog(fWindow.getShell(), SWT.OPEN);
+			fileDialog.setText("Model source");
+			fileDialog.setFilterExtensions(filterExtensions);
+			String path = fileDialog.open();
+			if (!path.endsWith(".tsm"))
+				path.concat(".tsm");
+			StateMachineEditor editor = (StateMachineEditor) part;
+			editor.setModelSource(path);
+		} else {
+			//MessageDialog messageDialog = new MessageDialog(fWindow.getShell(),"Error",null,"Layout file required",			
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardApplication.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardApplication.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardApplication.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardApplication.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,34 @@
+package org.tekkotsu.ui.rcp;
+
+import org.eclipse.core.runtime.IPlatformRunnable;
+import org.eclipse.swt.widgets.Display;
+import org.eclipse.ui.PlatformUI;
+import org.eclipse.ui.application.WorkbenchAdvisor;
+import org.tekkotsu.ui.editor.resources.GlobalRegistry;
+
+public class StoryboardApplication implements IPlatformRunnable {
+	
+	public Object run(Object args) {
+		GlobalRegistry.ParamObject param = new GlobalRegistry.ParamObject();
+		try {
+			String[] arg = (String[])args;
+			for (int i=0;i<arg.length;i++) System.out.println(arg[i]);
+			param.setDogName(arg[0]);
+		} catch (Exception e) {}
+
+		WorkbenchAdvisor workbenchAdvisor = new StoryboardWorkbenchAdvisor(param);
+        Display display = PlatformUI.createDisplay();
+
+        try {
+            int returnCode = PlatformUI.createAndRunWorkbench(display,
+                    workbenchAdvisor);
+            if (returnCode == PlatformUI.RETURN_RESTART) {
+                return IPlatformRunnable.EXIT_RESTART;
+            } else {
+                return IPlatformRunnable.EXIT_OK;
+            }    	    
+        } finally {
+            //display.dispose();
+        }        
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardPerspective.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardPerspective.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardPerspective.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardPerspective.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,62 @@
+package org.tekkotsu.ui.rcp;
+
+import org.eclipse.ui.IFolderLayout;
+import org.eclipse.ui.IPageLayout;
+import org.eclipse.ui.IPerspectiveFactory;
+import org.eclipse.ui.console.*;
+import java.io.*;
+
+public class StoryboardPerspective implements IPerspectiveFactory {
+	public static final String ID_STORYBOARD_VIEW = "org.tekkotsu.ui.storyboard.views.StoryboardView"; 
+	public static final String ID_RUNTIME_VIEW = "org.tekkotsu.ui.storyboard.views.RuntimeView";
+	public static final String ID_IMAGE_VIEW = "org.tekkotsu.ui.storyboard.views.ImageView";
+	
+    public StoryboardPerspective() {
+    }
+
+    public void createInitialLayout(IPageLayout layout) {        
+		IFolderLayout propRight = layout.createFolder("rightPropFolder", IPageLayout.RIGHT, 0.75f, IPageLayout.ID_EDITOR_AREA);
+		layout.addView(ID_STORYBOARD_VIEW,IPageLayout.BOTTOM, (float)0.48,IPageLayout.ID_EDITOR_AREA);
+		propRight.addView(IPageLayout.ID_PROP_SHEET);
+		propRight.addView(ID_RUNTIME_VIEW);
+		//propRight.addView(ID_IMAGE_VIEW);
+		layout.addView(ID_IMAGE_VIEW, IPageLayout.BOTTOM, (float)0.48, ID_RUNTIME_VIEW);
+    	//layout.addView(ID_RUNTIME_VIEW,IPageLayout.RIGHT,(float) 0.75,IPageLayout.ID_EDITOR_AREA);
+    	initializeConsole();    			
+    	//layout.addView(IConsoleConstants.ID_CONSOLE_VIEW,IPageLayout.BOTTOM, (float) 0.5, ID_STORYBOARD_VIEW);
+    	/*String editorArea = layout.getEditorArea();
+        IFolderLayout left =
+            layout.createFolder("right", IPageLayout.RIGHT, (float) 0.26, editorArea);
+        left.addView(IPageLayout.ID_PROP_SHEET);*/
+    }
+        
+    protected void initializeConsole() {
+    	ConsolePlugin console = ConsolePlugin.getDefault();
+    	MessageConsole outputConsole = new MessageConsole("Debug Console",null);
+    	
+    	MessageConsoleStream outs = outputConsole.newMessageStream();
+    	console.getConsoleManager().addConsoles(
+    			new IConsole[] { outputConsole });
+    	
+    	StreamRedirect redir = new StreamRedirect(outs);
+  
+    	System.setOut(redir);   	
+    }
+    
+    class StreamRedirect extends PrintStream {
+    	private MessageConsoleStream console;
+    	
+    	public StreamRedirect(MessageConsoleStream output) {
+    		super(System.err,true);
+    		this.console = output;
+    	}
+    	
+    	public void println(String s) {
+    		super.println(s);
+    		console.println(s);
+    	}
+
+    }
+
+}
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardWorkbenchAdvisor.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardWorkbenchAdvisor.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardWorkbenchAdvisor.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/StoryboardWorkbenchAdvisor.java	2006-02-14 00:22:32.000000000 -0500
@@ -0,0 +1,48 @@
+package org.tekkotsu.ui.rcp;
+
+import org.eclipse.swt.graphics.Point;
+
+import org.eclipse.ui.IWorkbenchWindow;
+import org.eclipse.ui.application.IActionBarConfigurer;
+import org.eclipse.ui.application.IWorkbenchWindowConfigurer;
+import org.eclipse.ui.application.WorkbenchAdvisor;
+import org.tekkotsu.ui.editor.resources.GlobalRegistry;
+import org.tekkotsu.ui.rcp.actions.WorkbenchActionBuilder;
+
+
+public class StoryboardWorkbenchAdvisor extends WorkbenchAdvisor {
+	private WorkbenchActionBuilder fActionBuilder;
+	
+	public StoryboardWorkbenchAdvisor(GlobalRegistry.ParamObject param) {
+		
+	}
+	
+	public StoryboardWorkbenchAdvisor() {
+	}
+
+    public String getInitialWindowPerspectiveId() {
+        return "org.tekkotsu.ui.rcp.StoryboardPerspective";
+    }
+    
+	public void preWindowOpen(IWorkbenchWindowConfigurer configurer) {
+		super.preWindowOpen(configurer);
+        configurer.setInitialSize(new Point(1000, 700));
+        configurer.setShowCoolBar(true);
+        configurer.setShowStatusLine(false);
+        configurer.setTitle("Storyboard Tool");
+	}
+	
+	public void fillActionBars(IWorkbenchWindow window, IActionBarConfigurer configurer, int flags) {
+		super.fillActionBars(window, configurer, flags);
+		if (fActionBuilder == null)
+			fActionBuilder= new WorkbenchActionBuilder(window);
+		
+		fActionBuilder.makeAndPopulateActions(getWorkbenchConfigurer(), configurer);
+	}
+	
+	public void postShutdown() {
+		if (fActionBuilder != null)
+			fActionBuilder.dispose();
+	}
+	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/NewFileAction.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/NewFileAction.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/NewFileAction.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/NewFileAction.java	2005-09-09 16:59:28.000000000 -0400
@@ -0,0 +1,127 @@
+/*
+ * Created on Jan 27, 2005
+ */
+package org.tekkotsu.ui.rcp.actions;
+
+import java.io.BufferedOutputStream;
+import java.io.File;
+import java.io.FileOutputStream;
+
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.core.runtime.Path;
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.IAction;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.jface.viewers.ISelection;
+import org.eclipse.ui.IEditorDescriptor;
+import org.eclipse.ui.IEditorInput;
+import org.eclipse.ui.IEditorRegistry;
+import org.eclipse.ui.IWorkbench;
+import org.eclipse.ui.IWorkbenchPage;
+import org.eclipse.ui.PartInitException;
+
+import org.eclipse.ui.IWorkbenchWindow;
+import org.eclipse.ui.IWorkbenchWindowActionDelegate;
+import org.jdom.Document;
+import org.jdom.output.Format;
+import org.jdom.output.XMLOutputter;
+
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.rcp.editors.PathEditorInput;
+
+/**
+ * @author asangpet
+ */
+public class NewFileAction extends Action implements
+		IWorkbenchWindowActionDelegate {
+
+	private IWorkbenchWindow fWindow;
+	private static int fileCount = -1;
+	
+	public NewFileAction() {
+		setEnabled(true);
+	}
+
+	/*
+	 * @see org.eclipse.ui.IWorkbenchWindowActionDelegate#dispose()
+	 */
+	public void dispose() {
+		fWindow = null;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IWorkbenchWindowActionDelegate#init(org.eclipse.ui.IWorkbenchWindow)
+	 */
+	public void init(IWorkbenchWindow window) {
+		fWindow = window;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IActionDelegate#run(org.eclipse.jface.action.IAction)
+	 */
+	public void run(IAction action) {
+		run();
+	}
+
+	/*
+	 * @see org.eclipse.ui.IActionDelegate#selectionChanged(org.eclipse.jface.action.IAction,
+	 *      org.eclipse.jface.viewers.ISelection)
+	 */
+	public void selectionChanged(IAction action, ISelection selection) {
+	}
+
+	/*
+	 * @see org.eclipse.jface.action.Action#run()
+	 */
+	public void run() {		
+		//File file = queryFile();//new File(wizard.getViewPath());
+		fileCount++;
+		String filename = "noname"+fileCount+".tsl";
+		File file = new File(filename);		
+		if (file==null) return;
+		// generate a new file
+		try {		    
+			Document doc = new Document();
+			filename = file.getAbsolutePath();
+			ViewModel rootModel = new ViewModel(new Path(filename));
+			rootModel.setModelSource("noname"+fileCount+".tsm");			
+			doc.addContent(rootModel.getXML());
+
+			XMLOutputter outputter = new XMLOutputter(Format.getPrettyFormat());
+			BufferedOutputStream ostream = new BufferedOutputStream(
+					new FileOutputStream(file));
+			outputter.output(doc, ostream);
+			ostream.close();
+		} catch (Exception e) {
+			//e.printStackTrace();
+			MessageDialog.openError(null,"Problem","cannot create temporary model file ");
+			e.printStackTrace();
+		}		
+		
+		// open editor
+		IEditorInput input= createEditorInput(file);
+		String editorId= getEditorId(file);
+		IWorkbenchPage page= fWindow.getActivePage();
+		try {
+			page.openEditor(input, editorId);
+		} catch (PartInitException e) {
+			e.printStackTrace();
+		}
+	}
+
+	private String getEditorId(File file) {
+		IWorkbench workbench = fWindow.getWorkbench();
+		IEditorRegistry editorRegistry = workbench.getEditorRegistry();
+		IEditorDescriptor descriptor = editorRegistry.getDefaultEditor(file
+				.getName());
+		if (descriptor != null)
+			return descriptor.getId();
+		return "org.tekkotsu.ui.rcp.editors.SimpleEditor"; //$NON-NLS-1$
+	}
+
+	private IEditorInput createEditorInput(File file) {
+		IPath location = new Path(file.getAbsolutePath());
+		PathEditorInput input = new PathEditorInput(location);
+		return input;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/OpenFileAction.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/OpenFileAction.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/OpenFileAction.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/OpenFileAction.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,119 @@
+/**********************************************************************
+Copyright (c) 2000, 2003 IBM Corp. and others.
+All rights reserved. This program and the accompanying materials
+are made available under the terms of the Common Public License v1.0
+which accompanies this distribution, and is available at
+http://www.eclipse.org/legal/cpl-v10.html
+
+Contributors:
+	IBM Corporation - Initial implementation
+**********************************************************************/
+package org.tekkotsu.ui.rcp.actions;
+
+import java.io.File;
+import java.text.MessageFormat;
+
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.core.runtime.Path;
+
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.widgets.FileDialog;
+
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.IAction;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.jface.viewers.ISelection;
+
+import org.eclipse.ui.IEditorDescriptor;
+import org.eclipse.ui.IEditorInput;
+import org.eclipse.ui.IEditorRegistry;
+import org.eclipse.ui.IWorkbench;
+import org.eclipse.ui.IWorkbenchPage;
+import org.eclipse.ui.IWorkbenchWindow;
+import org.eclipse.ui.IWorkbenchWindowActionDelegate;
+import org.eclipse.ui.PartInitException;
+import org.tekkotsu.ui.rcp.editors.PathEditorInput;
+
+/**
+ * @since 3.0
+ */
+public class OpenFileAction extends Action implements IWorkbenchWindowActionDelegate {
+	
+	private IWorkbenchWindow fWindow;
+
+	public OpenFileAction() {
+		setEnabled(true);
+	}
+
+	/*
+	 * @see org.eclipse.ui.IWorkbenchWindowActionDelegate#dispose()
+	 */
+	public void dispose() {
+		fWindow= null;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IWorkbenchWindowActionDelegate#init(org.eclipse.ui.IWorkbenchWindow)
+	 */
+	public void init(IWorkbenchWindow window) {
+		fWindow= window;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IActionDelegate#run(org.eclipse.jface.action.IAction)
+	 */
+	public void run(IAction action) {
+		run();
+	}
+
+	/*
+	 * @see org.eclipse.ui.IActionDelegate#selectionChanged(org.eclipse.jface.action.IAction, org.eclipse.jface.viewers.ISelection)
+	 */
+	public void selectionChanged(IAction action, ISelection selection) {
+	}
+
+	private File queryFile() {
+		FileDialog dialog= new FileDialog(fWindow.getShell(), SWT.OPEN);
+		dialog.setFilterExtensions(new String[] {"*.tsl"});
+		dialog.setText("Open File"); //$NON-NLS-1$
+		String path= dialog.open();
+		if (path != null && path.length() > 0)
+			return new File(path);
+		return null;
+	}
+
+	/*
+	 * @see org.eclipse.jface.action.Action#run()
+	 */
+	public void run() {
+		File file= queryFile();
+		if (file != null) {
+			IEditorInput input= createEditorInput(file);
+			String editorId= getEditorId(file);
+			IWorkbenchPage page= fWindow.getActivePage();
+			try {
+				page.openEditor(input, editorId);
+			} catch (PartInitException e) {
+				e.printStackTrace();
+			}
+		} else if (file != null) {
+			String msg = MessageFormat.format("File is null: {0}", new String[] {file.getName()}); //$NON-NLS-1$
+			MessageDialog.openWarning(fWindow.getShell(), "Problem", msg); //$NON-NLS-1$
+		}
+	}
+
+	private String getEditorId(File file) {
+		IWorkbench workbench= fWindow.getWorkbench();
+		IEditorRegistry editorRegistry= workbench.getEditorRegistry();
+		IEditorDescriptor descriptor= editorRegistry.getDefaultEditor(file.getName());
+		if (descriptor != null)
+			return descriptor.getId();
+		return "org.tekkotsu.ui.rcp.editors.SimpleEditor"; //$NON-NLS-1$
+	}
+
+	private IEditorInput createEditorInput(File file) {
+		IPath location= new Path(file.getAbsolutePath());
+		PathEditorInput input= new PathEditorInput(location);
+		return input;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/ShowActionFactory.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/ShowActionFactory.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/ShowActionFactory.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/ShowActionFactory.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,40 @@
+/*
+ * Created on Nov 7, 2004
+ */
+package org.tekkotsu.ui.rcp.actions;
+
+import org.eclipse.jface.action.Action;
+import org.eclipse.ui.IWorkbenchWindow;
+import org.eclipse.ui.PartInitException;
+
+/**
+ * @author asangpet
+ *
+ */
+public class ShowActionFactory {
+	private IWorkbenchWindow window;	
+	
+	public ShowActionFactory(IWorkbenchWindow window) {
+		this.window = window;
+	}
+	
+	class ShowAction extends Action {
+		private String viewID;
+		public ShowAction(String ID) {
+			viewID = ID;
+		}
+		public void run() {
+			try {					
+				window.getActivePage().showView(viewID);
+			} catch (PartInitException e) {
+				e.printStackTrace();
+			}
+		}
+	}
+	
+	public Action create(String viewName, String ID) {		
+		Action showAction = new ShowAction(ID);
+		showAction.setText(viewName);
+		return showAction;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/WorkbenchActionBuilder.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/WorkbenchActionBuilder.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/WorkbenchActionBuilder.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/actions/WorkbenchActionBuilder.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,306 @@
+package org.tekkotsu.ui.rcp.actions;
+
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.GroupMarker;
+import org.eclipse.jface.action.IAction;
+import org.eclipse.jface.action.ICoolBarManager;
+import org.eclipse.jface.action.IMenuManager;
+import org.eclipse.jface.action.IToolBarManager;
+import org.eclipse.jface.action.MenuManager;
+import org.eclipse.jface.action.Separator;
+import org.eclipse.jface.action.ToolBarContributionItem;
+import org.eclipse.jface.action.ToolBarManager;
+import org.eclipse.ui.IPageLayout;
+import org.eclipse.ui.IWorkbenchActionConstants;
+import org.eclipse.ui.IWorkbenchWindow;
+import org.eclipse.ui.actions.ActionFactory;
+import org.eclipse.ui.actions.ContributionItemFactory;
+import org.eclipse.ui.actions.ActionFactory.IWorkbenchAction;
+import org.eclipse.ui.application.IActionBarConfigurer;
+import org.eclipse.ui.application.IWorkbenchConfigurer;
+import org.eclipse.ui.console.IConsoleConstants;
+import org.tekkotsu.ui.rcp.StoryboardPerspective;
+
+/**
+ * Adds actions to a workbench window.
+ */
+public final class WorkbenchActionBuilder {
+	private IWorkbenchWindow window;
+
+	/** 
+	 * A convience variable and method so that the actionConfigurer doesn't need to
+	 * get passed into registerGlobalAction every time it's called.
+	 */
+	private IActionBarConfigurer fActionBarConfigurer;
+	
+	
+	// generic actions
+	private IWorkbenchAction closeAction;
+	private IWorkbenchAction closeAllAction;
+	private IWorkbenchAction closeAllSavedAction;
+	private IWorkbenchAction saveAction;
+	private IWorkbenchAction saveAllAction;
+	private IWorkbenchAction saveAsAction;
+	
+	// generic retarget actions
+	private IWorkbenchAction undoAction;
+	private IWorkbenchAction redoAction;
+	private IWorkbenchAction cutAction;
+	private IWorkbenchAction copyAction;
+	private IWorkbenchAction pasteAction;
+	private IWorkbenchAction selectAllAction;
+	private IWorkbenchAction findAction;
+	private IWorkbenchAction revertAction;
+	private IWorkbenchAction quitAction;
+	
+	/**
+	 * Constructs a new action builder which contributes actions
+	 * to the given window.
+	 * 
+	 * @param window the window
+	 */
+	public WorkbenchActionBuilder(IWorkbenchWindow window) {
+		this.window = window;
+	}
+
+	/**
+	 * Returns the window to which this action builder is contributing.
+	 */
+	private IWorkbenchWindow getWindow() {
+		return window;
+	}
+	
+	/**
+	 * Builds the actions and contributes them to the given window.
+	 * @param windowConfigurer
+	 * @param actionBarConfigurer
+	 */
+	public void makeAndPopulateActions(IWorkbenchConfigurer windowConfigurer, IActionBarConfigurer actionBarConfigurer) {
+		makeActions(windowConfigurer, actionBarConfigurer);
+		populateMenuBar(actionBarConfigurer);
+		populateCoolBar(actionBarConfigurer);
+	}
+	
+	/**
+	 * Fills the coolbar with the workbench actions.
+	 * @param configurer
+	 */
+	private void populateCoolBar(IActionBarConfigurer configurer) {
+		ICoolBarManager cbManager = configurer.getCoolBarManager();
+
+		cbManager.add(new GroupMarker("group.file")); //$NON-NLS-1$
+		{ // File Group
+			IToolBarManager fileToolBar = new ToolBarManager(cbManager.getStyle());
+			fileToolBar.add(new Separator(IWorkbenchActionConstants.NEW_GROUP));
+			fileToolBar.add(new GroupMarker(IWorkbenchActionConstants.SAVE_GROUP));
+			fileToolBar.add(saveAction);
+			
+			fileToolBar.add(new Separator(IWorkbenchActionConstants.MB_ADDITIONS));
+			
+			// Add to the cool bar manager
+			cbManager.add(new ToolBarContributionItem(fileToolBar,IWorkbenchActionConstants.TOOLBAR_FILE));
+		}
+		
+		cbManager.add(new GroupMarker(IWorkbenchActionConstants.MB_ADDITIONS));
+		
+		cbManager.add(new GroupMarker(IWorkbenchActionConstants.GROUP_EDITOR));
+		
+	}
+	
+	/**
+	 * Fills the menu bar with the workbench actions.
+	 * @param configurer
+	 */
+	public void populateMenuBar(IActionBarConfigurer configurer) {		
+		IMenuManager menubar = configurer.getMenuManager();
+		menubar.add(createFileMenu());
+		menubar.add(createEditMenu());
+		menubar.add(new GroupMarker(IWorkbenchActionConstants.MB_ADDITIONS));
+		menubar.add(createWindowMenu());
+	}
+	
+	private MenuManager createWindowMenu() {
+		MenuManager viewMenu = new MenuManager("Show View", IWorkbenchActionConstants.SHOW_EXT); 
+
+		ShowActionFactory showFactory = new ShowActionFactory(getWindow());
+		Action showStoryboardAction = showFactory.create("Storyboard",StoryboardPerspective.ID_STORYBOARD_VIEW);
+		registerGlobalAction(showStoryboardAction);		
+		Action showConsoleAction = showFactory.create("Console",IConsoleConstants.ID_CONSOLE_VIEW);
+		registerGlobalAction(showConsoleAction);
+		Action showPropSheetAction = showFactory.create("Property Sheet",IPageLayout.ID_PROP_SHEET);
+		registerGlobalAction(showPropSheetAction);
+		Action showRuntimeAction = showFactory.create("Runtime Property",StoryboardPerspective.ID_RUNTIME_VIEW);
+		registerGlobalAction(showRuntimeAction);
+		Action showImageAction = showFactory.create("Image Preview", StoryboardPerspective.ID_IMAGE_VIEW);
+		registerGlobalAction(showImageAction);
+		
+		viewMenu.add(showConsoleAction);
+		viewMenu.add(showPropSheetAction);
+		viewMenu.add(showStoryboardAction);
+		viewMenu.add(showRuntimeAction);
+		viewMenu.add(showImageAction);
+		MenuManager menu = new MenuManager("&Window",IWorkbenchActionConstants.M_WINDOW);		
+		menu.add(viewMenu);		
+		
+		return menu;
+	}
+	
+	/**
+	 * Creates and returns the File menu.
+	 */
+	private MenuManager createFileMenu() {
+		MenuManager menu = new MenuManager("&File", IWorkbenchActionConstants.M_FILE); //$NON-NLS-1$
+		menu.add(new GroupMarker(IWorkbenchActionConstants.FILE_START));
+		
+		menu.add(new GroupMarker(IWorkbenchActionConstants.NEW_EXT));
+		menu.add(closeAction);
+		menu.add(closeAllAction);
+		//		menu.add(closeAllSavedAction);
+		menu.add(new GroupMarker(IWorkbenchActionConstants.CLOSE_EXT));
+		menu.add(new Separator());
+		menu.add(saveAction);
+		menu.add(saveAsAction);
+		menu.add(saveAllAction);
+
+		menu.add(revertAction);
+		menu.add(ContributionItemFactory.REOPEN_EDITORS.create(getWindow()));
+		menu.add(new GroupMarker(IWorkbenchActionConstants.MRU));
+		menu.add(new Separator());
+		menu.add(quitAction);
+		menu.add(new GroupMarker(IWorkbenchActionConstants.FILE_END));
+		return menu;
+	}
+
+	/**
+	 * Creates and returns the Edit menu.
+	 */
+	private MenuManager createEditMenu() {
+		MenuManager menu = new MenuManager("&Edit", IWorkbenchActionConstants.M_EDIT); //$NON-NLS-1$
+		menu.add(new GroupMarker(IWorkbenchActionConstants.EDIT_START));
+
+		menu.add(undoAction);
+		menu.add(redoAction);
+		menu.add(new GroupMarker(IWorkbenchActionConstants.UNDO_EXT));
+
+		menu.add(cutAction);
+		menu.add(copyAction);
+		menu.add(pasteAction);
+		menu.add(new GroupMarker(IWorkbenchActionConstants.CUT_EXT));
+
+		menu.add(selectAllAction);
+		menu.add(new Separator());
+
+		menu.add(findAction);
+		menu.add(new GroupMarker(IWorkbenchActionConstants.FIND_EXT));
+
+		menu.add(new GroupMarker(IWorkbenchActionConstants.ADD_EXT));
+
+		menu.add(new GroupMarker(IWorkbenchActionConstants.EDIT_END));
+		menu.add(new Separator(IWorkbenchActionConstants.MB_ADDITIONS));
+		return menu;
+	}
+
+	/**
+	 * Disposes any resources and unhooks any listeners that are no longer needed.
+	 * Called when the window is closed.
+	 */
+	public void dispose() {
+		closeAction.dispose();
+		closeAllAction.dispose();
+		closeAllSavedAction.dispose();
+		saveAction.dispose();
+		saveAllAction.dispose();
+		saveAsAction.dispose();
+		redoAction.dispose();
+		cutAction.dispose();
+		copyAction.dispose();
+		pasteAction.dispose();
+		selectAllAction.dispose();
+		findAction.dispose();
+		revertAction.dispose();
+		quitAction.dispose();
+		
+
+		// null out actions to make leak debugging easier
+		closeAction = null;
+		closeAllAction = null;
+		closeAllSavedAction = null;
+		saveAction = null;
+		saveAllAction = null;
+		saveAsAction = null;
+		undoAction = null;
+		redoAction = null;
+		cutAction = null;
+		copyAction = null;
+		pasteAction = null;
+		selectAllAction = null;
+		findAction = null;
+		revertAction = null;
+		quitAction = null;
+
+	}
+
+	/**
+	 * Creates actions (and contribution items) for the menu bar, toolbar and status line.
+	 */
+	private void makeActions(IWorkbenchConfigurer workbenchConfigurer, IActionBarConfigurer actionBarConfigurer) {
+
+		// The actions in jface do not have menu vs. enable, vs. disable vs. color
+		// There are actions in here being passed the workbench - problem 
+		setCurrentActionBarConfigurer(actionBarConfigurer);
+		
+		saveAction = ActionFactory.SAVE.create(getWindow());
+		registerGlobalAction(saveAction);
+
+		saveAsAction = ActionFactory.SAVE_AS.create(getWindow());
+		registerGlobalAction(saveAsAction);
+
+		saveAllAction = ActionFactory.SAVE_ALL.create(getWindow());
+		registerGlobalAction(saveAllAction);
+		
+		undoAction = ActionFactory.UNDO.create(getWindow());
+		registerGlobalAction(undoAction);
+
+		redoAction = ActionFactory.REDO.create(getWindow());
+		registerGlobalAction(redoAction);
+
+		cutAction = ActionFactory.CUT.create(getWindow());
+		registerGlobalAction(cutAction);
+
+		copyAction = ActionFactory.COPY.create(getWindow());
+		registerGlobalAction(copyAction);
+
+		pasteAction = ActionFactory.PASTE.create(getWindow());
+		registerGlobalAction(pasteAction);
+
+		selectAllAction = ActionFactory.SELECT_ALL.create(getWindow());
+		registerGlobalAction(selectAllAction);
+		
+		findAction = ActionFactory.FIND.create(getWindow());
+		registerGlobalAction(findAction);
+
+		closeAction = ActionFactory.CLOSE.create(getWindow());
+		registerGlobalAction(closeAction);
+
+		closeAllAction = ActionFactory.CLOSE_ALL.create(getWindow());
+		registerGlobalAction(closeAllAction);
+
+		closeAllSavedAction = ActionFactory.CLOSE_ALL_SAVED.create(getWindow());
+		registerGlobalAction(closeAllSavedAction);
+
+		revertAction = ActionFactory.REVERT.create(getWindow());
+		registerGlobalAction(revertAction);
+
+		quitAction = ActionFactory.QUIT.create(getWindow());
+		registerGlobalAction(quitAction);
+	}
+
+	private void setCurrentActionBarConfigurer(IActionBarConfigurer actionBarConfigurer)
+	{
+		this.fActionBarConfigurer = actionBarConfigurer;
+	}
+	
+	private void registerGlobalAction(IAction action) {
+		fActionBarConfigurer.registerGlobalAction(action);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/PathEditorInput.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/PathEditorInput.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/PathEditorInput.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/PathEditorInput.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,107 @@
+/*******************************************************************************
+ * Copyright (c) 2000, 2003 IBM Corporation and others.
+ * All rights reserved. This program and the accompanying materials 
+ * are made available under the terms of the Common Public License v1.0
+ * which accompanies this distribution, and is available at
+ * http://www.eclipse.org/legal/cpl-v10.html
+ * 
+ * Contributors:
+ *     IBM Corporation - initial API and implementation
+ *******************************************************************************/
+package org.tekkotsu.ui.rcp.editors;
+
+import org.eclipse.core.runtime.IPath;
+
+import org.eclipse.jface.resource.ImageDescriptor;
+
+import org.eclipse.ui.IPathEditorInput;
+import org.eclipse.ui.IPersistableElement;
+import org.eclipse.ui.PlatformUI;
+
+/**
+ * EditorInput that stores a path.
+ */
+public class PathEditorInput implements IPathEditorInput {
+	private IPath fPath;
+	
+	/**
+	 * Creates an editor input based of the given file resource.
+	 *
+	 * @param path the file
+	 */
+	public PathEditorInput(IPath path) {
+		if (path == null) {
+			throw new IllegalArgumentException();
+		}
+		this.fPath = path;
+	}
+	
+	/*
+	 * @see java.lang.Object#hashCode()
+	 */
+	public int hashCode() {
+		return fPath.hashCode();
+	}
+	
+	/*
+	 * @see java.lang.Object#equals(java.lang.Object)
+	 */
+	public boolean equals(Object obj) {
+		if (this == obj)
+			return true;
+		if (!(obj instanceof PathEditorInput))
+			return false;
+		PathEditorInput other = (PathEditorInput) obj;
+		return fPath.equals(other.fPath);
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#exists()
+	 */
+	public boolean exists() {
+		return fPath.toFile().exists();
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getImageDescriptor()
+	 */
+	public ImageDescriptor getImageDescriptor() {
+		return PlatformUI.getWorkbench().getEditorRegistry().getImageDescriptor(fPath.toString());
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getName()
+	 */
+	public String getName() {
+		return fPath.toString();
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getToolTipText()
+	 */
+	public String getToolTipText() {
+		return fPath.makeRelative().toString();
+	}
+	
+	/*
+	 * @see org.eclipse.ui.IPathEditorInput#getPath()
+	 */
+	public IPath getPath() {
+		return fPath;
+	}
+
+	/*
+	 * @see org.eclipse.core.runtime.IAdaptable#getAdapter(java.lang.Class)
+	 */
+	public Object getAdapter(Class adapter) {
+		return null;
+	}
+
+	/*
+	 * @see org.eclipse.ui.IEditorInput#getPersistable()
+	 */
+	public IPersistableElement getPersistable() {
+		// no persistence
+		return null;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleDocumentProvider.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleDocumentProvider.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleDocumentProvider.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleDocumentProvider.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,170 @@
+package org.tekkotsu.ui.rcp.editors;
+
+import java.io.BufferedReader;
+import java.io.BufferedWriter;
+import java.io.File;
+import java.io.FileNotFoundException;
+import java.io.FileReader;
+import java.io.FileWriter;
+import java.io.IOException;
+import java.io.Reader;
+import java.io.Writer;
+
+import org.eclipse.core.runtime.CoreException;
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.core.runtime.IProgressMonitor;
+import org.eclipse.core.runtime.IStatus;
+import org.eclipse.core.runtime.Status;
+
+import org.eclipse.jface.operation.IRunnableContext;
+
+import org.eclipse.jface.text.Document;
+import org.eclipse.jface.text.IDocument;
+import org.eclipse.jface.text.source.IAnnotationModel;
+
+import org.eclipse.ui.IEditorInput;
+import org.eclipse.ui.IPathEditorInput;
+import org.eclipse.ui.texteditor.AbstractDocumentProvider;
+
+public class SimpleDocumentProvider extends AbstractDocumentProvider {
+
+	/*
+	 * @see org.eclipse.ui.texteditor.AbstractDocumentProvider#createDocument(java.lang.Object)
+	 */
+	protected IDocument createDocument(Object element) throws CoreException {
+		if (element instanceof IEditorInput) {
+			IDocument document= new Document();
+			if (setDocumentContent(document, (IEditorInput) element)) {
+				setupDocument(document);
+			}
+			return document;
+		}
+	
+		return null;
+	}
+	
+	private boolean setDocumentContent(IDocument document, IEditorInput input) throws CoreException {
+		Reader reader;
+		try {
+			if (input instanceof IPathEditorInput)
+				reader= new FileReader(((IPathEditorInput)input).getPath().toFile());
+			else
+				reader= new FileReader(input.getName());
+		} catch (FileNotFoundException e) {
+			// return empty document and save later
+			return true;
+		}
+		
+		try {
+			setDocumentContent(document, reader);
+			return true;
+		} catch (IOException e) {
+			throw new CoreException(new Status(IStatus.ERROR, "org.tekkotsu.ui.rcp", IStatus.OK, "error reading file", e)); //$NON-NLS-1$ //$NON-NLS-2$
+		}
+	}
+
+	private void setDocumentContent(IDocument document, Reader reader) throws IOException {
+		Reader in= new BufferedReader(reader);
+		try {
+			
+			StringBuffer buffer= new StringBuffer(512);
+			char[] readBuffer= new char[512];
+			int n= in.read(readBuffer);
+			while (n > 0) {
+				buffer.append(readBuffer, 0, n);
+				n= in.read(readBuffer);
+			}
+			
+			document.set(buffer.toString());
+		
+		} finally {
+			in.close();
+		}
+	}
+
+	/**
+	 * Set up the document - default implementation does nothing.
+	 * 
+	 * @param document the new document
+	 */
+	protected void setupDocument(IDocument document) {
+	}
+
+	/*
+	 * @see org.eclipse.ui.texteditor.AbstractDocumentProvider#createAnnotationModel(java.lang.Object)
+	 */
+	protected IAnnotationModel createAnnotationModel(Object element) throws CoreException {
+		return null;
+	}
+
+	/*
+	 * @see org.eclipse.ui.texteditor.AbstractDocumentProvider#doSaveDocument(org.eclipse.core.runtime.IProgressMonitor, java.lang.Object, org.eclipse.jface.text.IDocument, boolean)
+	 */
+	protected void doSaveDocument(IProgressMonitor monitor, Object element, IDocument document, boolean overwrite) throws CoreException {
+		if (element instanceof IPathEditorInput) {
+			IPathEditorInput pei= (IPathEditorInput) element;
+			IPath path= pei.getPath();
+			File file= path.toFile();
+			
+			try {
+				file.createNewFile();
+
+				if (file.exists()) {
+					if (file.canWrite()) {
+						Writer writer= new FileWriter(file);
+						writeDocumentContent(document, writer, monitor);
+					} else {
+						throw new CoreException(new Status(IStatus.ERROR, "org.tekkotsu.ui.rcp", IStatus.OK, "file is read-only", null)); //$NON-NLS-1$ //$NON-NLS-2$
+					}
+				} else {
+					throw new CoreException(new Status(IStatus.ERROR, "org.tekkotsu.ui.rcp", IStatus.OK, "error creating file", null)); //$NON-NLS-1$ //$NON-NLS-2$
+				}
+			} catch (IOException e) {
+				throw new CoreException(new Status(IStatus.ERROR, "org.tekkotsu.ui.rcp", IStatus.OK, "error when saving file", e)); //$NON-NLS-1$ //$NON-NLS-2$
+			}
+
+		}
+	}
+
+	private void writeDocumentContent(IDocument document, Writer writer, IProgressMonitor monitor) throws IOException {
+		Writer out= new BufferedWriter(writer);
+		try {
+			out.write(document.get());
+		} finally {
+			out.close();
+		}
+	}
+
+	/*
+	 * @see org.eclipse.ui.texteditor.AbstractDocumentProvider#getOperationRunner(org.eclipse.core.runtime.IProgressMonitor)
+	 */
+	protected IRunnableContext getOperationRunner(IProgressMonitor monitor) {
+		return null;
+	}
+	
+	/*
+	 * @see org.eclipse.ui.texteditor.IDocumentProviderExtension#isModifiable(java.lang.Object)
+	 */
+	public boolean isModifiable(Object element) {
+		if (element instanceof IPathEditorInput) {
+			IPathEditorInput pei= (IPathEditorInput) element;
+			File file= pei.getPath().toFile();
+			return file.canWrite() || !file.exists(); // Allow to edit new files
+		}
+		return false;
+	}
+	
+	/*
+	 * @see org.eclipse.ui.texteditor.IDocumentProviderExtension#isReadOnly(java.lang.Object)
+	 */
+	public boolean isReadOnly(Object element) {
+		return !isModifiable(element);
+	}
+	
+	/*
+	 * @see org.eclipse.ui.texteditor.IDocumentProviderExtension#isStateValidated(java.lang.Object)
+	 */
+	public boolean isStateValidated(Object element) {
+		return true;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleEditor.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleEditor.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleEditor.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/SimpleEditor.java	2005-09-08 22:03:02.000000000 -0400
@@ -0,0 +1,22 @@
+package org.tekkotsu.ui.rcp.editors;
+
+import org.eclipse.ui.texteditor.AbstractTextEditor;
+
+
+public class SimpleEditor extends AbstractTextEditor {
+
+	public SimpleEditor() {
+		super();
+		internal_init();
+	}
+
+	/**
+	 * Initializes the document provider and source viewer configuration.
+	 * Called by the constructor. Subclasses may replace this method.
+	 */
+	protected void internal_init() {
+		configureInsertMode(SMART_INSERT, false);
+		setDocumentProvider(new SimpleDocumentProvider());
+	}
+	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/ColorManager.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/ColorManager.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/ColorManager.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/ColorManager.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,28 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import java.util.HashMap;
+import java.util.Iterator;
+import java.util.Map;
+
+import org.eclipse.swt.graphics.Color;
+import org.eclipse.swt.graphics.RGB;
+import org.eclipse.swt.widgets.Display;
+
+class ColorManager {
+
+	protected Map fColorTable = new HashMap(10);
+
+	public void dispose() {
+		Iterator e = fColorTable.values().iterator();
+		while (e.hasNext())
+			 ((Color) e.next()).dispose();
+	}
+	public Color getColor(RGB rgb) {
+		Color color = (Color) fColorTable.get(rgb);
+		if (color == null) {
+			color = new Color(Display.getCurrent(), rgb);
+			fColorTable.put(rgb, color);
+		}
+		return color;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/IXMLColorConstants.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/IXMLColorConstants.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/IXMLColorConstants.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/IXMLColorConstants.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,11 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.swt.graphics.RGB;
+
+public interface IXMLColorConstants {
+	RGB XML_COMMENT = new RGB(128, 0, 0);
+	RGB PROC_INSTR = new RGB(128, 128, 128);
+	RGB STRING = new RGB(0, 128, 0);
+	RGB DEFAULT = new RGB(0, 0, 0);
+	RGB TAG = new RGB(0, 0, 128);
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/NonRuleBasedDamagerRepairer.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/NonRuleBasedDamagerRepairer.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/NonRuleBasedDamagerRepairer.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/NonRuleBasedDamagerRepairer.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,141 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.swt.custom.StyleRange;
+
+import org.eclipse.jface.util.Assert;
+
+import org.eclipse.jface.text.BadLocationException;
+import org.eclipse.jface.text.DocumentEvent;
+import org.eclipse.jface.text.IDocument;
+import org.eclipse.jface.text.IRegion;
+import org.eclipse.jface.text.ITypedRegion;
+import org.eclipse.jface.text.Region;
+import org.eclipse.jface.text.TextAttribute;
+import org.eclipse.jface.text.TextPresentation;
+import org.eclipse.jface.text.presentation.IPresentationDamager;
+import org.eclipse.jface.text.presentation.IPresentationRepairer;
+
+public class NonRuleBasedDamagerRepairer
+	implements IPresentationDamager, IPresentationRepairer {
+
+	/** The document this object works on */
+	protected IDocument fDocument;
+	/** The default text attribute if non is returned as data by the current token */
+	protected TextAttribute fDefaultTextAttribute;
+	
+	/**
+	 * Constructor for NonRuleBasedDamagerRepairer.
+	 * @param defaultTextAttribute
+	 */
+	public NonRuleBasedDamagerRepairer(TextAttribute defaultTextAttribute) {
+		Assert.isNotNull(defaultTextAttribute);
+
+		fDefaultTextAttribute = defaultTextAttribute;
+	}
+
+	/**
+	 * @see IPresentationRepairer#setDocument(IDocument)
+	 */
+	public void setDocument(IDocument document) {
+		fDocument = document;
+	}
+
+	/**
+	 * Returns the end offset of the line that contains the specified offset or
+	 * if the offset is inside a line delimiter, the end offset of the next line.
+	 *
+	 * @param offset the offset whose line end offset must be computed
+	 * @return the line end offset for the given offset
+	 * @exception BadLocationException if offset is invalid in the current document
+	 */
+	protected int endOfLineOf(int offset) throws BadLocationException {
+
+		IRegion info = fDocument.getLineInformationOfOffset(offset);
+		if (offset <= info.getOffset() + info.getLength())
+			return info.getOffset() + info.getLength();
+
+		int line = fDocument.getLineOfOffset(offset);
+		try {
+			info = fDocument.getLineInformation(line + 1);
+			return info.getOffset() + info.getLength();
+		} catch (BadLocationException x) {
+			return fDocument.getLength();
+		}
+	}
+
+	/**
+	 * @see IPresentationDamager#getDamageRegion(ITypedRegion, DocumentEvent, boolean)
+	 */
+	public IRegion getDamageRegion(
+		ITypedRegion partition,
+		DocumentEvent event,
+		boolean documentPartitioningChanged) {
+		if (!documentPartitioningChanged) {
+			try {
+
+				IRegion info =
+					fDocument.getLineInformationOfOffset(event.getOffset());
+				int start = Math.max(partition.getOffset(), info.getOffset());
+
+				int end =
+					event.getOffset()
+						+ (event.getText() == null
+							? event.getLength()
+							: event.getText().length());
+
+				if (info.getOffset() <= end
+					&& end <= info.getOffset() + info.getLength()) {
+					// optimize the case of the same line
+					end = info.getOffset() + info.getLength();
+				} else
+					end = endOfLineOf(end);
+
+				end =
+					Math.min(
+						partition.getOffset() + partition.getLength(),
+						end);
+				return new Region(start, end - start);
+
+			} catch (BadLocationException x) {
+			}
+		}
+
+		return partition;
+	}
+
+	/**
+	 * @see IPresentationRepairer#createPresentation(TextPresentation, ITypedRegion)
+	 */
+	public void createPresentation(
+		TextPresentation presentation,
+		ITypedRegion region) {
+		addRange(
+			presentation,
+			region.getOffset(),
+			region.getLength(),
+			fDefaultTextAttribute);
+	}
+
+	/**
+	 * Adds style information to the given text presentation.
+	 *
+	 * @param presentation the text presentation to be extended
+	 * @param offset the offset of the range to be styled
+	 * @param length the length of the range to be styled
+	 * @param attr the attribute describing the style of the range to be styled
+	 */
+	protected void addRange(
+		TextPresentation presentation,
+		int offset,
+		int length,
+		TextAttribute attr) {
+		if (attr != null)
+			presentation.addStyleRange(
+				new StyleRange(
+					offset,
+					length,
+					attr.getForeground(),
+					attr.getBackground(),
+					attr.getStyle()));
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/TagRule.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/TagRule.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/TagRule.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/TagRule.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,34 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.rules.ICharacterScanner;
+import org.eclipse.jface.text.rules.IToken;
+import org.eclipse.jface.text.rules.MultiLineRule;
+
+
+public class TagRule extends MultiLineRule {
+
+	public TagRule(IToken token) {
+		super("<", ">", token);  //$NON-NLS-1$//$NON-NLS-2$
+	}
+	protected boolean sequenceDetected(
+		ICharacterScanner scanner,
+		char[] sequence,
+		boolean eofAllowed) {
+		int c = scanner.read();
+		if (sequence[0] == '<') {
+			if (c == '?') {
+				// processing instruction - abort
+				scanner.unread();
+				return false;
+			}
+			if (c == '!') {
+				scanner.unread();
+				// comment - abort
+				return false;
+			}
+		} else if (sequence[0] == '>') {
+			scanner.unread();
+		}
+		return super.sequenceDetected(scanner, sequence, eofAllowed);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLConfiguration.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLConfiguration.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLConfiguration.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLConfiguration.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,80 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.IDocument;
+import org.eclipse.jface.text.ITextDoubleClickStrategy;
+import org.eclipse.jface.text.TextAttribute;
+import org.eclipse.jface.text.presentation.IPresentationReconciler;
+import org.eclipse.jface.text.presentation.PresentationReconciler;
+import org.eclipse.jface.text.rules.DefaultDamagerRepairer;
+import org.eclipse.jface.text.rules.Token;
+import org.eclipse.jface.text.source.ISourceViewer;
+import org.eclipse.jface.text.source.SourceViewerConfiguration;
+
+
+public class XMLConfiguration extends SourceViewerConfiguration {
+	private XMLDoubleClickStrategy doubleClickStrategy;
+	private XMLTagScanner tagScanner;
+	private XMLScanner scanner;
+	private ColorManager colorManager;
+
+	public XMLConfiguration(ColorManager colorManager) {
+		this.colorManager = colorManager;
+	}
+	public String[] getConfiguredContentTypes(ISourceViewer sourceViewer) {
+		return new String[] {
+			IDocument.DEFAULT_CONTENT_TYPE,
+			XMLPartitionScanner.XML_COMMENT,
+			XMLPartitionScanner.XML_TAG };
+	}
+	public ITextDoubleClickStrategy getDoubleClickStrategy(
+		ISourceViewer sourceViewer,
+		String contentType) {
+		if (doubleClickStrategy == null)
+			doubleClickStrategy = new XMLDoubleClickStrategy();
+		return doubleClickStrategy;
+	}
+
+	protected XMLScanner getXMLScanner() {
+		if (scanner == null) {
+			scanner = new XMLScanner(colorManager);
+			scanner.setDefaultReturnToken(
+				new Token(
+					new TextAttribute(
+						colorManager.getColor(IXMLColorConstants.DEFAULT))));
+		}
+		return scanner;
+	}
+	protected XMLTagScanner getXMLTagScanner() {
+		if (tagScanner == null) {
+			tagScanner = new XMLTagScanner(colorManager);
+			tagScanner.setDefaultReturnToken(
+				new Token(
+					new TextAttribute(
+						colorManager.getColor(IXMLColorConstants.TAG))));
+		}
+		return tagScanner;
+	}
+
+	public IPresentationReconciler getPresentationReconciler(ISourceViewer sourceViewer) {
+		PresentationReconciler reconciler = new PresentationReconciler();
+
+		DefaultDamagerRepairer dr =
+			new DefaultDamagerRepairer(getXMLTagScanner());
+		reconciler.setDamager(dr, XMLPartitionScanner.XML_TAG);
+		reconciler.setRepairer(dr, XMLPartitionScanner.XML_TAG);
+
+		dr = new DefaultDamagerRepairer(getXMLScanner());
+		reconciler.setDamager(dr, IDocument.DEFAULT_CONTENT_TYPE);
+		reconciler.setRepairer(dr, IDocument.DEFAULT_CONTENT_TYPE);
+
+		NonRuleBasedDamagerRepairer ndr =
+			new NonRuleBasedDamagerRepairer(
+				new TextAttribute(
+					colorManager.getColor(IXMLColorConstants.XML_COMMENT)));
+		reconciler.setDamager(ndr, XMLPartitionScanner.XML_COMMENT);
+		reconciler.setRepairer(ndr, XMLPartitionScanner.XML_COMMENT);
+
+		return reconciler;
+	}
+
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDocumentProvider.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDocumentProvider.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDocumentProvider.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDocumentProvider.java	2007-03-01 15:26:25.000000000 -0500
@@ -0,0 +1,30 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.core.runtime.CoreException;
+
+import org.eclipse.jface.text.IDocument;
+import org.eclipse.jface.text.IDocumentPartitioner;
+import org.eclipse.jface.text.rules.FastPartitioner;
+import org.eclipse.jface.text.source.IAnnotationModel;
+
+import org.tekkotsu.ui.rcp.editors.SimpleDocumentProvider;
+
+public class XMLDocumentProvider extends SimpleDocumentProvider {
+
+	protected void setupDocument(IDocument document) {
+		if (document != null) {
+			IDocumentPartitioner partitioner =
+				new FastPartitioner(
+					new XMLPartitionScanner(),
+					new String[] {
+						XMLPartitionScanner.XML_TAG,
+						XMLPartitionScanner.XML_COMMENT });
+			partitioner.connect(document);
+			document.setDocumentPartitioner(partitioner);
+		}
+	}
+
+	protected IAnnotationModel createAnnotationModel(Object element) throws CoreException {
+		return null;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDoubleClickStrategy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDoubleClickStrategy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDoubleClickStrategy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLDoubleClickStrategy.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,116 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.BadLocationException;
+import org.eclipse.jface.text.IDocument;
+import org.eclipse.jface.text.ITextDoubleClickStrategy;
+import org.eclipse.jface.text.ITextViewer;
+
+
+public class XMLDoubleClickStrategy implements ITextDoubleClickStrategy {
+	protected ITextViewer fText;
+
+	public void doubleClicked(ITextViewer part) {
+		int pos = part.getSelectedRange().x;
+
+		if (pos < 0)
+			return;
+
+		fText = part;
+
+		if (!selectComment(pos)) {
+			selectWord(pos);
+		}
+	}
+	protected boolean selectComment(int caretPos) {
+		IDocument doc = fText.getDocument();
+		int startPos, endPos;
+
+		try {
+			int pos = caretPos;
+			char c = ' ';
+
+			while (pos >= 0) {
+				c = doc.getChar(pos);
+				if (c == '\\') {
+					pos -= 2;
+					continue;
+				}
+				if (c == Character.LINE_SEPARATOR || c == '\"')
+					break;
+				--pos;
+			}
+
+			if (c != '\"')
+				return false;
+
+			startPos = pos;
+
+			pos = caretPos;
+			int length = doc.getLength();
+			c = ' ';
+
+			while (pos < length) {
+				c = doc.getChar(pos);
+				if (c == Character.LINE_SEPARATOR || c == '\"')
+					break;
+				++pos;
+			}
+			if (c != '\"')
+				return false;
+
+			endPos = pos;
+
+			int offset = startPos + 1;
+			int len = endPos - offset;
+			fText.setSelectedRange(offset, len);
+			return true;
+		} catch (BadLocationException x) {
+		}
+
+		return false;
+	}
+	protected boolean selectWord(int caretPos) {
+
+		IDocument doc = fText.getDocument();
+		int startPos, endPos;
+
+		try {
+
+			int pos = caretPos;
+			char c;
+
+			while (pos >= 0) {
+				c = doc.getChar(pos);
+				if (!Character.isJavaIdentifierPart(c))
+					break;
+				--pos;
+			}
+
+			startPos = pos;
+
+			pos = caretPos;
+			int length = doc.getLength();
+
+			while (pos < length) {
+				c = doc.getChar(pos);
+				if (!Character.isJavaIdentifierPart(c))
+					break;
+				++pos;
+			}
+
+			endPos = pos;
+			selectRange(startPos, endPos);
+			return true;
+
+		} catch (BadLocationException x) {
+		}
+
+		return false;
+	}
+
+	private void selectRange(int startPos, int stopPos) {
+		int offset = startPos + 1;
+		int length = stopPos - offset;
+		fText.setSelectedRange(offset, length);
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLEditor.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLEditor.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLEditor.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLEditor.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,21 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.tekkotsu.ui.rcp.editors.SimpleEditor;
+
+
+public class XMLEditor extends SimpleEditor {
+
+	private ColorManager colorManager;
+
+	protected void internal_init() {
+		configureInsertMode(SMART_INSERT, false);
+		colorManager = new ColorManager();
+		setSourceViewerConfiguration(new XMLConfiguration(colorManager));
+		setDocumentProvider(new XMLDocumentProvider());
+	}
+	
+	public void dispose() {
+		colorManager.dispose();
+		super.dispose();
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLPartitionScanner.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLPartitionScanner.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLPartitionScanner.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLPartitionScanner.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,28 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.rules.IPredicateRule;
+import org.eclipse.jface.text.rules.IToken;
+import org.eclipse.jface.text.rules.MultiLineRule;
+import org.eclipse.jface.text.rules.RuleBasedPartitionScanner;
+import org.eclipse.jface.text.rules.Token;
+
+
+
+public class XMLPartitionScanner extends RuleBasedPartitionScanner {
+	public final static String XML_DEFAULT = "__xml_default"; //$NON-NLS-1$
+	public final static String XML_COMMENT = "__xml_comment"; //$NON-NLS-1$
+	public final static String XML_TAG = "__xml_tag"; //$NON-NLS-1$
+
+	public XMLPartitionScanner() {
+
+		IToken xmlComment = new Token(XML_COMMENT);
+		IToken tag = new Token(XML_TAG);
+
+		IPredicateRule[] rules = new IPredicateRule[2];
+
+		rules[0] = new MultiLineRule("<!--", "-->", xmlComment);  //$NON-NLS-1$//$NON-NLS-2$
+		rules[1] = new TagRule(tag);
+
+		setPredicateRules(rules);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLScanner.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLScanner.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLScanner.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLScanner.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,28 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.TextAttribute;
+import org.eclipse.jface.text.rules.IRule;
+import org.eclipse.jface.text.rules.IToken;
+import org.eclipse.jface.text.rules.RuleBasedScanner;
+import org.eclipse.jface.text.rules.SingleLineRule;
+import org.eclipse.jface.text.rules.Token;
+import org.eclipse.jface.text.rules.WhitespaceRule;
+
+
+public class XMLScanner extends RuleBasedScanner {
+
+	public XMLScanner(ColorManager manager) {
+		IToken procInstr =
+			new Token(
+				new TextAttribute(
+					manager.getColor(IXMLColorConstants.PROC_INSTR)));
+
+		IRule[] rules = new IRule[2];
+		//Add rule for processing instructions
+		rules[0] = new SingleLineRule("<?", "?>", procInstr); //$NON-NLS-1$ //$NON-NLS-2$
+		// Add generic whitespace rule.
+		rules[1] = new WhitespaceRule(new XMLWhitespaceDetector());
+
+		setRules(rules);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLTagScanner.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLTagScanner.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLTagScanner.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLTagScanner.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,30 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.TextAttribute;
+import org.eclipse.jface.text.rules.IRule;
+import org.eclipse.jface.text.rules.IToken;
+import org.eclipse.jface.text.rules.RuleBasedScanner;
+import org.eclipse.jface.text.rules.SingleLineRule;
+import org.eclipse.jface.text.rules.Token;
+import org.eclipse.jface.text.rules.WhitespaceRule;
+
+
+public class XMLTagScanner extends RuleBasedScanner {
+
+	public XMLTagScanner(ColorManager manager) {
+		IToken string =
+			new Token(
+				new TextAttribute(manager.getColor(IXMLColorConstants.STRING)));
+
+		IRule[] rules = new IRule[3];
+
+		// Add rule for double quotes
+		rules[0] = new SingleLineRule("\"", "\"", string, '\\'); //$NON-NLS-1$ //$NON-NLS-2$
+		// Add a rule for single quotes
+		rules[1] = new SingleLineRule("'", "'", string, '\\'); //$NON-NLS-1$ //$NON-NLS-2$
+		// Add generic whitespace rule.
+		rules[2] = new WhitespaceRule(new XMLWhitespaceDetector());
+
+		setRules(rules);
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLWhitespaceDetector.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLWhitespaceDetector.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLWhitespaceDetector.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/rcp/editors/xml/XMLWhitespaceDetector.java	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1,11 @@
+package org.tekkotsu.ui.rcp.editors.xml;
+
+import org.eclipse.jface.text.rules.IWhitespaceDetector;
+
+
+public class XMLWhitespaceDetector implements IWhitespaceDetector {
+
+	public boolean isWhitespace(char c) {
+		return (c == ' ' || c == '\t' || c == '\n' || c == '\r');
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/Base64.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/Base64.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/Base64.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/Base64.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,159 @@
+package org.tekkotsu.ui.storyboard;
+
+//*********************************************************************
+//* Base64 - a simple base64 encoder and decoder.
+//*
+//*     Copyright (c) 1999, Bob Withers - bwit@pobox.com
+//*
+//* This code may be freely used for any purpose, either personal
+//* or commercial, provided the authors copyright notice remains
+//* intact.
+//*********************************************************************
+
+public class Base64 {
+
+	public static String encode(String data)
+	{
+		return encode(getBinaryBytes(data));
+	}
+	
+	public static String encode(byte[] data)
+	{
+		int c;
+		int len = data.length;
+		StringBuffer ret = new StringBuffer(((len / 3) + 1) * 4);
+		for (int i = 0; i < len; ++i)
+		{
+			c = (data[i] >> 2) & 0x3f;
+			ret.append(cvt.charAt(c));
+			c = (data[i] << 4) & 0x3f;
+			if (++i < len)
+				c |= (data[i] >> 4) & 0x0f;
+			
+			ret.append(cvt.charAt(c));
+			if (i < len)
+			{
+				c = (data[i] << 2) & 0x3f;
+				if (++i < len)
+					c |= (data[i] >> 6) & 0x03;
+				
+				ret.append(cvt.charAt(c));
+			}
+			else
+			{
+				++i;
+				ret.append((char) fillchar);
+			}
+			
+			if (i < len)
+			{
+				c = data[i] & 0x3f;
+				ret.append(cvt.charAt(c));
+			}
+			else
+			{
+				ret.append((char) fillchar);
+			}
+		}
+		
+		return ret.toString();
+	}
+	
+	public static byte[] decode(String data)
+	{
+		return decode(getBinaryBytes(data));
+	}
+	
+	public static byte[] decode(byte[] data)
+	{
+		int c;
+		int c1;
+		int len = data.length;
+		StringBuffer ret = new StringBuffer((len * 3) / 4);
+		for (int i = 0; i < len; ++i)
+		{
+			c = cvt.indexOf(data[i]);
+			++i;
+			c1 = cvt.indexOf(data[i]);
+			c = ((c << 2) | ((c1 >> 4) & 0x3));
+			ret.append((char) c);
+			if (++i < len)
+			{
+				c = data[i];
+				if (fillchar == c)
+					break;
+				
+				c = cvt.indexOf((char) c);
+				c1 = ((c1 << 4) & 0xf0) | ((c >> 2) & 0xf);
+				ret.append((char) c1);
+			}
+			
+			if (++i < len)
+			{
+				c1 = data[i];
+				if (fillchar == c1)
+					break;
+				
+				c1 = cvt.indexOf((char) c1);
+				c = ((c << 6) & 0xc0) | c1;
+				ret.append((char) c);
+			}
+		}
+		
+		return(getBinaryBytes(ret.toString()));
+	}
+	
+	private static String getString(byte[] arr)
+	{
+		StringBuffer buf = new StringBuffer();
+		for (int i = 0; i < arr.length; ++i)
+			buf.append((char) arr[i]);
+		
+		return(buf.toString());
+	}
+	
+	private static byte[] getBinaryBytes(String str)
+	{
+		byte[] b = new byte[str.length()];
+		for (int i = 0; i < b.length; ++i)
+			b[i] = (byte) str.charAt(i);
+		
+		return(b);
+	}
+	
+	private static final int    fillchar = '=';
+	
+	// 00000000001111111111222222
+	// 01234567890123456789012345
+	private static final String cvt = "ABCDEFGHIJKLMNOPQRSTUVWXYZ"
+		
+		// 22223333333333444444444455
+		// 67890123456789012345678901
+		+ "abcdefghijklmnopqrstuvwxyz"
+		
+		// 555555556666
+		// 234567890123
+		+ "0123456789+/";
+	
+	public static void main(String[] args)
+	{
+		String str;
+		if (args.length > 0)
+			str = args[0];
+		else
+			str = "Now is the time for all good men";
+		
+		System.out.println("Encoding string [" + str + "]");
+		str = encode(str);
+		System.out.println("Encoded string  [" + str + "]");
+		str = getString(decode(str));
+		System.out.println("Decoded string  [" + str + "]");
+		System.out.println();
+		byte[] b = getBinaryBytes(str);
+		System.out.println("Encoding bytes  [" + getString(b) + "]");
+		b = getBinaryBytes(encode(b));
+		System.out.println("Encoded bytes   [" + getString(b) + "]");
+		b = decode(b);
+		System.out.println("Decoded bytes   [" + getString(b) + "]");
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/ResourceRegistry.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/ResourceRegistry.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/ResourceRegistry.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/ResourceRegistry.java	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,46 @@
+/*
+ * Created on Apr 13, 2005
+ */
+package org.tekkotsu.ui.storyboard;
+
+import org.eclipse.jface.resource.ColorRegistry;
+import org.eclipse.jface.resource.ImageRegistry;
+import org.eclipse.swt.widgets.Display;
+
+/**
+ * 
+ * @author asangpet
+ */
+public class ResourceRegistry {
+    private ImageRegistry imgReg = null;
+    private ColorRegistry colReg = null;
+    private Display display = null;
+    
+    private static ResourceRegistry resourceReg = null;
+    
+    private ResourceRegistry(Display display) {
+        this.display = display;
+        imgReg = new ImageRegistry(display);
+        colReg = new ColorRegistry(display);        
+    }
+    
+    public static void init(Display display) {
+        resourceReg = new ResourceRegistry(display);
+    }
+    
+    public static ResourceRegistry getInstance() {
+        return resourceReg; 
+    }
+    
+    public ImageRegistry getImageRegistry() {        
+        return imgReg;
+    }
+    
+    public Display getDisplay() {     
+        return display;
+    }
+    
+    public ColorRegistry getColorRegistry() {
+        return colReg;
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,183 @@
+/*
+ * Created on Nov 11, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Label;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.PointList;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ColorRegistry;
+import org.eclipse.swt.graphics.Color;
+import org.eclipse.swt.graphics.RGB;
+import org.eclipse.swt.widgets.Display;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.storyboard.model.BlockModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class Block extends Figure {	
+	boolean active = false;
+	ColorRegistry colReg;
+	static final String COLOR_BASE = "_color_base";
+	static final String COLOR_FADE = "_color_fade";
+	static final String COLOR_BORDER="_color_border";
+	Color baseColor, fgColor, bgColor;
+	
+	BlockModel model;
+	StateNodeModel state;
+	Rectangle constraint;
+	TimeLine timeline;
+	int offset = TimeLine.xoffset;
+	int metric = TimeLine.gap;
+	
+	/*
+	public Block() {
+		super();
+		colReg = new ColorRegistry();
+		setColor(new RGB(220,220,220));
+	}*/
+	
+	public Block(Display display, IFigure parent, BlockModel model, StateNodeModel state, TimeLine timeLine) {
+		timeline = timeLine;
+		colReg = new ColorRegistry(display);
+		this.state = state;
+		setModel(model);
+		Color c = state.getColor();
+		setColor(new RGB(c.getRed(), c.getGreen(), c.getBlue()));
+		this.setToolTip(new Label(state.getLabel()));
+	}
+	
+	private void setModel(BlockModel model) {
+		this.model = model;
+		Rectangle bound = state.getConstraint();
+		
+		int xoff = timeline.getOffset(model.getStart());
+		int xwidth = timeline.getOffset(model.getEnd())-xoff;
+
+		if ((xwidth<TimeLine.gap) && (model.isFinish())) {
+		    timeline.getMarker().addMarker(model.getStart(),xoff);
+		    timeline.getMarker().addMarker(model.getEnd(),xoff+state.getConstraint().width);
+		    xwidth = timeline.getOffset(model.getEnd())-xoff;
+		}
+		
+		setConstraint(new Rectangle(xoff,bound.y,xwidth,bound.height));
+	}
+	
+	public void extendTo(int value) {
+		Rectangle bound = state.getConstraint();
+		int xoff = timeline.getOffset(model.getStart());
+		int xwidth = timeline.getOffset(value)-xoff;
+		setConstraint(new Rectangle(xoff,bound.y,xwidth,bound.height));		
+	}
+	
+	private void setConstraint(Rectangle r) {
+		constraint = r;
+	}
+	
+	public Rectangle getConstraint() {
+		return constraint;
+	}
+	
+	private int colorMod(int oldcol, int delta) {
+		oldcol = ((int)Math.round((double)oldcol*0.2) + delta);
+		if (oldcol<0) return 0;
+		if (oldcol>255) return 255;
+		return oldcol;
+	}
+	
+	public void setColor(RGB c) {		
+		colReg.put(COLOR_BASE, c);		
+		colReg.put(COLOR_FADE, new RGB(colorMod(c.red,200),colorMod(c.green,200),colorMod(c.blue,200)));
+		colReg.put(COLOR_BORDER, new RGB(colorMod(c.red,100),colorMod(c.green,100),colorMod(c.blue,100)));
+		setActive(active);
+	}
+
+	public void setActive(boolean b) {
+		active = b;		
+		Color c = colReg.get(COLOR_BASE);
+		if (active) {
+			bgColor = colReg.get(COLOR_BASE);
+			if (c.getRed()+c.getGreen()+c.getBlue()>250)
+				fgColor = ColorConstants.black;
+			else 
+				fgColor = ColorConstants.white;
+		} else {
+			fgColor = colReg.get(COLOR_BORDER);
+			bgColor = colReg.get(COLOR_FADE);			
+		}
+	}
+
+	protected void paintFigure(Graphics g2d) {
+		//Graphics2D g2d = (Graphics2D)gr;		
+		//Rectangle bound = (Rectangle)getParent().getLayoutManager().getConstraint(this);
+		Rectangle clArea = getClientArea();
+		Rectangle bound = getConstraint();		
+
+		//g2d.setBackgroundColor(ColorConstants.cyan);
+		//g2d.fillRectangle(0,0,400,400);
+
+		//g2d.clearRect(0,0,bound.width,bound.height);		
+		g2d.setBackgroundColor(bgColor);
+		g2d.setForegroundColor(fgColor);
+		
+		String shape = state.getShape();
+		if (shape.equals(StateNodeModel.P_SHAPE_STYLE_ELLIPSE)) {
+		    int hbound = bound.height;
+		    if (bound.width<bound.height) hbound = bound.width;
+		    g2d.fillOval(clArea.x,clArea.y,hbound,bound.height);
+		    g2d.fillOval(clArea.x+bound.width-hbound,clArea.y,hbound,bound.height);		    
+		    g2d.drawArc(clArea.x,clArea.y,hbound,bound.height,90,180);
+		    g2d.drawArc(clArea.x+bound.width-hbound,clArea.y,hbound,bound.height,270,180);		    
+		    int xoff = clArea.x+hbound/2;
+		    g2d.fillRectangle(xoff,clArea.y,bound.width-hbound,bound.height);
+		    g2d.drawLine(xoff,clArea.y,xoff+bound.width-hbound,clArea.y);
+		    g2d.drawLine(xoff-2,clArea.y+bound.height-1,xoff+bound.width-hbound+2,clArea.y+bound.height-1);
+		} else if (shape.equals(StateNodeModel.P_SHAPE_STYLE_HEXAGON)){
+		    int hbound = state.getConstraint().width/6;
+		    if (2*hbound>bound.width) hbound = bound.width/6;
+
+		    PointList plist = new PointList();
+			plist.addPoint(new Point(clArea.x+hbound,clArea.y));
+			plist.addPoint(new Point(clArea.x+bound.width-hbound,clArea.y));
+			plist.addPoint(new Point(clArea.x+bound.width-1,clArea.y+clArea.height/2));
+			plist.addPoint(new Point(clArea.x+bound.width-hbound,clArea.y+clArea.height-1));
+			plist.addPoint(new Point(clArea.x+hbound,clArea.y+clArea.height-1));
+			plist.addPoint(new Point(clArea.x,clArea.y+clArea.height/2));
+			g2d.fillPolygon(plist);
+			g2d.drawPolygon(plist);
+		}  else if (shape.equals(StateNodeModel.P_SHAPE_STYLE_ROUNDED_RECTANGLE)){
+		    Rectangle r = new Rectangle(clArea.x,clArea.y,bound.width,bound.height);
+		    g2d.fillRoundRectangle(r,8,8);		
+		    r = new Rectangle(clArea.x,clArea.y,bound.width-1,bound.height-1);
+			g2d.drawRoundRectangle(r,8,8);
+		} else {
+		    //if (shape.equals(StateNodeModel.P_SHAPE_STYLE_RECTANGLE)){
+		    // default style is RECTANGLE
+			g2d.fillRectangle(clArea.x,clArea.y,bound.width,bound.height);		
+			g2d.drawRectangle(clArea.x,clArea.y,bound.width-1,bound.height-1);		    
+		}
+		
+		String label = state.getLabel();
+		if (label==null) label = state.getId();
+		int swidth = g2d.getFontMetrics().getAverageCharWidth()*label.length();
+		int sheight = g2d.getFontMetrics().getHeight();
+		if (swidth<bound.width) {
+			g2d.drawString(label,clArea.x+(bound.width-swidth)/2,clArea.y+(bound.height-sheight)/2);
+		} else {
+			g2d.drawString(label,clArea.x+2,clArea.y+(bound.height-sheight)/2);
+		}
+	}
+	/**
+	 * @return Returns the model.
+	 */
+	public BlockModel getModel() {
+		return model;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java.j2d ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java.j2d
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java.j2d	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Block.java.j2d	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,82 @@
+/*
+ * Created on Nov 11, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.awt.Color;
+import java.awt.Component;
+import java.awt.Graphics;
+import java.awt.Rectangle;
+
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.storyboard.model.BlockModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class Block extends Component {
+	static final long serialVersionUID = 0xACAC0003;
+	
+	boolean active = false;
+	Color baseColor, fgColor, bgColor;
+	
+	BlockModel model;
+	StateNodeModel state;
+	int offset = 20;
+	int metric = 8;
+	
+	public Block() {
+		super();
+		setColor(new Color(220,220,220));
+	}
+	
+	public Block(BlockModel model, StateNodeModel state) {
+		this.model = model;
+		this.state = state;
+		org.eclipse.draw2d.geometry.Rectangle bound = state.getConstraint();		
+		setBounds(model.getStart()*metric+offset,bound.y,(model.getEnd()-model.getStart())*metric+1,bound.height);
+		org.eclipse.swt.graphics.Color c = state.getColor();
+		setColor(new Color(c.getRed(), c.getGreen(), c.getBlue()));
+	}
+	
+	public void setColor(Color c) {
+		baseColor = new Color(c.getRed(),c.getGreen(),c.getBlue());
+		setActive(active);
+	}
+
+	public void setActive(boolean b) {
+		active = b;		
+		Color c = baseColor;
+		if (active) {
+			bgColor = (new Color(c.getRed(),c.getGreen(),c.getBlue(),220));
+			if (c.getRed()+c.getGreen()+c.getBlue()>250)
+				fgColor = Color.BLACK;
+			else 
+				fgColor = Color.lightGray;
+		} else {
+			fgColor = (new Color(c.getRed(),c.getGreen(),c.getBlue(),150));
+			bgColor = (new Color(c.getRed(),c.getGreen(),c.getBlue(),80));			
+		}
+	}
+	
+	public void paint(Graphics g2d) {
+		//Graphics2D g2d = (Graphics2D)gr;
+		Rectangle bound = this.getBounds();		
+		//g2d.clearRect(0,0,bound.width,bound.height);
+		g2d.setColor(bgColor);		
+		g2d.fillRect(0,0,bound.width,bound.height);
+		g2d.setColor(fgColor);
+		g2d.drawRect(0,0,bound.width-1,bound.height-1);
+		String label = state.getLabel();
+		if (label==null) label = state.getId();
+		int swidth = g2d.getFontMetrics().stringWidth(label);
+		g2d.drawString(label,(bound.width-swidth)/2,bound.height/2);
+	}
+	/**
+	 * @return Returns the model.
+	 */
+	public BlockModel getModel() {
+		return model;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/DoubleBufferPanel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/DoubleBufferPanel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/DoubleBufferPanel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/DoubleBufferPanel.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,72 @@
+/*
+ * Created on Nov 17, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.awt.Graphics;
+import java.awt.Image;
+import java.awt.Panel;
+
+/**
+ * @author asangpet
+ */
+public class DoubleBufferPanel extends Panel {
+	static final long serialVersionUID = 0xACAC0006;
+
+	private int bufferWidth, bufferHeight;
+	private Image bufferImage;
+	private Graphics bufferGraphics;
+	
+	public DoubleBufferPanel() {
+		super(null);
+	}
+
+	public void update(Graphics g) {
+		paint(g);
+	}
+	
+	public void paint(Graphics g) {
+		if (bufferWidth!=getSize().width || bufferHeight!=getSize().height
+			|| bufferImage==null || bufferGraphics==null)
+			resetBuffer();
+			
+		if (bufferGraphics!=null) {
+			bufferGraphics.clearRect(0,0,bufferWidth,bufferHeight);
+			//super.paint(bufferGraphics);
+			paintBuffer(bufferGraphics);
+			g.drawImage(bufferImage,0,0,this);
+		}
+	}
+	
+	public void paintChildren(Graphics g) {
+		if (bufferGraphics!=null)
+			super.paint(g);
+	}
+	
+	private void resetBuffer() {
+		bufferWidth = getSize().width;
+		bufferHeight = getSize().height;
+		
+		if (bufferGraphics!=null) {
+			bufferGraphics.dispose();
+			bufferGraphics=null;
+		}
+		if (bufferImage != null) {
+			bufferImage.flush();
+			bufferImage=null;
+		}
+		System.gc();
+		bufferImage = createImage(bufferWidth,bufferHeight);
+		bufferGraphics = bufferImage.getGraphics();
+	}
+	
+	
+	/**
+	 * Paint this component to graphics buffer,
+	 * subclass should override this method for drawing
+	 * @param g
+	 */
+	public void paintBuffer(Graphics g) {
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageDialog.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageDialog.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageDialog.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageDialog.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,74 @@
+/*
+ * Created on Apr 22, 2005
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import org.eclipse.jface.window.Window;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.custom.ScrolledComposite;
+import org.eclipse.swt.events.PaintEvent;
+import org.eclipse.swt.events.PaintListener;
+import org.eclipse.swt.graphics.Image;
+import org.eclipse.swt.graphics.ImageData;
+import org.eclipse.swt.layout.GridData;
+import org.eclipse.swt.layout.GridLayout;
+import org.eclipse.swt.widgets.Canvas;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.Control;
+import org.eclipse.swt.widgets.Shell;
+
+/**
+ * 
+ * @author asangpet
+ */
+public class ImageDialog extends Window {
+    Image image;
+    String title=null;
+    
+    public ImageDialog(Shell parent, Image image) {
+        super(parent);
+        this.image = image;
+        this.setShellStyle( SWT.SHELL_TRIM );
+    }
+
+    protected void configureShell(Shell shell)
+    {
+        super.configureShell(shell);        
+        if (title != null)
+            shell.setText(title);
+    }	
+
+    public void setTitle(String title)
+    {
+        this.title = title;
+    }
+
+    
+    protected Control createContents(Composite parent)
+    {
+        ScrolledComposite composite = new ScrolledComposite(parent,SWT.H_SCROLL | SWT.V_SCROLL);
+        //composite.setSize(400,300);
+        //ScrolledComposite composite = (Composite) super.createDialogArea(parent);        
+        Canvas canvas = new Canvas(composite,SWT.FILL);
+        ImageData data = image.getImageData();
+        canvas.setSize(data.width,data.height);
+        canvas.addPaintListener(new PaintListener() {
+            public void paintControl(PaintEvent e) {
+                e.gc.drawImage(image,0,0);
+            }
+        });        
+        
+        composite.setContent(canvas);
+        GridLayout layout = new GridLayout();
+        layout.numColumns = 1;
+        parent.setLayout(layout);
+        GridData gd = new GridData();
+        gd.horizontalAlignment = SWT.FILL;
+        gd.verticalAlignment = SWT.FILL;
+        gd.grabExcessVerticalSpace = true;
+        gd.grabExcessHorizontalSpace = true;
+        composite.setLayoutData(gd);
+        parent.setSize(600,600);
+        return composite;
+    }
+  }
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageObject.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageObject.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageObject.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/ImageObject.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,209 @@
+package org.tekkotsu.ui.storyboard.components;
+
+import java.io.ByteArrayInputStream;
+import java.io.ByteArrayOutputStream;
+import java.io.FileWriter;
+
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Label;
+import org.eclipse.draw2d.MouseEvent;
+import org.eclipse.draw2d.MouseListener;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ImageDescriptor;
+import org.eclipse.jface.resource.ImageRegistry;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.graphics.Image;
+import org.eclipse.swt.graphics.ImageData;
+import org.eclipse.swt.graphics.ImageLoader;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+import org.tekkotsu.ui.storyboard.model.ImageModel;
+import org.tekkotsu.ui.storyboard.Base64;
+
+
+/**
+ * @author asangpet
+ *  
+ */
+public class ImageObject extends Figure
+{
+    boolean active = false;
+    
+    ImageRegistry imgReg;
+
+    Rectangle constraint;
+
+    ImageModel model;
+
+    StateNodeModel state;
+
+    TimeLine timeline;
+
+    org.tekkotsu.ui.editor.model.TransitionModel etrans;
+
+    int offset = TimeLine.xoffset;
+
+    int metric = TimeLine.gap;
+
+    public ImageObject(ImageModel model, StateNodeModel state,
+            TimeLine timeLine)
+    {
+        imgReg = ResourceRegistry.getInstance().getImageRegistry();
+        this.state = state;
+        this.timeline = timeLine;
+        setModel(model);
+        this.setToolTip(getToolTipFigure());
+        
+        addMouseListener(new MouseListener() {
+            /* (non-Javadoc)
+             * @see org.eclipse.draw2d.MouseListener#mouseDoubleClicked(org.eclipse.draw2d.MouseEvent)
+             */
+            public void mouseDoubleClicked(MouseEvent me) {                
+                ImageDialog imgDialog = new ImageDialog(ResourceRegistry.getInstance().getDisplay().getActiveShell(),imgReg.get(getImageName()));
+                imgDialog.setTitle("Image: "+getImageName());
+                imgDialog.open();
+            }
+            
+            /* (non-Javadoc)
+             * @see org.eclipse.draw2d.MouseListener#mousePressed(org.eclipse.draw2d.MouseEvent)
+             */
+            public void mousePressed(MouseEvent me) {
+            }
+            
+            /* (non-Javadoc)
+             * @see org.eclipse.draw2d.MouseListener#mouseReleased(org.eclipse.draw2d.MouseEvent)
+             */
+            public void mouseReleased(MouseEvent me) {
+            }
+        });
+    }
+
+    private IFigure getToolTipFigure() {
+        Label label = new Label("Record at:" + model.getTime() * .001 + "s");        
+        return label;
+    }
+
+    private String getImageName() {
+        return model.getImageName();
+    }
+    
+    private String getThumbImageName() {
+        return "thumb_"+model.getID()+model.getTime();
+    }
+    
+    private void setModel(ImageModel model)
+    {
+        this.model = model;
+        Rectangle bound = null;
+        if (state == null)
+            bound = new Rectangle(0, 6, 10, TimeLine.height);
+        else
+            bound = state.getConstraint();
+        
+        int xoff = timeline.getOffset(model.getStart());
+        try {            
+            final Image image = new Image(ResourceRegistry.getInstance().getDisplay(),model.getImageData());
+            ImageData tb = model.getImageData();
+            tb.alpha = 100;
+            final Image thumb = new Image(ResourceRegistry.getInstance().getDisplay(),tb.scaledTo(48,48));//bound.width,bound.height));
+            tb.alpha = -1;
+            
+            imgReg.put(getImageName(), image);
+            imgReg.put(getThumbImageName(), thumb);
+        } catch (IllegalArgumentException ex) {}
+        setConstraint(new Rectangle(xoff/*-data.width/2*/, bound.y
+                /*+ (bound.height - data.height) / 2 */, 48,48));//data.width, data.height));
+        //setConstraint(new Rectangle(xoff,bound.y+bound.height/2,16,16));
+    }
+
+    private void setConstraint(Rectangle r)
+    {
+        constraint = r;
+    }
+
+    public Rectangle getConstraint()
+    {
+        return constraint;
+    }
+
+    public void setActive(boolean b)
+    {
+    }
+
+    protected void paintFigure(Graphics g2d)
+    {
+        Rectangle clArea = getClientArea();
+        Rectangle bound = getConstraint();
+        
+        Image img = imgReg.get(getThumbImageName());
+        if (img!=null)
+            g2d.drawImage(imgReg.get(getThumbImageName()), new Point(clArea.x,
+                    clArea.y));
+    }
+
+    /**
+     * @return Returns the model.
+     */
+    public ImageModel getModel()
+    {
+        return model;
+    }
+    
+    /**
+     * Set layout index for this log object
+     * @param idx position (1-top,2-left,3-right)
+     */
+    public void setLayoutIndex(int idx) {
+        if (model.getLayoutIndex() == 0) model.setLayoutIndex(idx);
+        int xoff = timeline.getOffset(model.getStart());
+        idx = model.getLayoutIndex();
+        Rectangle bound = getConstraint();
+        if (idx==1) {            
+            bound.y=2;
+            bound.x=xoff-8;
+        } else if (idx==2) {
+            bound.y=10;
+            bound.x=xoff-12;
+        } else if (idx==3) {
+            bound.y=10;
+            bound.x=xoff-4;
+        } else {
+            bound.y=LogBar.height;
+        }
+        setConstraint(new Rectangle(bound)); 
+    }
+    
+    public static void test() {
+        try {
+        System.out.println("getting img");
+        ImageDescriptor desc = ImageDescriptor.createFromFile(
+                org.tekkotsu.ui.storyboard.icons.IconDummy.class, "vision.jpg");
+        
+        Image img = desc.createImage();        
+        ImageData imData = img.getImageData();
+        System.out.println("init image "+imData.width+" "+imData.height);
+        ImageLoader imLoad = new ImageLoader();
+        imLoad.data = new ImageData[] {imData};
+        ByteArrayOutputStream os = new ByteArrayOutputStream();
+        System.out.println("save to outstream");
+        imLoad.save(os,SWT.IMAGE_JPEG);
+        img.dispose();
+        
+        System.out.println("b64");        
+        String b64 = (Base64.encode(os.toByteArray()));
+        System.out.println("length:"+b64.length()+"\n");
+        FileWriter fw = new FileWriter("test.b64");        
+        fw.write(b64);
+        fw.close();
+        imLoad = new ImageLoader();
+        ByteArrayInputStream is = new ByteArrayInputStream(Base64.decode(b64));
+        imLoad.load(is);
+        imLoad.save("aug.jpg",SWT.IMAGE_JPEG);
+        } catch (Exception e) {
+            e.printStackTrace();
+        }
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogBar.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogBar.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogBar.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogBar.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,188 @@
+/*
+ * Created on Mar 29, 2005
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.util.Iterator;
+
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.MouseEvent;
+import org.eclipse.draw2d.MouseListener;
+import org.eclipse.draw2d.MouseMotionListener;
+import org.eclipse.draw2d.Panel;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ColorRegistry;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+
+/**
+ * 
+ * @author asangpet
+ */
+public class LogBar extends Panel implements PropertyChangeListener
+{
+	public static int gap = 8, halfgap = 4, xoffset = 20, height=28;//25;
+		
+	private ColorRegistry colorReg;
+	private boolean timeLock = false;
+	
+	int cursor = 0;
+	int timeLimit = TimeLine.TIMELINE_INIT_LIMIT;
+	int maxValue = 0;
+	double timeScale = 0.001;
+	Rectangle constraint;
+	TimeLine timeLine;
+	
+	public void setLimit(int time) {
+		timeLimit = time;
+		int voffset = TimeLine.height-1; //getParent().getClientArea().height - TimeLine.height;
+		constraint = new Rectangle(0,voffset,timeLine.getOffset(time),height);
+		getParent().getLayoutManager().setConstraint(this,constraint);
+		firePropertyChange(TimeLine.TIMELINE_LIMIT_CHANGED,null,constraint);
+	}
+	
+	public void setVerticalOffset(int voff) {
+	    int voffset = TimeLine.height-1; // getParent().getClientArea().height - TimeLine.height;
+	    Rectangle constraint = new Rectangle(0,voffset+voff,timeLine.getOffset(timeLimit),height);		
+		getParent().getLayoutManager().setConstraint(this,constraint);		
+		// firePropertyChange(TIMELINE_LIMIT_CHANGED,null,constraint);	    
+	}
+	
+	public int getLimit() {
+		return timeLimit;
+	}
+	
+	public void setLock(boolean locked) {
+		timeLock = locked;
+		if (locked) {
+			this.setValue(maxValue);
+		}
+	}
+	
+	public boolean isLock() {
+		return timeLock;
+	}
+	
+	public Rectangle getConstraint() {
+		return constraint;
+	}
+	
+	public double getTimeScale() {
+		return timeScale;
+	}
+	
+	/* (non-Javadoc)
+	 * @see org.eclipse.draw2d.Figure#paintFigure(org.eclipse.draw2d.Graphics)
+	 */
+	protected void paintFigure(Graphics gc) {
+	    super.paintFigure(gc);		    
+
+	    Rectangle bounds = getBounds();
+		
+		gc.setBackgroundColor(colorReg.get("timeline_bg"));
+		gc.fillRectangle(getBounds());
+		gc.setForegroundColor(colorReg.get("timeline_bgdim1"));
+		gc.drawLine(bounds.x, bounds.y+bounds.height-2, bounds.x+bounds.width, bounds.y+bounds.height-2);
+		gc.setForegroundColor(colorReg.get("timeline_bgdim2"));
+		gc.drawLine(bounds.x, bounds.y+bounds.height - 3, bounds.x+bounds.width, bounds.y+bounds.height - 3);
+		gc.setForegroundColor(colorReg.get("timeline_bgdim3"));
+		gc.drawLine(bounds.x, bounds.y+bounds.height - 4, bounds.x+bounds.width, bounds.y+bounds.height - 4);
+		
+		gc.setForegroundColor(colorReg.get("timeline_tick"));
+		gc.drawLine(bounds.x, bounds.y, bounds.x+bounds.width, bounds.y);
+		gc.drawLine(bounds.x, bounds.y+bounds.height - 1, bounds.x+bounds.width, bounds.y+bounds.height - 1);
+
+		//Font sansSerifFont = new Font("Sans", Font.PLAIN, 10);
+		//g2d.setFont(sansSerifFont);
+		int count = 4, metric = 0, xoff;
+		
+		// draw cursor
+		gc.setXORMode(true);
+		gc.setBackgroundColor(colorReg.get("timeline_cursor"));
+		gc.fillRectangle(bounds.x+ timeLine.getOffset(getValue())- TimeLine.halfgap, bounds.y+1, TimeLine.gap,
+				bounds.height - 2);
+		gc.setXORMode(false);
+	}
+	
+	/**
+	 * 
+	 */
+	public LogBar(TimeLine timeline) {	
+		//setBounds(new Rectangle(0,0,limit*gap,25));
+		timeLine = timeline;
+		
+		// initiate color registry
+		colorReg = ResourceRegistry.getInstance().getColorRegistry();
+		
+		// initialize event listener
+		addMouseListener(new MouseListener.Stub() {
+			public void mousePressed(MouseEvent me) {
+				if (me.button==1)
+					moveCursor(me.getLocation());
+			}
+		});
+		
+		addMouseMotionListener(new MouseMotionListener.Stub() {
+			public void mouseDragged(MouseEvent me) {
+				if (me.getState() == MouseEvent.BUTTON1)
+					moveCursor(me.getLocation());
+			}
+		});
+		
+	}
+
+	// move cursor to specific coordinate
+	public void moveCursor(Point p) {		
+	    int cursor = timeLine.getTime(p.x);
+		if (cursor<0) cursor = 0;
+		setValue(cursor);
+		firePropertyChange(TimeLine.TIMELINE_CURSOR_CHANGED, null, new Integer(this.cursor));
+	}
+	
+	// set cursor to the specified time unit
+	public void setValue(int value) {
+		if (maxValue<value) maxValue = value;
+		cursor = value;
+		if (cursor<0) cursor = 0;		
+		repaint();
+	}
+	
+	// get the current cursor position
+	public int getValue() {
+		return cursor;
+	}
+
+	public void propertyChange(PropertyChangeEvent evt) {	
+		if (evt.getPropertyName().equals(TimeLine.TIMELINE_CURSOR_CHANGED)) {
+			setValue(((Integer) evt.getNewValue()).intValue());
+		}
+	}	
+	
+    public void addChild(IFigure figure) {
+        Rectangle rect = null;
+        add(figure);
+              
+        if (figure instanceof LogObject) {
+            LogObject fig = (LogObject)figure;
+            rect = fig.getConstraint();            
+            // scan for close figure
+            int curoff = timeLine.getOffset(fig.getModel().getTime());
+            int idx = 0;
+            for (Iterator iter = getChildren().iterator(); iter.hasNext(); ) {
+                Object child = iter.next();
+                if ((child instanceof LogObject) && (fig.getModel()!=((LogObject)child).getModel())) {
+                    LogObject clog = (LogObject)child;
+                    int coff = timeLine.getOffset(clog.getModel().getTime());
+                    if (Math.abs(coff-curoff)<8) {
+                        clog.setLayoutIndex(++idx);
+                    }
+                }
+            }
+            fig.setLayoutIndex(++idx);
+        }
+    }
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogObject.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogObject.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogObject.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/LogObject.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,155 @@
+package org.tekkotsu.ui.storyboard.components;
+
+import java.util.List;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.Label;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ImageDescriptor;
+import org.eclipse.jface.resource.ImageRegistry;
+import org.eclipse.swt.graphics.ImageData;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+import org.tekkotsu.ui.storyboard.model.LogModel;
+
+/**
+ * @author asangpet
+ *  
+ */
+public class LogObject extends Figure
+{
+    boolean active = false;
+
+    ImageRegistry imgReg;
+
+    Rectangle constraint;
+
+    LogModel model;
+
+    StateNodeModel state;
+
+    TimeLine timeline;
+
+    org.tekkotsu.ui.editor.model.TransitionModel etrans;
+
+    List nodeList;
+
+    int offset = TimeLine.xoffset;
+
+    int metric = TimeLine.gap;
+
+    public LogObject(LogModel model, StateNodeModel state,
+            TimeLine timeLine)
+    {
+        imgReg = ResourceRegistry.getInstance().getImageRegistry();
+        this.state = state;
+        this.timeline = timeLine;
+        setModel(model);
+        this.setToolTip(getToolTipFigure());
+    }
+
+    private IFigure getToolTipFigure() {
+        Label label = new Label("Time:" + model.getTime() * .001 + "s\n"
+                + model.getETIDString()+ "\n"+ model.getContent());
+        if (model.getETID().equals(LogModel.ETID_ACTIVATE)) {
+            label.setForegroundColor(ColorConstants.darkGreen);
+        } else
+        if (model.getETID().equals(LogModel.ETID_DEACTIVATE)) {
+            label.setForegroundColor(ColorConstants.red);
+        } else if (model.getETID().equals(LogModel.ETID_STATUS)) {
+            label.setForegroundColor(ColorConstants.blue);
+        }
+        return label;
+    }
+    
+    private void setModel(LogModel model)
+    {
+        this.model = model;
+        Rectangle bound = null;
+        if (state == null)
+            bound = new Rectangle(0, 6, 10, TimeLine.height);
+        else
+            bound = state.getConstraint();
+        
+        int xoff = timeline.getOffset(model.getStart());
+        try {
+            imgReg.put(model.getIconName(), ImageDescriptor.createFromFile(
+                org.tekkotsu.ui.storyboard.icons.IconDummy.class, model
+                        .getIconName()));
+        } catch (IllegalArgumentException ex) {}
+        ImageData data = imgReg.getDescriptor(model.getIconName())
+                .getImageData();
+        setConstraint(new Rectangle(xoff-data.width/2, bound.y
+                + (bound.height - data.height) / 2, data.width, data.height));
+        //setConstraint(new Rectangle(xoff,bound.y+bound.height/2,16,16));
+    }
+
+    private void setConstraint(Rectangle r)
+    {
+        constraint = r;
+    }
+
+    public Rectangle getConstraint()
+    {
+        return constraint;
+    }
+
+    public void setActive(boolean b)
+    {
+    }
+
+    protected void paintFigure(Graphics g2d)
+    {
+        Rectangle clArea = getClientArea();
+        Rectangle bound = getConstraint();
+
+        g2d.drawImage(imgReg.get(model.getIconName()), new Point(clArea.x,
+                clArea.y));
+        
+        if (model.getETID().equals(LogModel.ETID_DEACTIVATE)) {
+            g2d.setForegroundColor(ColorConstants.red);
+            g2d.setLineWidth(3);
+            g2d.drawLine(clArea.x,clArea.y,clArea.x+bound.width, clArea.y+bound.height);            
+        } else if (model.getETID().equals(LogModel.ETID_STATUS)) {
+            g2d.setForegroundColor(ColorConstants.blue);
+            g2d.setLineWidth(3);
+            g2d.drawLine(clArea.x,clArea.y+bound.height-2,clArea.x+bound.width, clArea.y+bound.height-2);                    
+        }
+    }
+
+    /**
+     * @return Returns the model.
+     */
+    public LogModel getModel()
+    {
+        return model;
+    }
+    
+    /**
+     * Set layout index for this log object
+     * @param idx position (1-top,2-left,3-right)
+     */
+    public void setLayoutIndex(int idx) {
+        if (model.getLayoutIndex() == 0) model.setLayoutIndex(idx);
+        int xoff = timeline.getOffset(model.getStart());
+        idx = model.getLayoutIndex();
+        Rectangle bound = getConstraint();
+        if (idx==1) {            
+            bound.y=2;
+            bound.x=xoff-8;
+        } else if (idx==2) {
+            bound.y=10;
+            bound.x=xoff-12;
+        } else if (idx==3) {
+            bound.y=10;
+            bound.x=xoff-4;
+        } else {
+            bound.y=LogBar.height;
+        }
+        setConstraint(new Rectangle(bound)); 
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java	2006-02-14 00:22:32.000000000 -0500
@@ -0,0 +1,244 @@
+/*
+ * Created on Nov 11, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.util.HashSet;
+import java.util.Iterator;
+import java.util.List;
+import java.util.Set;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.draw2d.MouseEvent;
+import org.eclipse.draw2d.MouseListener;
+import org.eclipse.draw2d.MouseMotionListener;
+import org.eclipse.draw2d.Panel;
+import org.eclipse.draw2d.geometry.Dimension;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.viewers.StructuredSelection;
+import org.tekkotsu.ui.storyboard.views.StoryboardViewer;
+
+/**
+ * @author asangpet
+ *  
+ */
+
+public class Storyboard extends Panel implements PropertyChangeListener {
+
+    static final int preferredWidth = 800, preferredHeight = 25;
+
+    public static final String PROP_DIM_CHANGE = "_prop_dim_change";
+
+    int gap = 8, halfgap = 4, xoffset = 20;
+
+    int cursor = 0;
+
+    boolean mouseDown = false;
+
+    StoryboardViewer parentViewer;
+
+    TimeLine timeLine;
+
+    public Storyboard(StoryboardViewer viewer, TimeLine timeline) {
+        super();
+        timeLine = timeline;
+        parentViewer = viewer;
+
+        // initialize event listener
+        addMouseListener(new MouseListener.Stub() {
+            public void mousePressed(MouseEvent me) {
+                if (me.button == 1)
+                    moveCursor(me.getLocation());
+            }
+        });
+
+        addMouseMotionListener(new MouseMotionListener.Stub() {
+            public void mouseDragged(MouseEvent me) {
+                if (me.getState() == MouseEvent.BUTTON1)
+                    moveCursor(me.getLocation());
+            }
+        });
+    }
+
+    public void addChild(IFigure figure) {
+        add(figure);
+        Rectangle rect = null;
+        if (figure instanceof Block)
+            rect = ((Block) figure).getConstraint();
+        if (figure instanceof Transition)
+            rect = ((Transition) figure).getConstraint();
+        if (figure instanceof LogObject)
+            rect = ((LogObject) figure).getConstraint();
+        if (figure instanceof ImageObject)
+            rect = ((ImageObject) figure).getConstraint();
+        if (rect != null) {
+            Rectangle newrect = new Rectangle((Rectangle) getParent()
+                    .getLayoutManager().getConstraint(this));
+            if (rect.y + rect.height > newrect.height) {
+                newrect.height = rect.y + rect.height;
+                getParent().getLayoutManager().setConstraint(this, newrect);
+            }
+        }
+    }
+
+    public void propertyChange(PropertyChangeEvent evt) {
+        if (evt.getPropertyName().equals(TimeLine.TIMELINE_CURSOR_CHANGED)) {
+            setValue(((Integer) evt.getNewValue()).intValue());
+        } else if (evt.getPropertyName().equals(PROP_DIM_CHANGE)) {
+            Rectangle newrect = new Rectangle((Rectangle) getParent()
+                    .getLayoutManager().getConstraint(this));
+            newrect.height = ((Rectangle) evt.getNewValue()).height
+                    - TimeLine.height - TimeLine.height;
+            getParent().getLayoutManager().setConstraint(this, newrect);
+        } else if (evt.getPropertyName()
+                .equals(TimeLine.TIMELINE_LIMIT_CHANGED)) {
+            Rectangle newrect = new Rectangle((Rectangle) getParent()
+                    .getLayoutManager().getConstraint(this));
+            newrect.width = ((Rectangle) evt.getNewValue()).width;
+            //System.out.println(newrect);
+            getParent().getLayoutManager().setConstraint(this, newrect);
+        }
+    }
+
+    public void setLimit(int time) {
+    	Rectangle newrect = new Rectangle((Rectangle) getParent()
+                .getLayoutManager().getConstraint(this));        
+        newrect.width = timeLine.getOffset(time);
+        getParent().getLayoutManager().setConstraint(this, newrect);	
+    }
+    
+    /**
+     * Move cursor to a specific time located by point P
+     * 
+     * @param p
+     *            a point which the cursor should move to
+     */
+    public void moveCursor(Point p) {
+        int cursor = timeLine.getTime(p.x);
+        if (cursor < 0)
+            cursor = 0;
+        setValue(cursor);
+        firePropertyChange(TimeLine.TIMELINE_CURSOR_CHANGED, null, new Integer(
+                this.cursor));
+    }
+
+    /**
+     * Set cursor at a specific point in time
+     * 
+     * @param cursor
+     *            time which the cursor should move to
+     */
+    public void setValue(int cursor) {
+        boolean changed = this.cursor != cursor;
+
+        this.cursor = cursor;
+        if (cursor < 0)
+            cursor = 0;
+
+        // extends all unfinished block
+        if (timeLine.isLock()) {
+            Iterator itr = this.getChildren().iterator();
+            while (itr.hasNext()) {
+                IFigure figure = (IFigure) itr.next();
+                if (figure instanceof Block) {
+                    Block block = (Block) figure;
+                    if (!block.model.isFinish()) {
+                        block.extendTo(cursor);
+                        getLayoutManager().setConstraint(block,
+                                block.getConstraint());
+                        //Rectangle realcon =
+                        // (Rectangle)getLayoutManager().getConstraint(block);
+                        this.layout();
+                        //System.out.println(">"+block.model.getStart()+","+cursor*500+":"+realcon);
+                    }
+                }
+            }
+        }
+
+        // set proper highlighting
+        if (changed) {
+            //Component[] components = this.getComponents();
+            List components = this.getChildren();
+            Set selectSet = new HashSet();
+            int tcursor = timeLine.getOffset(getValue());
+
+            Iterator iter = components.iterator();
+            while (iter.hasNext()) {
+                Object component = iter.next();
+                if (component instanceof ImageObject) {
+                    ImageObject img = (ImageObject) component;
+                    Rectangle bound = img.getConstraint();
+                    int starttime = bound.x;
+                    int endtime = bound.x + bound.width - 1;
+                    if (starttime <= tcursor && endtime >= tcursor) {
+                        selectSet.add(img.getModel());
+                    }
+                } else if (component instanceof LogObject) {
+                    LogObject log = (LogObject) component;
+                    Rectangle bound = log.getConstraint();
+                    int starttime = bound.x;
+                    int endtime = bound.x + bound.width - 1;
+                    if (starttime <= tcursor && endtime >= tcursor) {
+                        selectSet.add(log.getModel());
+                    }
+                } else if (component instanceof Transition) {
+                    Transition t = (Transition) component;
+                    Rectangle bound = t.getConstraint();
+                    int starttime = bound.x;
+                    int endtime = bound.x + bound.width - 1;
+                    int temp=0;
+                    if (timeLine.isLock()) temp=8; 
+                    if (starttime-temp <= tcursor && endtime+temp >= tcursor) {
+                        selectSet.add(t.getModel());
+                        t.setActive(true);
+                    } else
+                        t.setActive(false);
+                } else if (component instanceof Block) {
+                    Block block = (Block) component;
+                    Rectangle bound = block.getConstraint();
+                    int starttime = bound.x;
+                    int endtime = bound.x + bound.width - 1;
+                    if (starttime-2 <= tcursor && endtime+2 >= tcursor) {
+                        selectSet.add(block.getModel());
+                        block.setActive(true);
+                    } else {
+                        block.setActive(false);
+                    }
+                }
+            }
+            StructuredSelection selection = new StructuredSelection(selectSet
+                    .toArray());
+            parentViewer.setSelection(selection);
+        }
+
+        //drawBuffer();
+        repaint();
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.draw2d.Figure#paintFigure(org.eclipse.draw2d.Graphics)
+     */
+    protected void paintFigure(Graphics g) {
+        super.paintFigure(g);
+        Dimension dim = getSize();
+        //paintChildren(g);
+
+        // draw cursor
+        g.setForegroundColor(ColorConstants.red);
+        g.drawLine(timeLine.getOffset(getValue()), TimeLine.height, timeLine
+                .getOffset(getValue()), TimeLine.height + LogBar.height
+                + dim.height - 1);
+
+    }
+
+    public int getValue() {
+        return cursor;
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java.j2d ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java.j2d
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java.j2d	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Storyboard.java.j2d	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,164 @@
+/*
+ * Created on Nov 11, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.awt.Color;
+import java.awt.Component;
+import java.awt.Dimension;
+import java.awt.Graphics;
+import java.awt.Point;
+import java.awt.event.ComponentAdapter;
+import java.awt.event.ComponentEvent;
+import java.awt.event.MouseAdapter;
+import java.awt.event.MouseEvent;
+import java.awt.event.MouseMotionAdapter;
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.util.HashSet;
+import java.util.Set;
+
+import org.eclipse.jface.viewers.StructuredSelection;
+import org.tekkotsu.ui.storyboard.views.StoryboardViewer;
+
+/**
+ * @author asangpet
+ *  
+ */
+
+public class Storyboard extends DoubleBufferPanel implements PropertyChangeListener {
+	static final long serialVersionUID = 0xACAC0002;
+
+	static final int preferredWidth = 800, preferredHeight = 25;
+
+	int gap = 8, halfgap = 4, xoffset = 20;
+
+	int cursor = 0;
+
+	boolean mouseDown = false;
+	StoryboardViewer parentViewer;
+
+	//protected BufferedImage img_buffer = null;
+
+	//protected Graphics2D g_context;
+
+	public Storyboard(StoryboardViewer viewer) {
+		super();
+		//this.setLayout(null);
+		parentViewer = viewer;
+		
+		this.addMouseListener(new MouseAdapter() {
+			public void mouseClicked(MouseEvent e) {
+				if (e.getButton() == MouseEvent.BUTTON1)
+					moveCursor(e.getPoint());
+			}
+		});
+
+		this.addMouseMotionListener(new MouseMotionAdapter() {
+			public void mouseDragged(MouseEvent e) {
+				if ((e.getModifiersEx() & MouseEvent.BUTTON1_DOWN_MASK) != 0)
+					moveCursor(e.getPoint());
+			}
+		});
+
+		this.addComponentListener(new ComponentAdapter() {
+			public void componentShown(ComponentEvent e) {
+				//drawBuffer();
+				repaint();
+			}
+
+			public void componentResized(ComponentEvent e) {
+				Dimension dim = getSize();
+				if (dim.width <= 0)
+					dim.width = 1;
+				if (dim.height <= 0)
+					dim.height = 1;
+				//img_buffer = (BufferedImage) createImage(dim.width, dim.height);
+				//drawBuffer();
+				repaint();
+			}
+		});
+
+		setPreferredSize(new Dimension(preferredWidth, preferredHeight));
+	}
+
+	public void propertyChange(PropertyChangeEvent evt) {		
+		if (evt.getPropertyName().equals(TimeLine.TIMELINE_CURSOR_CHANGED)) {
+			setCursor(((Integer) evt.getNewValue()).intValue());
+		}
+	}
+
+	
+	/**
+	 * Move cursor to a specific time located by point P
+	 * @param p a point which the cursor should move to
+	 */
+	public void moveCursor(Point p) {
+		int cursor = (p.x - xoffset) / gap;
+		if (cursor < 0)
+			cursor = 0;
+		setCursor(cursor);
+		firePropertyChange(TimeLine.TIMELINE_CURSOR_CHANGED, null, new Integer(
+				this.cursor));
+	}
+
+	/**
+	 * Set cursor at a specific point in time
+	 * @param cursor time which the cursor should move to
+	 */
+	public void setCursor(int cursor) {
+		boolean changed = this.cursor != cursor;
+				
+		this.cursor = cursor;
+		if (cursor < 0)
+			cursor = 0;
+		
+		if (changed) {
+			Component[] components = this.getComponents();
+			Set selectSet = new HashSet();
+		
+			for (int i = 0; i < components.length; i++) {
+				if (components[i] instanceof Transition) {
+					Transition t = (Transition)components[i];
+					int time=t.getModel().getTime();
+					if (time==cursor) {
+						selectSet.add(t.getModel());
+						t.setActive(true);
+						//setComponentZOrder(t,0);
+					} else t.setActive(false);
+				} else
+				if (components[i] instanceof Block) {
+					Block block = (Block) components[i];
+					int starttime = block.getModel().getStart();
+					int endtime = block.getModel().getEnd();
+					if (starttime <= cursor && endtime >= cursor) {
+						selectSet.add(block.getModel());
+						block.setActive(true);
+						//this.setComponentZOrder(block,1);
+					} else {
+						block.setActive(false);
+					}
+				}
+			}
+			StructuredSelection selection = new StructuredSelection(selectSet.toArray());
+			parentViewer.setSelection(selection);
+		}
+
+		//drawBuffer();
+		repaint();
+	}
+
+	public void paintBuffer(Graphics g) {
+		Dimension dim = getSize();
+		paintChildren(g);
+		// draw cursor
+		g.setColor(new Color(255, 0, 0));
+		g.drawLine(xoffset + getValue() * gap, 0, xoffset + getValue() * gap,
+				dim.height - 1);		
+
+	}
+
+	public int getValue() {
+		return cursor;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java	2005-10-11 06:12:58.000000000 -0400
@@ -0,0 +1,242 @@
+/*
+ * Created on Nov 9, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.text.DecimalFormat;
+import java.text.NumberFormat;
+
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.MouseEvent;
+import org.eclipse.draw2d.MouseListener;
+import org.eclipse.draw2d.MouseMotionListener;
+import org.eclipse.draw2d.geometry.Point;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ColorRegistry;
+import org.eclipse.swt.graphics.RGB;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+
+public class TimeLine extends Figure implements PropertyChangeListener {
+    public static int gap = 8, halfgap = 4, xoffset = 20, height = 25;
+
+    public static final String TIMELINE_CURSOR_CHANGED = "_time_change";
+
+    public static final String TIMELINE_LIMIT_CHANGED = "_time_limit";
+
+    public static final int TIMELINE_INIT_LIMIT = 200000;
+
+    private ColorRegistry colorReg;
+
+    private boolean timeLock = false;
+
+    TimeMarker marker;
+
+    int cursor = 0;
+
+    int timeLimit = TIMELINE_INIT_LIMIT;
+
+    int maxValue = 0;
+
+    double timeScale = 0.001;
+
+    Rectangle constraint;
+
+    public int getOffset(int time) {
+        return marker.getOffset(time);
+    }
+
+    public int getTime(int offset) {
+        return marker.getTime(offset);
+    }
+
+    public TimeMarker getMarker() {
+        return marker;
+    }
+
+    public void setLimit(int time) {
+        timeLimit = time;
+        constraint = new Rectangle(0, 0, getOffset(timeLimit), TimeLine.height);
+        getParent().getLayoutManager().setConstraint(this, constraint);
+        firePropertyChange(TIMELINE_LIMIT_CHANGED, null, constraint);
+    }
+
+    public void setVerticalOffset(int voff) {
+        Rectangle constraint = new Rectangle(0, voff, getOffset(timeLimit),
+                TimeLine.height);
+        getParent().getLayoutManager().setConstraint(this, constraint);
+        // firePropertyChange(TIMELINE_LIMIT_CHANGED,null,constraint);
+    }
+
+    public int getLimit() {
+        return timeLimit;
+    }
+
+    public void setLock(boolean locked) {
+        timeLock = locked;
+        if (locked) {
+            this.setValue(maxValue);
+        }
+    }
+
+    public boolean isLock() {
+        return timeLock;
+    }
+
+    public Rectangle getConstraint() {
+        return constraint;
+    }
+
+    public double getTimeScale() {
+        return timeScale;
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.draw2d.Figure#paintFigure(org.eclipse.draw2d.Graphics)
+     */
+    protected void paintFigure(Graphics gc) {
+        Rectangle bounds = getBounds();
+
+        gc.setBackgroundColor(colorReg.get("timeline_bg"));
+        gc.fillRectangle(getBounds());
+        gc.setForegroundColor(colorReg.get("timeline_bgdim1"));
+        gc.drawLine(bounds.x, bounds.y + bounds.height - 2, bounds.x
+                + bounds.width, bounds.y + bounds.height - 2);
+        gc.setForegroundColor(colorReg.get("timeline_bgdim2"));
+        gc.drawLine(bounds.x, bounds.y + bounds.height - 3, bounds.x
+                + bounds.width, bounds.y + bounds.height - 3);
+        gc.setForegroundColor(colorReg.get("timeline_bgdim3"));
+        gc.drawLine(bounds.x, bounds.y + bounds.height - 4, bounds.x
+                + bounds.width, bounds.y + bounds.height - 4);
+
+        gc.setForegroundColor(colorReg.get("timeline_tick"));
+        gc.drawLine(bounds.x, bounds.y, bounds.x + bounds.width, bounds.y);
+        gc.drawLine(bounds.x, bounds.y + bounds.height - 1, bounds.x
+                + bounds.width, bounds.y + bounds.height - 1);
+
+        //Font sansSerifFont = new Font("Sans", Font.PLAIN, 10);
+        //g2d.setFont(sansSerifFont);
+        int count = 4, metric = 0, xoff;
+        int x = 0;
+        int cwidth = gc.getFontMetrics().getAverageCharWidth();
+        for (int t = 0; x < bounds.width; t += 1000) {
+            x = getOffset(t);
+            gc.drawLine(bounds.x + x, bounds.y + 2, bounds.x + x, bounds.y + 4);
+            gc.drawLine(bounds.x + x, bounds.y + bounds.height - 3, bounds.x
+                    + x, bounds.y + bounds.height - 5);
+            if (count == 4) {
+                gc.setForegroundColor(colorReg.get("timeline_text"));
+                xoff = x - ("" + metric).length() * cwidth / 2;
+                gc.drawString(metric + "", bounds.x + xoff, bounds.y + 6);
+                gc.setForegroundColor(colorReg.get("timeline_tick"));
+                count = 0;
+            } else
+                count++;
+            metric++;
+        }
+
+        NumberFormat nf = new DecimalFormat("0.###");
+        nf.setMaximumFractionDigits(2);
+        int lastoff = marker.getOffset(0), nextoff = marker.getOffset(5000);
+        for (int i = 1; i < marker.timeVec.size(); i++) {
+            int time = marker.timeVec.get(i);
+            if (i < marker.offsetVec.size() - 1)
+                nextoff = marker.offsetVec.get(i + 1);
+            x = marker.offsetVec.get(i);
+
+            // draw marker
+            gc.setForegroundColor(colorReg.get("timeline_tick"));
+            gc.drawLine(bounds.x + x, bounds.y + 2, bounds.x + x, bounds.y + 4);
+            gc.drawLine(bounds.x + x, bounds.y + bounds.height - 3, bounds.x
+                    + x, bounds.y + bounds.height - 5);
+
+            // draw timer (if possible)
+            String label = nf.format(time * 0.001f);
+            int lwidth = cwidth * label.length() / 2;
+
+            xoff = x - lwidth;
+            int nextTick = getOffset(((time/5000)+1)*5000);
+            if ((xoff - lastoff > 2) && (nextTick-lwidth>x+2)) {
+                gc.setForegroundColor(colorReg.get("timeline_text"));
+                gc.drawString(label, bounds.x + xoff, bounds.y + 6);
+            }
+            lastoff = x + lwidth;
+        }
+
+        // draw cursor
+        gc.setXORMode(true);
+        gc.setBackgroundColor(colorReg.get("timeline_cursor"));
+        gc.fillRectangle(bounds.x + marker.getOffset(getValue()) - halfgap,
+                bounds.y + 1, gap, bounds.height - 2);
+        gc.setXORMode(false);
+    }
+
+    /**
+     *  
+     */
+    public TimeLine() {
+        //setBounds(new Rectangle(0,0,limit*gap,25));
+
+        // initiate color registry
+        colorReg = ResourceRegistry.getInstance().getColorRegistry();
+        colorReg.put("timeline_bg", new RGB(235, 235, 228));
+        colorReg.put("timeline_bgdim1", new RGB(209, 209, 203));
+        colorReg.put("timeline_bgdim2", new RGB(218, 218, 211));
+        colorReg.put("timeline_bgdim3", new RGB(226, 226, 220));
+        colorReg.put("timeline_tick", new RGB(128, 128, 128));
+        colorReg.put("timeline_text", new RGB(0, 0, 0));
+        colorReg.put("timeline_cursor", new RGB(0, 128, 128));
+
+        // initialize event listener
+        addMouseListener(new MouseListener.Stub() {
+            public void mousePressed(MouseEvent me) {
+                if (me.button == 1)
+                    moveCursor(me.getLocation());
+            }
+        });
+
+        addMouseMotionListener(new MouseMotionListener.Stub() {
+            public void mouseDragged(MouseEvent me) {
+                if (me.getState() == MouseEvent.BUTTON1)
+                    moveCursor(me.getLocation());
+            }
+        });
+
+        marker = new TimeMarker(xoffset, gap, (float) timeScale);
+    }
+
+    // move cursor to specific coordinate
+    public void moveCursor(Point p) {
+        int cursor = marker.getTime(p.x);
+        if (cursor < 0)
+            cursor = 0;
+        setValue(cursor);
+        firePropertyChange(TimeLine.TIMELINE_CURSOR_CHANGED, null, new Integer(
+                this.cursor));
+    }
+
+    // set cursor to the specified time unit
+    public void setValue(int value) {
+        if (maxValue < value)
+            maxValue = value;
+        cursor = value;
+        if (cursor < 0)
+            cursor = 0;
+        repaint();
+    }
+
+    // get the current cursor position
+    public int getValue() {
+        return cursor;
+    }
+
+    public void propertyChange(PropertyChangeEvent evt) {
+        if (evt.getPropertyName().equals(TimeLine.TIMELINE_CURSOR_CHANGED)) {
+            setValue(((Integer) evt.getNewValue()).intValue());
+        }
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java.j2d ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java.j2d
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java.j2d	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeLine.java.j2d	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,130 @@
+/*
+ * Created on Nov 9, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.awt.*;
+import java.awt.event.ComponentAdapter;
+import java.awt.event.ComponentEvent;
+import java.awt.event.MouseAdapter;
+import java.awt.event.MouseEvent;
+import java.awt.event.MouseMotionAdapter;
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+
+public class TimeLine 
+	extends DoubleBufferPanel
+	implements PropertyChangeListener {
+	
+	static final long serialVersionUID = 0xACAC0001;
+	static final int preferredWidth = 800, preferredHeight = 25;
+	public static final String TIMELINE_CURSOR_CHANGED = "_time_change";
+	
+	int gap = 8, halfgap = 4, xoffset = 20;
+
+	int cursor = 0;
+
+	boolean mouseDown = false;
+	
+	public TimeLine() {
+		super();
+		this.addMouseListener(new MouseAdapter() {
+			public void mouseClicked(MouseEvent e) {
+				if (e.getButton() == MouseEvent.BUTTON1)
+					moveCursor(e.getPoint());
+			}
+		});
+		
+		this.addMouseMotionListener(new MouseMotionAdapter() {
+			public void mouseDragged(MouseEvent e) {
+				if ((e.getModifiersEx() & MouseEvent.BUTTON1_DOWN_MASK) != 0)
+					moveCursor(e.getPoint());
+			}
+		});
+		
+		this.addComponentListener(new ComponentAdapter() {
+			public void componentShown(ComponentEvent e) {
+				repaint();
+			}
+			public void componentResized(ComponentEvent e) {
+				repaint();
+			}			
+		});
+		
+		setPreferredSize(new Dimension(preferredWidth, preferredHeight));
+	}	
+	
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals(TimeLine.TIMELINE_CURSOR_CHANGED)) {
+			setCursor(((Integer)evt.getNewValue()).intValue());
+		}
+	}
+	
+	public void moveCursor(Point p) {		
+		int cursor = (p.x - xoffset) / gap;
+		if (cursor<0) cursor = 0;
+		setCursor(cursor);
+		firePropertyChange(TimeLine.TIMELINE_CURSOR_CHANGED, null, new Integer(this.cursor));
+	}
+	
+	public void setCursor(int cursor) {
+		this.cursor = cursor;
+		if (cursor<0) cursor = 0;
+		repaint();
+	}
+		
+	public void paintBuffer(Graphics g) {
+		Dimension dim = getSize();
+		boolean recreate = false;
+		if ((dim.width<=0) || (dim.height<=0)) return;
+		
+		Graphics2D g2d = (Graphics2D)g;
+		
+		Color bgColor = new Color(235, 235, 228);
+		g2d.setColor(bgColor);
+		g2d.fillRect(0, 0, dim.width, dim.height - 1);
+
+		g2d.setColor(new Color(209, 209, 203));
+		g2d.drawLine(0, dim.height - 2, dim.width, dim.height - 2);
+		g2d.setColor(new Color(218, 218, 211));
+		g2d.drawLine(0, dim.height - 3, dim.width, dim.height - 3);
+		g2d.setColor(new Color(226, 226, 220));
+		g2d.drawLine(0, dim.height - 4, dim.width, dim.height - 4);
+
+		Color tickColor = new Color(128, 128, 128);
+		Color textColor = new Color(0, 0, 0);
+		g2d.setColor(tickColor);
+		g2d.drawLine(0, 0, dim.width, 0);
+		g2d.drawLine(0, dim.height - 1, dim.width, dim.height - 1);
+
+		Font sansSerifFont = new Font("Sans", Font.PLAIN, 10);
+		g2d.setFont(sansSerifFont);
+		int count = 4, metric = 0, xoff;
+		for (int x = xoffset; x < dim.width; x += gap) {
+			g2d.drawLine(x, 2, x, 4);
+			g2d.drawLine(x, dim.height - 3, x, dim.height - 5);
+			if (count == 4) {
+				g2d.setColor(textColor);
+				xoff = x - ("" + metric).length() * 2;
+				g2d.drawString(metric + "", xoff, 16);
+				g2d.setColor(tickColor);
+				count = 0;
+			} else
+				count++;
+			metric++;
+		}
+
+		// draw cursor
+		g2d.setColor(new Color(255, 0, 0, 60));
+		g2d.fillRect(xoffset + getValue() * gap - halfgap, 1, gap,
+				dim.height - 2);
+		g2d.setColor(new Color(255, 0, 0));
+		g2d.drawRect(xoffset + getValue() * gap - halfgap, 1, gap,
+				dim.height - 3);
+						
+	}
+
+	public int getValue() {
+		return cursor;
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeMarker.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeMarker.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeMarker.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/TimeMarker.java	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,147 @@
+package org.tekkotsu.ui.storyboard.components;
+
+import java.util.Vector;
+
+/**
+ * 
+ * @author asangpet
+ */
+public class TimeMarker {
+    int defaultGap, xoffset;
+
+    float defaultScale;
+
+    IntVector timeVec;
+
+    IntVector offsetVec;
+
+    class IntVector {
+        Vector v;
+
+        public IntVector() {
+            v = new Vector();
+        }
+
+        public int get(int index) {
+            return ((Integer) (v.get(index))).intValue();
+        }
+
+        /**
+         * @param value
+         * @return index of value, or (-insert_index) if not found
+         */
+        public int seek(int value) {
+            int l = 0, r = v.size();
+            int mid = (l + r) / 2;
+            while (l < r) {
+                int test = get(mid);
+                if (test < value)
+                    l = mid + 1;
+                else if (test > value)
+                    r = mid;
+                else
+                    return mid;
+                mid = (l + r) / 2;
+            }
+            if (mid < v.size()) {
+                int test = get(mid);
+                if (test < value)
+                    return -(mid + 1);
+                else if (test > value)
+                    return -mid;
+                else
+                    return mid;
+            } else
+                return -mid;
+        }
+
+        public void add(int idx, int value) {
+            v.add(idx, new Integer(value));
+        }
+
+        public boolean add(int value) {
+            return v.add(new Integer(value));
+        }
+
+        public int size() {
+            return v.size();
+        }
+    }
+
+    public TimeMarker(int xoff, int gap, float scale) {
+        xoffset = xoff;
+        defaultGap = gap;
+        defaultScale = scale;
+        clearMarker();
+    }
+    
+    public void clearMarker() {
+        timeVec = new IntVector();
+        offsetVec = new IntVector();
+        timeVec.add(0);
+        offsetVec.add(xoffset);
+    }
+    
+    public synchronized void addMarker(int time, int offset) {
+        if (timeVec.get(timeVec.size()-1) != time) {
+            timeVec.add(time);
+            offsetVec.add(offset);
+        }
+    }
+
+    public synchronized int getOffset(int time) {
+        int idx = timeVec.seek(time);
+        // exact match
+        if (idx >= 0)
+            return offsetVec.get(idx);
+
+        idx = -idx;
+
+        if (idx >= timeVec.size()) {
+            //only left boundary available
+            int ltime = timeVec.get(timeVec.size() - 1);
+            int lbound = offsetVec.get(timeVec.size() - 1);
+            int offset = (int) Math.round((time - ltime) * defaultScale
+                    * defaultGap)
+                    + lbound;            
+            return offset;
+        } else {
+            //right boundary available
+            int rtime = timeVec.get(idx);
+            int rbound = offsetVec.get(idx);
+            int ltime = timeVec.get(idx - 1);
+            int lbound = offsetVec.get(idx - 1);
+            int offset = (int) Math.round(1.0f * (time - ltime)
+                    * (rbound - lbound) / (rtime - ltime)) + lbound;            
+            return offset;
+        }
+    }
+
+    public int getTime(int xoffset) {
+        int idx = offsetVec.seek(xoffset);
+        // exact match
+        if (idx >= 0)
+            return timeVec.get(idx);
+
+        idx = -idx;
+        if (idx >= offsetVec.size()) {
+            //only left boundary available
+            int ltime = timeVec.get(offsetVec.size() - 1);
+            int lbound = offsetVec.get(offsetVec.size() - 1);
+            int time = (int) Math.round((xoffset - lbound) / defaultScale
+                    / defaultGap) + ltime;
+            //System.out.println("l:"+time);
+            return time;
+        } else {
+            //right boundary available
+            int rtime = timeVec.get(idx);
+            int rbound = offsetVec.get(idx);
+            int ltime = timeVec.get(idx - 1);
+            int lbound = offsetVec.get(idx - 1);
+            int time = (int) Math.round(1.0f * (xoffset - lbound)
+                    * (rtime - ltime) / (rbound - lbound))+ltime;
+            //System.out.println("lr:"+time);
+            return time;
+        }
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java	2007-03-01 15:26:26.000000000 -0500
@@ -0,0 +1,158 @@
+/*
+ * Created on Nov 17, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.Figure;
+import org.eclipse.draw2d.Graphics;
+import org.eclipse.draw2d.Label;
+import org.eclipse.draw2d.Polygon;
+import org.eclipse.draw2d.geometry.PointList;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.resource.ColorRegistry;
+import org.eclipse.swt.graphics.RGB;
+import org.eclipse.swt.widgets.Display;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.SourceTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.storyboard.model.TransitionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class Transition extends Figure {
+	static final String COLOR_BASE="_color_base";
+	static final String COLOR_FADE="_color_fade";
+	
+	boolean active = false;
+	ColorRegistry colReg;
+	Rectangle constraint;
+		
+	TransitionModel model;
+	MultiTransitionModel trans;
+	org.tekkotsu.ui.editor.model.TransitionModel etrans;
+	List nodeList;
+	int offset = TimeLine.xoffset;
+	
+	public Transition() {
+		super();
+		colReg = new ColorRegistry();
+		setColor(new RGB(0,0,0));
+	}
+	
+	public Transition(Display d, TransitionModel model, MultiTransitionModel trans, TimeLine timeLine) {
+		colReg = new ColorRegistry(d);
+		this.model = model;
+		this.trans = trans;
+		//org.eclipse.draw2d.geometry.Rectangle bound = trans.getConstraint();		
+		ViewModel view = (ViewModel)trans.getParent();
+		SourceTransitionModel strans = (SourceTransitionModel)trans.getSource();
+		int ymin=Integer.MAX_VALUE;
+		int ymax=Integer.MIN_VALUE;
+				
+		List nodes = new ArrayList();
+		nodes.addAll(strans.getSourceNodes());				
+		nodes.addAll(strans.getDestNodes());
+		nodeList = new ArrayList();		
+		Iterator iter = nodes.iterator();
+		while (iter.hasNext()) {
+			StateNodeModel state = (StateNodeModel)view.getPartChild((String)iter.next());
+			nodeList.add(state);
+			int top = state.getConstraint().y;
+			int bottom = state.getConstraint().y+state.getConstraint().height;
+			if (top<ymin) ymin=top;
+			if (bottom>ymax) ymax=bottom;
+		}
+		
+		//int xoff = ((int)Math.round(model.getStart()*timeLine.getTimeScale())*metric+offset);
+		int xoff = 0;
+		if (model.getEnd()>-1)
+			xoff = timeLine.getOffset(model.getEnd());
+		else
+			xoff = timeLine.getOffset(model.getStart());
+		
+		setConstraint(new Rectangle(xoff-3,ymin,7,ymax-ymin));
+		setColor(trans.getColor().getRGB());
+		this.setToolTip(new Label(trans.getId()));// .getLabel()));
+	}
+	
+	private void setConstraint(Rectangle r) {
+		constraint = r;
+	}
+	
+	public Rectangle getConstraint() {
+		return new Rectangle(constraint);
+	}
+
+	private int colorMod(int oldcol, int delta) {
+		oldcol = (int)Math.round((double)oldcol*0.2) + delta;
+		if (oldcol<0) return 0;
+		if (oldcol>255) return 255;
+		return oldcol;
+	}
+	
+	public void setColor(RGB c) {
+		colReg.put(COLOR_BASE,c);
+		colReg.put(COLOR_FADE, new RGB(colorMod(c.red,200),colorMod(c.green,200),colorMod(c.blue,200)));
+		setActive(active);
+	}
+
+	public void setActive(boolean b) {
+		active = b;				
+		if (active) {
+			setBackgroundColor(colReg.get(COLOR_BASE));
+			setForegroundColor(ColorConstants.black);
+		} else {
+			setForegroundColor(colReg.get(COLOR_FADE));
+			setBackgroundColor(colReg.get(COLOR_FADE));			
+		}
+	}
+	
+	public void paint(Graphics g2d) {
+		Rectangle bound = this.getConstraint();
+		Rectangle clArea = this.getClientArea();
+		
+		g2d.setBackgroundColor(getLocalBackgroundColor());	
+		g2d.setForegroundColor(getLocalForegroundColor());
+		//g2d.drawLine(3+clArea.x,clArea.y,3+clArea.x,bound.height+clArea.y);
+		
+		Polygon p = new Polygon();
+		int[] xp = new int[] {clArea.x,clArea.x+3,clArea.x+6,clArea.x+3};
+		
+		int miny=Integer.MAX_VALUE, maxy=-1;
+		if (nodeList!=null) {
+			Iterator iter = nodeList.iterator();			
+			while (iter.hasNext()) {
+				StateNodeModel state = (StateNodeModel)iter.next();
+				Rectangle rect = state.getConstraint();
+				int yoff = clArea.y+(rect.y-bound.y)+rect.height/2;
+				if (yoff<miny) miny = yoff;
+				if (yoff>maxy) maxy = yoff;
+				int[] yp = new int[] {yoff,yoff-3,yoff,yoff+3};
+				PointList plist = new PointList(4);
+				plist.addPoint(xp[0],yp[0]);
+				plist.addPoint(xp[1],yp[1]);
+				plist.addPoint(xp[2],yp[2]);
+				plist.addPoint(xp[3],yp[3]);				
+				g2d.fillPolygon(plist);
+			}		
+		}
+		if (miny==Integer.MAX_VALUE) miny=clArea.y;
+		if (maxy==-1) maxy=clArea.y+bound.height;
+		g2d.drawLine(3+clArea.x,miny,3+clArea.x,maxy);
+	}
+	/**
+	 * @return Returns the model.
+	 */
+	public TransitionModel getModel() {
+		return model;
+	}
+	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java.j2d ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java.j2d
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java.j2d	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/components/Transition.java.j2d	2005-09-08 22:02:56.000000000 -0400
@@ -0,0 +1,153 @@
+/*
+ * Created on Nov 17, 2004
+ */
+package org.tekkotsu.ui.storyboard.components;
+
+import java.awt.Color;
+import java.awt.Component;
+import java.awt.Graphics;
+import java.awt.Polygon;
+import java.awt.Rectangle;
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.SourceTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.storyboard.model.TransitionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class Transition extends Component {
+	static final long serialVersionUID = 0xACAC0004;
+	
+	
+	boolean active = false;
+	Color baseColor, fgColor, bgColor;
+	
+	TransitionModel model;
+	MultiTransitionModel trans;
+	org.tekkotsu.ui.editor.model.TransitionModel etrans;
+	List nodeList;
+	int offset = 20;
+	int metric = 8;
+	
+	public Transition() {
+		super();
+		setColor(new Color(0,0,0));
+	}
+	
+	public Transition(TransitionModel model, MultiTransitionModel trans) {
+		this.model = model;
+		this.trans = trans;
+		//org.eclipse.draw2d.geometry.Rectangle bound = trans.getConstraint();		
+		ViewModel view = (ViewModel)trans.getParent();
+		SourceTransitionModel strans = (SourceTransitionModel)trans.getSource();
+		int ymin=Integer.MAX_VALUE;
+		int ymax=Integer.MIN_VALUE;
+		List nodes = new ArrayList();
+		nodes.addAll(strans.getSourceNodes());
+		nodes.addAll(strans.getDestNodes());
+		nodeList = new ArrayList();		
+		Iterator iter = nodes.iterator();
+		while (iter.hasNext()) {
+			StateNodeModel state = (StateNodeModel)view.getPartChild((String)iter.next());
+			nodeList.add(state);
+			int top = state.getConstraint().y;
+			int bottom = state.getConstraint().y+state.getConstraint().height;
+			if (top<ymin) ymin=top;
+			if (bottom>ymax) ymax=bottom;
+		}
+		
+		int xoff = model.getStart()*metric+offset;
+		setBounds(xoff-3,ymin,7,ymax-ymin);
+
+		//org.eclipse.swt.graphics.Color c = trans.getColor();
+		//setColor(new Color(c.getRed(), c.getGreen(), c.getBlue()));		
+		setColor(Color.black);
+	}
+
+	public Transition(TransitionModel model, org.tekkotsu.ui.editor.model.TransitionModel trans) {
+		this.model = model;
+		this.etrans = trans;
+		//org.eclipse.draw2d.geometry.Rectangle bound = trans.getConstraint();		
+		ViewModel view = (ViewModel)trans.getParent();		
+		SourceTransitionModel strans = (SourceTransitionModel)trans.getSourceModel();
+		int ymin=Integer.MAX_VALUE;
+		int ymax=Integer.MIN_VALUE;
+		List nodes = new ArrayList();
+		nodes.addAll(strans.getSourceNodes());
+		nodes.addAll(strans.getDestNodes());
+		Iterator iter = nodes.iterator();
+		while (iter.hasNext()) {
+			StateNodeModel state = (StateNodeModel)view.getPartChild((String)iter.next());
+			int top = state.getConstraint().y;
+			int bottom = state.getConstraint().y+state.getConstraint().height;
+			if (top<ymin) ymin=top;
+			if (bottom>ymax) ymax=bottom;
+		}
+		
+		int xoff = model.getStart()*metric+offset;
+		setBounds(xoff-3,ymin,7,ymax-ymin);
+
+		setColor(Color.black);		
+	}	
+	
+	public void setColor(Color c) {
+		baseColor = c;
+		setActive(active);
+	}
+
+	public void setActive(boolean b) {
+		active = b;		
+		Color c = baseColor;
+		if (active) {
+			bgColor = c;
+			fgColor = Color.RED;
+		} else {
+			fgColor = (new Color(c.getRed(),c.getGreen(),c.getBlue(),250));
+			bgColor = (new Color(c.getRed(),c.getGreen(),c.getBlue(),220));			
+		}
+	}
+	
+	public void paint(Graphics g2d) {
+		//Graphics2D g2d = (Graphics2D)gr;
+		Rectangle bound = this.getBounds();		
+		
+		g2d.setColor(bgColor);	
+		g2d.drawLine(3,0,3,bound.height);
+		g2d.setColor(fgColor);
+		Polygon p = new Polygon();
+		int[] xp = new int[] {0,3,6,3};
+		int k=bound.height/2;		
+		int[] yp = new int[] {k,k-3,k,k+3};
+		//g2d.fillPolygon(xp,yp,4);
+		
+		if (nodeList!=null) {
+			Iterator iter = nodeList.iterator();
+			while (iter.hasNext()) {
+				StateNodeModel state = (StateNodeModel)iter.next();
+				org.eclipse.draw2d.geometry.Rectangle rect = state.getConstraint();
+				int yoff = (rect.y-bound.y)+rect.height/2;
+				int[] ypoints = new int[] {yoff,yoff-3,yoff,yoff+3};
+				g2d.fillPolygon(xp,ypoints,4);
+			}
+		}
+		//g2d.fillOval(0,bound.height/2,6,6);
+		//String label = trans.getLabel();
+		//if (label==null) label = trans.getId();
+		//int swidth = g2d.getFontMetrics().stringWidth(label);
+		//g2d.drawString(label,(bound.width-swidth)/2,bound.height/2);
+	}
+	/**
+	 * @return Returns the model.
+	 */
+	public TransitionModel getModel() {
+		return model;
+	}
+	
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.dtd ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.dtd
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.dtd	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.dtd	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,69 @@
+<!DOCTYPE event [
+
+<!ELEMENT event (#PCDATA|#CDATA|param*|(statestart|statestop|fire)*)>
+<!ELEMENT statestart (EMPTY)>
+<!ELEMENT statestop (EMPTY)>
+<!ELEMENT fire (EMPTY)>
+<!ELEMENT param (EMPTY)>
+
+<!ATTLIST event type (transition|log|userlog|image|webcam) #REQUIRED>
+<!ATTLIST event egid CDATA #IMPLIED>
+<!ATTLIST event sid CDATA #REQUIRED>
+<!ATTLIST event etid (A|D|S) #IMPLIED>
+<!ATTLIST event time CDATA #REQUIRED>
+<!ATTLIST event voff CDATA #IMPLIED>
+<!ATTLIST event format CDATA #IMPLIED>
+<!ATTLIST event bytes CDATA #IMPLIED>
+
+<!ATTLIST param name CDATA #REQUIRED>
+<!ATTLIST param value CDATA #REQUIRED>
+
+<!ATTLIST fire id CDATA #REQUIRED>
+<!ATTLIST fire time CDATA #REQUIRED>
+<!ATTLIST statestart id CDATA #REQUIRED>
+<!ATTLIST statestart time CDATA #REQUIRED>
+<!ATTLIST statestop id CDATA #REQUIRED>
+<!ATTLIST statestop time CDATA #REQUIRED> 
+
+]>
+
+note:
+egid = group id
+sid = state(source) id
+etid = type id
+time = timewstamp
+voff = vertical offset (for state log)
+
+<event type="transition">
+	<statestart id="xxx" time="123" />
+	<statestop id="xxx" time="123" />
+	<fire id="xxx" time="123" />
+</event>
+
+//TODO: send message string along with events
+// TYPE option : Activate normal - yellow tooltip
+//				 Deactivate red cross - red tooltip
+//				 Status blue underscore - blue tooltip
+				 
+				  group	 	 source	   type
+<event type="log" egid="xxx" sid="xxx" etid="A|D|S" time="123">
+	<param name="xxx" value="xxx" />
+	<param name="xxx" value="xxx" />
+	<message>stringblahblah</message>
+</event>
+
+event group from system event egid:
+	- button (ico: button)
+	- timer (clock)
+	- motion (...)
+	- locomotion (running shoe)
+	- audio (musical note)
+	- pinkball activate/deactivate (not status)
+	- emergency stop (stop sign)
+	- text message (cap T)
+
+<event type="userlog" sid="stateid" icon="filename.png" time="123" voff="123">user message here</event>
+
+<event type="image" sid="stateid" format="png" bytes="128" time="123">128_bytes_later</event>
+
+<event type="webcam" sid="stateid" time="123" />
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.sample ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.sample
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.sample	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/eventxml.sample	2005-09-08 22:02:57.000000000 -0400
@@ -0,0 +1,18 @@
+spider state machine transition message:
+<event type="transition">
+	<statestart id="xxx" time="123" />
+	<statestop id="xxx" time="123" />
+	<fire id="xxx" time="123" />
+</event>
+
+				  group	 	 source	   type
+<event type="log" egid="xxx" sid="xxx" etid="A|D|S" time="123">
+	<param name="xxx" value="xxx" />
+	<param name="xxx" value="xxx" />
+</event>
+
+<event type="userlog" sid="stateid" icon="filename.png" time="123" voff="15">user message here</event>
+
+<event type="image" sid="stateid" format="png" bytes="128" time="123">128_bytes_later</event>
+
+<event type="webcam" sid="stateid" time="123" />
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/.cvsignore ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/.cvsignore
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/.cvsignore	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/.cvsignore	2005-09-08 22:02:59.000000000 -0400
@@ -0,0 +1 @@
+Thumbs.db
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/IconDummy.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/IconDummy.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/IconDummy.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/IconDummy.java	2005-09-08 22:02:58.000000000 -0400
@@ -0,0 +1,5 @@
+package org.tekkotsu.ui.storyboard.icons;
+
+public class IconDummy {
+
+}
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/audio.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/audio.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/bookmark.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/bookmark.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/button.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/button.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/color_line.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/color_line.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/desktop.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/desktop.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/desktop.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/desktop.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/fileopen.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/fileopen.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/filesave.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/filesave.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/flag.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/flag.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/graphic.jpg and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/graphic.jpg differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/key_enter.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/key_enter.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/locomotion.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/locomotion.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/note.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/note.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/paw.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/paw.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/sample.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/sample.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/save.gif and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/save.gif differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/stop.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/stop.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/text.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/text.png differ
Binary files ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/timer.png and ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/icons/timer.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/AbstractModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/AbstractModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/AbstractModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/AbstractModel.java	2005-09-08 22:03:03.000000000 -0400
@@ -0,0 +1,44 @@
+package org.tekkotsu.ui.storyboard.model;
+
+public class AbstractModel {
+	int start, end;	//raw time (integer in ms)
+	boolean finish = false;
+	String id;
+	
+	public AbstractModel(String id, int start, int end, boolean finish) {
+		this.id = id;
+		this.start = start;
+		this.end = end;
+		this.finish = finish;
+	}
+	
+	public AbstractModel(String id, int start) {
+		this(id,start,-1, false);
+	}
+	
+	public String getID() { return id; }
+	public int getStart() { return start; }
+	public int getEnd() { return end; }
+	public void setEnd(int end) { this.end = end; this.finish = true; }
+	
+	public boolean isFinish() {
+		return finish;
+	}
+	
+	public String toString() {
+		return super.toString() + id + ":" + start+":"+end;
+	}
+	
+	/* (non-Javadoc)
+	 * @see java.lang.Object#equals(java.lang.Object)
+	 */
+	public boolean equals(Object obj) {
+		if (obj==null) return false;
+		if (obj instanceof AbstractModel) {
+			AbstractModel comp = (AbstractModel)obj;
+			return comp.getID().equals(this.getID()) && comp.getStart()==(this.getStart()) && comp.getEnd()==(this.getEnd());
+		}
+		return false;
+	}
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/BlockModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/BlockModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/BlockModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/BlockModel.java	2005-09-08 22:03:03.000000000 -0400
@@ -0,0 +1,29 @@
+/*
+ * Created on Nov 11, 2004
+ */
+package org.tekkotsu.ui.storyboard.model;
+
+/**
+ * @author asangpet
+ */
+public class BlockModel extends AbstractModel{	
+	public BlockModel(String id, int start, int end, boolean finish) {
+		super(id,start,end,finish);
+	}
+	
+	public BlockModel(String id, int start) {
+		this(id,start,-1, false);
+	}
+	
+	/* (non-Javadoc)
+	 * @see java.lang.Object#equals(java.lang.Object)
+	 */
+	public boolean equals(Object obj) {
+		if (obj==null) return false;
+		if (obj instanceof BlockModel) {
+			BlockModel comp = (BlockModel)obj;
+			return comp.getID().equals(this.getID()) && comp.getStart()==(this.getStart()) && comp.getEnd()==(this.getEnd());
+		}
+		return false;
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/ImageModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/ImageModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/ImageModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/ImageModel.java	2005-09-08 22:03:03.000000000 -0400
@@ -0,0 +1,83 @@
+package org.tekkotsu.ui.storyboard.model;
+
+import java.io.ByteArrayInputStream;
+import java.io.FileOutputStream;
+
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.graphics.ImageData;
+import org.eclipse.swt.graphics.ImageLoader;
+import org.tekkotsu.ui.storyboard.Base64;
+
+public class ImageModel extends AbstractModel {
+	String icon="bookmark.gif";
+	String content = "";
+	String etid = "";
+	public static final String ETID_ACTIVATE = "A";
+	public static final String ETID_DEACTIVATE = "D";
+	public static final String ETID_STATUS = "S";	    
+    int layoutIndex = 0;
+    ImageData imData;
+
+	public ImageModel(String sid, int start, String content) {
+		super(sid,start,-1, true);		
+		if (content!=null) this.content = content;
+
+		ImageLoader imLoad = new ImageLoader();
+        ByteArrayInputStream is = new ByteArrayInputStream(Base64.decode(content)); 
+        imLoad.load(is);
+        imData = imLoad.data[0];        
+	}
+	
+	public int getTime() {
+		return start;
+	}
+	
+	public ImageData getImageData() {
+	    return imData;
+	}
+	
+	public String getIconName() {
+		return icon;
+	}
+	
+	public String getContent() {
+		return content;
+	}
+	
+	public String getETID() {
+	    return etid;
+	}
+	
+	public String getETIDString() {
+	    if (ETID_ACTIVATE.equals(etid)) return "Activate";
+	    if (ETID_DEACTIVATE.equals(etid)) return "Deactivate";
+	    if (ETID_STATUS.equals(etid)) return "Status";
+	    return "Unknown";
+	}
+	
+    public int getLayoutIndex() {
+        return layoutIndex;
+    }
+    
+    public void setLayoutIndex(int layoutIndex) {
+        this.layoutIndex = layoutIndex;
+    }
+    
+    public String getImageName() {
+        return "img_"+getID()+getTime();
+    }
+    
+    public boolean saveTo(IPath path) {        
+        ImageLoader imLoad = new ImageLoader();
+        imLoad.data = new ImageData[] {imData};
+        try {
+            FileOutputStream os = new FileOutputStream(path.toFile());
+            imLoad.save(os,SWT.IMAGE_JPEG);
+            os.close();
+        } catch (Exception e) {
+            return false;
+        }
+        return true;
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/LogModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/LogModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/LogModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/LogModel.java	2005-09-08 22:03:03.000000000 -0400
@@ -0,0 +1,47 @@
+package org.tekkotsu.ui.storyboard.model;
+
+public class LogModel extends AbstractModel {
+	String icon="bookmark.gif";
+	String content = "";
+	String etid = "";
+	public static final String ETID_ACTIVATE = "A";
+	public static final String ETID_DEACTIVATE = "D";
+	public static final String ETID_STATUS = "S";	    
+    int layoutIndex = 0;
+
+	public LogModel(String sid, int start, String iconName, String etid, String content) {
+		super(sid,start,-1, true);
+		if (iconName!=null) icon = iconName;
+		if (content!=null) this.content = content;
+		if (etid!=null) this.etid = etid; else this.etid = ETID_ACTIVATE;
+	}
+	
+	public int getTime() {
+		return start;
+	}
+	
+	public String getIconName() {
+		return icon;
+	}
+	
+	public String getContent() {
+		return content;
+	}
+	
+	public String getETID() {
+	    return etid;
+	}
+	
+	public String getETIDString() {
+	    if (ETID_ACTIVATE.equals(etid)) return "Activate";
+	    if (ETID_DEACTIVATE.equals(etid)) return "Deactivate";
+	    if (ETID_STATUS.equals(etid)) return "Status";
+	    return "Unknown";
+	}
+    public int getLayoutIndex() {
+        return layoutIndex;
+    }
+    public void setLayoutIndex(int layoutIndex) {
+        this.layoutIndex = layoutIndex;
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/TransitionModel.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/TransitionModel.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/TransitionModel.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/model/TransitionModel.java	2005-09-29 05:56:53.000000000 -0400
@@ -0,0 +1,50 @@
+/*
+ * Created on Nov 17, 2004
+ */
+package org.tekkotsu.ui.storyboard.model;
+
+import java.util.LinkedList;
+import java.util.List;
+
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.SourceTransitionModel;
+
+/**
+ * @author asangpet
+ *
+ */
+public class TransitionModel extends AbstractModel {
+	List sourceNodeList, destNodeList;
+	int endCount = 0;
+	
+	public TransitionModel(String id, int start, MultiTransitionModel trans) {
+		super(id,start,-1, true);
+		sourceNodeList = new LinkedList();
+		destNodeList = new LinkedList();
+		
+		SourceTransitionModel strans = (SourceTransitionModel)trans.getSource();
+		sourceNodeList.addAll(strans.getSourceNodes());				
+		destNodeList.addAll(strans.getDestNodes());
+	}
+
+	public boolean isSourceNode(String id) {
+		return sourceNodeList.contains(id);
+	}
+	
+	public boolean isDestNode(String id) {
+		return destNodeList.contains(id);
+	}
+	
+	public int getTime() {
+		return start;
+	}
+	
+	public void setEnd(int end) {
+		if (this.end>=0) {
+			endCount++;
+			super.setEnd((end*(endCount-1)+end)/endCount);
+		} else {
+			super.setEnd(end);		
+		}
+	}
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageView.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageView.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageView.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageView.java	2005-09-09 16:59:28.000000000 -0400
@@ -0,0 +1,228 @@
+package org.tekkotsu.ui.storyboard.views;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.text.MessageFormat;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.graphics.Device;
+import org.eclipse.swt.graphics.Image;
+import org.eclipse.swt.graphics.ImageData;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.FileDialog;
+import org.eclipse.swt.widgets.Shell;
+import org.eclipse.core.runtime.IPath;
+import org.eclipse.core.runtime.Path;
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.IMenuListener;
+import org.eclipse.jface.action.IMenuManager;
+import org.eclipse.jface.action.IToolBarManager;
+import org.eclipse.jface.action.MenuManager;
+import org.eclipse.jface.action.Separator;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.jface.resource.ImageDescriptor;
+import org.eclipse.jface.viewers.DoubleClickEvent;
+import org.eclipse.jface.viewers.IDoubleClickListener;
+import org.eclipse.jface.viewers.IStructuredContentProvider;
+import org.eclipse.jface.viewers.Viewer;
+import org.eclipse.swt.widgets.Menu;
+import org.eclipse.ui.IActionBars;
+import org.eclipse.ui.IWorkbenchActionConstants;
+import org.eclipse.ui.part.ViewPart;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+import org.tekkotsu.ui.storyboard.components.ImageDialog;
+import org.tekkotsu.ui.storyboard.model.ImageModel;
+
+public class ImageView extends ViewPart implements PropertyChangeListener {
+    ImageViewer viewer;
+
+    Action doubleClickAction, saveAction;
+
+    class ViewContentProvider implements IStructuredContentProvider {
+        ImageModel model = null;
+
+        public Object[] getElements(Object inputElement) {
+            return null;
+        }
+
+        public void inputChanged(Viewer v, Object oldInput, Object newInput) {
+        }
+
+        public void dispose() {
+        }
+
+        public void setContent(ImageModel img) {
+            model = img;
+        }
+
+        public ImageModel getDefaultModel() {
+            return model;
+        }
+    }
+
+    private ViewContentProvider content;
+
+    /**
+     * The constructor.
+     */
+    public ImageView() {
+    }
+
+    /**
+     * This is a callback that will allow us to create the viewer and initialize
+     * it.
+     */
+    public void createPartControl(Composite parent) {
+        //drillDownAdapter = new DrillDownAdapter(viewer);
+        viewer = new ImageViewer(parent);
+        content = new ViewContentProvider();
+        makeActions();
+        hookContextMenu();
+        hookDoubleClickAction();
+        contributeToActionBars();
+    }
+
+    private void hookContextMenu() {
+        MenuManager menuMgr = new MenuManager("#ImagePopupMenu");
+        menuMgr.setRemoveAllWhenShown(true);
+        menuMgr.addMenuListener(new IMenuListener() {
+            public void menuAboutToShow(IMenuManager manager) {
+                ImageView.this.fillContextMenu(manager);
+            }
+        });
+        Menu menu = menuMgr.createContextMenu(viewer.getControl());
+        viewer.getControl().setMenu(menu);
+        getSite().registerContextMenu(menuMgr, viewer);
+    }
+
+    private void contributeToActionBars() {
+        IActionBars bars = getViewSite().getActionBars();
+        fillLocalPullDown(bars.getMenuManager());
+        fillLocalToolBar(bars.getToolBarManager());
+    }
+
+    private void fillLocalPullDown(IMenuManager manager) {
+    }
+
+    private void fillContextMenu(IMenuManager manager) {
+        manager.add(saveAction);
+        manager.add(new Separator(IWorkbenchActionConstants.MB_ADDITIONS));
+    }
+
+    private void fillLocalToolBar(IToolBarManager manager) {
+        manager.add(saveAction);
+    }
+
+    private void makeActions() {
+        saveAction = new Action() {
+            private IPath queryFile() {
+                FileDialog dialog = new FileDialog(viewer.getControl()
+                        .getShell(), SWT.SAVE);
+                dialog.setFilterExtensions(new String[] { "*.jpg" });
+                dialog.setText("Save Image as"); //$NON-NLS-1$
+                String path = dialog.open();
+                if (path != null && path.length() > 0) {
+                    if (!path.endsWith(".jpg"))
+                        path = path + ".jpg";
+                    return new Path(path);
+                }
+                return null;
+            }
+
+            public void run() {
+                if (viewer.getImageModel() == null) {
+                    MessageDialog.openWarning(viewer.getControl().getShell(),
+                            "Error", "No image has been selected");
+                    return;
+                }
+                IPath path = queryFile();
+                boolean success = false;
+                if (path != null) {
+                    success = viewer.getImageModel().saveTo(path);
+                    if (!success) {
+                        String msg = MessageFormat
+                                .format("Cannot write file: {0}",
+                                        new String[] { path.toOSString() });
+                        MessageDialog.openWarning(viewer.getControl()
+                                .getShell(), "Problem", msg);
+                    }
+                }
+            }
+        };
+        saveAction.setText("Save Image As");
+        saveAction.setToolTipText("Save Image As");
+        saveAction.setImageDescriptor(ImageDescriptor.createFromFile(
+                org.tekkotsu.ui.storyboard.icons.IconDummy.class, "save.gif"));
+
+        doubleClickAction = new Action() {
+            public void run() {
+                ImageData data = viewer.getImageModel().getImageData();
+                Shell shell = ResourceRegistry.getInstance().getDisplay()
+                        .getActiveShell();
+                Device device = ResourceRegistry.getInstance().getDisplay();
+                ImageDialog imgDialog = new ImageDialog(shell, new Image(
+                        device, data));
+                imgDialog.setTitle("Image: "
+                        + viewer.getImageModel().getImageName());
+                imgDialog.open();
+            }
+        };
+    }
+
+    private void hookDoubleClickAction() {
+        viewer.addDoubleClickListener(new IDoubleClickListener() {
+            public void doubleClick(DoubleClickEvent e) {
+                doubleClickAction.run();
+            }
+        });
+
+    }
+
+    private void showMessage(String message) {
+        MessageDialog.openInformation(viewer.getControl().getShell(),
+                "Image Preview", message);
+    }
+
+    /**
+     * Passing the focus request to the viewer's control.
+     */
+    public void setFocus() {
+        viewer.getControl().setFocus();
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see java.beans.PropertyChangeListener#propertyChange(java.beans.PropertyChangeEvent)
+     */
+    public void propertyChange(PropertyChangeEvent evt) {
+        if (evt.getPropertyName().equals("_BLOCK_INFO")) {
+            List list = (List) evt.getNewValue();
+            if (list != null) {
+                ImageModel img = null;
+                for (Iterator iter = list.iterator(); iter.hasNext();) {
+                    Object next = iter.next();
+                    if (next instanceof ImageModel) {
+                        img = (ImageModel) next;
+                        break;
+                    }
+                }
+                if (img != null) {
+                    content.setContent(img);
+
+                    Debugger.printDebug(Debugger.DEBUG_ALL, "PROC "
+                            + evt.getNewValue());
+                    viewer.getControl().getDisplay().syncExec(new Runnable() {
+                        public void run() {
+                            viewer.setContent(content);
+                        }
+                    });
+                }
+            }
+        }
+
+    }
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageViewer.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageViewer.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageViewer.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/ImageViewer.java	2005-09-08 22:03:01.000000000 -0400
@@ -0,0 +1,215 @@
+/*
+ * Created on Nov 7, 2004
+ */
+package org.tekkotsu.ui.storyboard.views;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeSupport;
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.jface.viewers.DoubleClickEvent;
+import org.eclipse.jface.viewers.IDoubleClickListener;
+import org.eclipse.jface.viewers.ISelection;
+import org.eclipse.jface.viewers.StructuredSelection;
+import org.eclipse.jface.viewers.Viewer;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.custom.ScrolledComposite;
+import org.eclipse.swt.events.MouseAdapter;
+import org.eclipse.swt.events.MouseEvent;
+import org.eclipse.swt.events.PaintEvent;
+import org.eclipse.swt.events.PaintListener;
+import org.eclipse.swt.graphics.Image;
+import org.eclipse.swt.graphics.ImageData;
+import org.eclipse.swt.graphics.Point;
+import org.eclipse.swt.layout.GridData;
+import org.eclipse.swt.layout.GridLayout;
+import org.eclipse.swt.widgets.Canvas;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.Control;
+import org.eclipse.swt.widgets.Display;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+import org.tekkotsu.ui.storyboard.model.ImageModel;
+
+/**
+ * @author asangpet
+ *  
+ */
+public class ImageViewer extends Viewer implements PropertyChangeListener {
+    Composite parent;
+
+    private PropertyChangeSupport listeners = new PropertyChangeSupport(this);
+
+    private ArrayList listenobjs = new ArrayList();
+
+    ScrolledComposite control = null;
+
+    ViewModel viewModel;
+
+    ImageView.ViewContentProvider content;
+
+    ISelection curSelect = null;
+    Canvas canvas = null;
+    Display display;
+    ImageData imageData = null;
+    Image image = null;
+    ImageModel imageModel = null;
+
+    List doubleClickListeners = null;
+    
+    public ImageViewer(Composite parent) {
+        this.parent = parent;
+        doubleClickListeners = new ArrayList();
+        try {
+        control = new ScrolledComposite(parent,SWT.H_SCROLL | SWT.V_SCROLL);
+        canvas = new Canvas(control,SWT.FILL);
+        if (imageData!=null) {            
+        	canvas.setSize(imageData.width,imageData.height);
+        } else canvas.setSize(200,200);
+        canvas.addPaintListener(new PaintListener() {
+            public void paintControl(PaintEvent e) {
+                if (imageData!=null) {
+                    canvas.setSize(imageData.width,imageData.height);
+                    e.gc.drawImage(image,0,0);
+                }
+                else e.gc.fillRectangle(0,0,control.getSize().x,control.getSize().y);
+            }
+        });        
+        canvas.addMouseListener(new MouseAdapter() {             
+            /* (non-Javadoc)
+             * @see org.eclipse.swt.events.MouseAdapter#mouseDoubleClick(org.eclipse.swt.events.MouseEvent)
+             */
+            public void mouseDoubleClick(MouseEvent e) {
+                for (Iterator iter=doubleClickListeners.iterator();iter.hasNext();) {
+                    try {
+                    IDoubleClickListener listener = (IDoubleClickListener)iter.next();
+                    listener.doubleClick(new DoubleClickEvent(ImageViewer.this,new StructuredSelection()));
+                    } catch (Exception ex) {ex.printStackTrace();}
+                }
+            }
+        });        
+        
+        control.setContent(canvas);
+        GridLayout layout = new GridLayout();
+        layout.numColumns = 1;
+        parent.setLayout(layout);
+        GridData gd = new GridData();
+        gd.horizontalAlignment = SWT.FILL;
+        gd.verticalAlignment = SWT.FILL;
+        gd.grabExcessVerticalSpace = true;
+        gd.grabExcessHorizontalSpace = true;
+        control.setLayoutData(gd);
+
+        } catch (Exception e) {
+            e.printStackTrace();
+        }
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see java.beans.PropertyChangeListener#propertyChange(java.beans.PropertyChangeEvent)
+     */
+    public void propertyChange(PropertyChangeEvent evt) {
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#getControl()
+     */
+    public Control getControl() {
+        return control;
+    }
+
+    public void setContent(ImageView.ViewContentProvider content) {
+        this.content = content;
+        if (content.getDefaultModel() != imageModel) {
+            imageModel = content.getDefaultModel();
+            imageData = content.getDefaultModel().getImageData();               
+            if (image!=null) image.dispose();
+            Point size = new Point(control.getSize().x,control.getSize().y);
+            if (size.x>size.y) size.x = imageData.width*size.y/imageData.height;
+            else size.y = imageData.height*size.x/imageData.width;
+            imageData = imageData.scaledTo(size.x,size.y);
+            image = new Image(ResourceRegistry.getInstance().getDisplay(),imageData);
+            canvas.redraw();
+        }
+    }
+    
+    public void addDoubleClickListener(IDoubleClickListener listener) {
+        doubleClickListeners.add(listener);
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.IInputProvider#getInput()
+     */
+    public Object getInput() {
+        return null;
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#setSelection(org.eclipse.jface.viewers.ISelection,
+     *      boolean)
+     */
+    public void setSelection(ISelection selection, boolean reveal) {
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.ISelectionProvider#getSelection()
+     */
+    public ISelection getSelection() {
+        return null;
+    }
+    
+    
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#refresh()
+     */
+    public void refresh() {
+        //storyboard.repaint();
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#setInput(java.lang.Object)
+     */
+    public void setInput(Object input) {
+        setInput(input, true);
+    }
+
+    public void setInput(Object input, boolean rebuild) {
+    }
+
+    public void addPropertyChangeListener(PropertyChangeListener listener) {
+        listeners.addPropertyChangeListener(listener);
+        listenobjs.add(listener);
+    }
+
+    public void firePropertyChange(String propName, Object oldValue,
+            Object newValue) {
+        listeners.firePropertyChange(propName, oldValue, newValue);
+    }
+
+    public void removePropertyChangeListener(PropertyChangeListener listener) {
+        listeners.removePropertyChangeListener(listener);
+        listenobjs.remove(listener);
+    }
+
+    public ImageModel getImageModel() {
+        return imageModel;
+    }
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/RuntimeView.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/RuntimeView.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/RuntimeView.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/RuntimeView.java	2005-09-29 05:56:53.000000000 -0400
@@ -0,0 +1,391 @@
+package org.tekkotsu.ui.storyboard.views;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.ui.part.*;
+import org.eclipse.jface.viewers.*;
+import org.eclipse.swt.graphics.Image;
+import org.eclipse.jface.action.*;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.ui.*;
+import org.eclipse.swt.widgets.Menu;
+import org.eclipse.swt.SWT;
+import org.eclipse.core.runtime.IAdaptable;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.storyboard.model.BlockModel;
+import org.tekkotsu.ui.storyboard.model.ImageModel;
+import org.tekkotsu.ui.storyboard.model.LogModel;
+import org.tekkotsu.ui.storyboard.model.TransitionModel;
+
+public class RuntimeView extends ViewPart implements PropertyChangeListener {	
+	private TreeViewer viewer;
+	//private DrillDownAdapter drillDownAdapter;
+	//private Action action1;
+	//private Action action2;
+	//private Action doubleClickAction;
+
+	/*
+	 * The content provider class is responsible for
+	 * providing objects to the view. It can wrap
+	 * existing objects in adapters or simply return
+	 * objects as-is. These objects may be sensitive
+	 * to the current input of the view, or ignore
+	 * it and always show the same content 
+	 * (like Task List, for example).
+	 */
+	 
+	class TreeObject implements IAdaptable {
+		private String name;
+		private TreeParent parent;
+		
+		public TreeObject(String name) {
+			this.name = name;
+		}
+		public String getName() {
+			return name;
+		}
+		public void setParent(TreeParent parent) {
+			this.parent = parent;
+		}
+		public TreeParent getParent() {
+			return parent;
+		}
+		public String toString() {
+			return getName();
+		}
+		public Object getAdapter(Class key) {
+			return null;
+		}
+	}
+	
+	class TreeParent extends TreeObject {
+		private ArrayList children;
+		private int start,stop;
+		public int getStop() {
+			return stop;
+		}
+		public int getStart() {
+			return start;
+		}
+		public TreeParent(String name, int start,int stop) {
+			super(name);
+			this.start = start; this.stop = stop;
+			children = new ArrayList();
+		}
+		public TreeParent(String name) {
+			this(name,0,0);
+		}
+
+		public void addChild(TreeObject child) {
+			children.add(child);
+			child.setParent(this);
+		}
+		public void removeChild(TreeObject child) {
+			children.remove(child);
+			child.setParent(null);
+		}
+		public TreeObject [] getChildren() {
+			return (TreeObject [])children.toArray(new TreeObject[children.size()]);
+		}
+		public boolean hasChildren() {
+			return children.size()>0;
+		}
+	}
+
+	class ViewContentProvider implements IStructuredContentProvider, 
+										   ITreeContentProvider {
+		private TreeParent invisibleRoot;
+
+		public void inputChanged(Viewer v, Object oldInput, Object newInput) {
+		}
+		public void dispose() {
+		}
+		public Object[] getElements(Object parent) {
+			if (parent.equals(getViewSite())) {
+				if (invisibleRoot==null) initialize();
+				return getChildren(invisibleRoot);
+			}
+			return getChildren(parent);
+		}
+		public Object getParent(Object child) {
+			if (child instanceof TreeObject) {
+				return ((TreeObject)child).getParent();
+			}
+			return null;
+		}
+		public Object [] getChildren(Object parent) {
+			if (parent instanceof TreeParent) {
+				return ((TreeParent)parent).getChildren();
+			}
+			return new Object[0];
+		}
+		public boolean hasChildren(Object parent) {
+			if (parent instanceof TreeParent)
+				return ((TreeParent)parent).hasChildren();
+			return false;
+		}
+
+		private void initialize() {
+			invisibleRoot = new TreeParent("");
+		}
+		
+		/**
+		 * Fetch information on selected model
+		 */
+		public void setContent(List nodes) {
+			Iterator iter = nodes.iterator();		    
+			Integer curTime = (Integer)iter.next();
+			
+			TreeParent root = new TreeParent("Current selection :"+(curTime.intValue()/1000.0)+"s");
+			while (iter.hasNext()) {
+				Object next = iter.next();
+
+				if (next instanceof ImageModel) {
+				    ImageModel img = (ImageModel)next;
+				    TreeParent par = new TreeParent("Image:"+img.getID(),img.getTime(),img.getTime());
+					par.addChild(new TreeObject("type: image"));
+					par.addChild(new TreeObject("record at: "+img.getTime()*0.001+"s"));
+					root.addChild(par);
+				} else
+				if (next instanceof LogModel) {
+					LogModel log = (LogModel)next;
+					TreeParent par = new TreeParent(log.getID(),log.getTime(),log.getTime());
+					par.addChild(new TreeObject("type: log"));
+					par.addChild(new TreeObject("report at: "+log.getTime()*0.001+"s"));
+					par.addChild(new TreeObject("message: "+log.getContent()));
+					root.addChild(par);
+				} else if (next instanceof TransitionModel) {
+					TransitionModel trans = (TransitionModel)next;
+					TreeParent par = new TreeParent(trans.getID(),trans.getTime(),trans.getTime());
+					par.addChild(new TreeObject("type: transition"));
+					par.addChild(new TreeObject("fire at: "+trans.getTime()*0.001+"s"));
+					root.addChild(par);
+				} else if (next instanceof BlockModel) {
+					BlockModel node = (BlockModel)next;
+					TreeParent par = null;
+					if (node.getEnd()<0)
+						par = new TreeParent(node.getID(),node.getStart(),Integer.MAX_VALUE);
+					else 
+						par = new TreeParent(node.getID(),node.getStart(),node.getEnd());
+					par.addChild(new TreeObject("type: state"));
+					par.addChild(new TreeObject("activate at: "+node.getStart()*.001+"s"));
+					if (node.getEnd()<0) par.addChild(new TreeObject("deactivate at: still active")); else 
+						par.addChild(new TreeObject("deactivate at: "+node.getEnd()*.001+"s"));
+					root.addChild(par);
+				} else {
+				    root.addChild(new TreeObject("Unknown Entity"));
+				}
+				Thread.yield();
+			}			
+			invisibleRoot = new TreeParent("");
+			invisibleRoot.addChild(root);
+		}
+	}
+	
+	private ViewContentProvider content;
+
+	class ViewLabelProvider extends LabelProvider {
+
+		public String getText(Object obj) {
+			return obj.toString();
+		}
+		public Image getImage(Object obj) {
+			return null;
+			/*String imageKey = ISharedImages.IMG_OBJ_ELEMENT;
+			if (obj instanceof TreeParent)
+			   imageKey = ISharedImages.IMG_OBJ_FOLDER;
+			return PlatformUI.getWorkbench().getSharedImages().getImage(imageKey);
+			*/
+		}
+	}
+	class NameSorter extends ViewerSorter {
+	    public int compare(Viewer viewer, Object e1, Object e2) {
+	        int cat1 = category(e1);
+	        int cat2 = category(e2);
+
+	        if (cat1 != cat2)
+	            return cat1 - cat2;
+	        // cat1 == cat2
+	        if (e1 instanceof TreeParent) {
+	        	TreeParent t1 = (TreeParent)e1;
+	        	TreeParent t2 = (TreeParent)e2;
+	        	int result = t1.getStop()-t2.getStop();
+	        	if (result!=0) return result;
+	        	result = t1.getStart()-t2.getStart();
+	        	if (result!=0) return result;
+	        }
+	        return super.compare(viewer,e1,e2);
+	    }
+	        /*
+	        String name1;
+	        String name2;
+
+	        if (viewer == null || !(viewer instanceof ContentViewer)) {
+	            name1 = e1.toString();
+	            name2 = e2.toString();
+	        } else {
+	            IBaseLabelProvider prov = ((ContentViewer) viewer)
+	                    .getLabelProvider();
+	            if (prov instanceof ILabelProvider) {
+	                ILabelProvider lprov = (ILabelProvider) prov;
+	                name1 = lprov.getText(e1);
+	                name2 = lprov.getText(e2);
+	            } else {
+	                name1 = e1.toString();
+	                name2 = e2.toString();
+	            }
+	        }
+	        if (name1 == null)
+	            name1 = "";//$NON-NLS-1$
+	        if (name2 == null)
+	            name2 = "";//$NON-NLS-1$
+	        return collator.compare(name1, name2);
+	    }	*/
+	}
+
+	/**
+	 * The constructor.
+	 */
+	public RuntimeView() {
+	}
+
+	/**
+	 * This is a callback that will allow us
+	 * to create the viewer and initialize it.
+	 */
+	public void createPartControl(Composite parent) {
+		viewer = new TreeViewer(parent, SWT.MULTI | SWT.H_SCROLL | SWT.V_SCROLL);
+		//drillDownAdapter = new DrillDownAdapter(viewer);
+		content = new ViewContentProvider();
+		viewer.setContentProvider(content);
+		viewer.setLabelProvider(new ViewLabelProvider());
+		viewer.setSorter(new NameSorter());
+		viewer.setInput(getViewSite());
+		//makeActions();
+		//hookContextMenu();
+		//hookDoubleClickAction();
+		//contributeToActionBars();
+	}
+
+	private void hookContextMenu() {
+		MenuManager menuMgr = new MenuManager("#PopupMenu");
+		menuMgr.setRemoveAllWhenShown(true);
+		menuMgr.addMenuListener(new IMenuListener() {
+			public void menuAboutToShow(IMenuManager manager) {
+				RuntimeView.this.fillContextMenu(manager);
+			}
+		});
+		Menu menu = menuMgr.createContextMenu(viewer.getControl());
+		viewer.getControl().setMenu(menu);
+		getSite().registerContextMenu(menuMgr, viewer);
+	}
+
+	private void contributeToActionBars() {
+		IActionBars bars = getViewSite().getActionBars();
+		fillLocalPullDown(bars.getMenuManager());
+		fillLocalToolBar(bars.getToolBarManager());
+	}
+
+	private void fillLocalPullDown(IMenuManager manager) {
+		/*
+		manager.add(action1);
+		manager.add(new Separator());
+		manager.add(action2);
+		*/
+	}
+
+	private void fillContextMenu(IMenuManager manager) {
+		/*
+		manager.add(action1);
+		manager.add(action2);
+		manager.add(new Separator());
+		drillDownAdapter.addNavigationActions(manager);
+		*/
+		// Other plug-ins can contribute there actions here
+		manager.add(new Separator(IWorkbenchActionConstants.MB_ADDITIONS));
+	}
+	
+	private void fillLocalToolBar(IToolBarManager manager) {
+		/*
+		manager.add(action1);
+		manager.add(action2);
+		manager.add(new Separator());
+		drillDownAdapter.addNavigationActions(manager);
+		*/
+	}
+
+	private void makeActions() {
+		/*
+		action1 = new Action() {
+			public void run() {
+				showMessage("Action 1 executed");
+			}
+		};
+		action1.setText("Action 1");
+		action1.setToolTipText("Action 1 tooltip");
+		action1.setImageDescriptor(PlatformUI.getWorkbench().getSharedImages().
+			getImageDescriptor(ISharedImages.IMG_OBJS_INFO_TSK));
+		
+		action2 = new Action() {
+			public void run() {
+				showMessage("Action 2 executed");
+			}
+		};
+		action2.setText("Action 2");
+		action2.setToolTipText("Action 2 tooltip");
+		action2.setImageDescriptor(PlatformUI.getWorkbench().getSharedImages().
+				getImageDescriptor(ISharedImages.IMG_OBJS_INFO_TSK));
+		doubleClickAction = new Action() {
+			public void run() {
+				ISelection selection = viewer.getSelection();
+				Object obj = ((IStructuredSelection)selection).getFirstElement();
+				showMessage("Double-click detected on "+obj.toString());
+			}
+		};
+		*/
+	}
+
+	private void hookDoubleClickAction() {
+		/*
+		viewer.addDoubleClickListener(new IDoubleClickListener() {
+			public void doubleClick(DoubleClickEvent event) {
+				doubleClickAction.run();
+			}
+		});
+		*/
+	}
+	private void showMessage(String message) {
+		MessageDialog.openInformation(
+			viewer.getControl().getShell(),
+			"Runtime View",
+			message);
+	}
+
+	/**
+	 * Passing the focus request to the viewer's control.
+	 */
+	public void setFocus() {
+		viewer.getControl().setFocus();
+	}
+	
+	/* (non-Javadoc)
+	 * @see java.beans.PropertyChangeListener#propertyChange(java.beans.PropertyChangeEvent)
+	 */
+	public void propertyChange(PropertyChangeEvent evt) {
+		if (evt.getPropertyName().equals("_BLOCK_INFO")) {
+			content.setContent((List)evt.getNewValue());
+			Debugger.printDebug(Debugger.DEBUG_ALL,"PROC "+evt.getNewValue());
+			viewer.getControl().getDisplay().syncExec(new Runnable() {			
+				public void run() {
+					viewer.setContentProvider(content);						
+					viewer.expandToLevel(3);
+				}
+			});
+		}
+	}
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardView.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardView.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardView.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardView.java	2005-10-11 14:59:06.000000000 -0400
@@ -0,0 +1,695 @@
+package org.tekkotsu.ui.storyboard.views;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeSupport;
+import java.io.BufferedOutputStream;
+import java.io.File;
+import java.io.FileOutputStream;
+import java.io.IOException;
+import java.io.StringReader;
+import java.util.ArrayList;
+import java.util.Collection;
+import java.util.Comparator;
+import java.util.HashMap;
+import java.util.Iterator;
+import java.util.List;
+import java.util.Map;
+import java.util.SortedSet;
+import java.util.TreeSet;
+
+import org.eclipse.draw2d.IFigure;
+import org.eclipse.jface.action.Action;
+import org.eclipse.jface.action.IMenuListener;
+import org.eclipse.jface.action.IMenuManager;
+import org.eclipse.jface.action.IToolBarManager;
+import org.eclipse.jface.action.MenuManager;
+import org.eclipse.jface.action.Separator;
+import org.eclipse.jface.dialogs.MessageDialog;
+import org.eclipse.jface.resource.ImageDescriptor;
+import org.eclipse.jface.viewers.ITableLabelProvider;
+import org.eclipse.jface.viewers.LabelProvider;
+import org.eclipse.jface.viewers.Viewer;
+import org.eclipse.jface.viewers.ViewerSorter;
+import org.eclipse.swt.SWT;
+import org.eclipse.swt.graphics.Image;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.FileDialog;
+import org.eclipse.swt.widgets.Menu;
+import org.eclipse.ui.IActionBars;
+import org.eclipse.ui.IPartListener;
+import org.eclipse.ui.ISharedImages;
+import org.eclipse.ui.IWorkbenchActionConstants;
+import org.eclipse.ui.IWorkbenchPart;
+import org.eclipse.ui.PlatformUI;
+import org.eclipse.ui.part.ViewPart;
+import org.jdom.Document;
+import org.jdom.Element;
+import org.jdom.input.SAXBuilder;
+import org.jdom.output.Format;
+import org.jdom.output.XMLOutputter;
+import org.tekkotsu.ui.editor.ModelConnector;
+import org.tekkotsu.ui.editor.StateMachineEditor;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.storyboard.components.Block;
+import org.tekkotsu.ui.storyboard.components.Transition;
+import org.tekkotsu.ui.storyboard.model.AbstractModel;
+import org.tekkotsu.ui.storyboard.model.BlockModel;
+import org.tekkotsu.ui.storyboard.model.ImageModel;
+import org.tekkotsu.ui.storyboard.model.LogModel;
+import org.tekkotsu.ui.storyboard.model.TransitionModel;
+
+public class StoryboardView extends ViewPart implements IPartListener,
+		PropertyChangeListener {
+
+	public static final double timeUnit = 1000.0;
+
+	private StoryboardViewer viewer;
+
+	private Action doubleClickAction;
+
+	private StateMachineEditor editor;
+
+	private RuntimeView runtime;
+
+	private ContentProvider content;
+
+	Action redrawAction, loadTraceAction, saveTraceAction;
+
+	public class ContentProvider {
+		private List blockList = new ArrayList();
+
+		private List blockUpdate = new ArrayList();
+
+		SAXBuilder builder;
+
+		Element root;
+
+		Map iconMap = new HashMap();
+
+		int latestTime = 0;
+
+		int offsetTime = -1;
+
+		public ContentProvider() {
+			builder = new SAXBuilder();
+			blockList = new ArrayList();
+			root = new Element("trace");
+			initIconMap();
+		}
+
+		private void initIconMap() {
+			iconMap = new HashMap();
+			iconMap.put("button", "key_enter.png");
+			iconMap.put("timer", "timer.png");
+			iconMap.put("locomotion", "locomotion.png");
+			iconMap.put("audio", "audio.png");
+			iconMap.put("estop", "stop.png");
+			iconMap.put("textmsg", "text.png");
+		}
+
+		public void readInput(File file) throws IOException {
+			try {
+				Document document = builder.build(file);
+				blockList = new ArrayList();
+				offsetTime = -1;
+				latestTime = 0;
+				parseInput(document.getRootElement());
+			} catch (Exception e) {
+				throw new IOException("Cannot read input file "+file);
+			}
+		}
+
+		public void saveTrace(File file) throws IOException {
+			// TODO mark the end of timeline and put statestop whenever user
+			// pause/save
+			Document document = new Document(root);			
+			//document.setRootElement(root);
+			try {
+				XMLOutputter outputter = new XMLOutputter(Format
+						.getPrettyFormat());
+				Debugger.printDebug(Debugger.DEBUG_ALL, "Attempting to create "
+						+ file.getCanonicalPath());
+				BufferedOutputStream ostream = new BufferedOutputStream(
+						new FileOutputStream(file));
+				outputter.output(document, ostream);
+				ostream.close();
+			} catch (Exception e) {
+				throw  new IOException("Unable to save trace file");				
+			}
+		}
+
+		public void readInput(String filename) throws IOException {
+			readInput(new File(filename));
+		}
+
+		public void getUpdate(String update) {
+			try {
+				Debugger.printDebug(Debugger.DEBUG_ALL, "Update:" + update);
+				StringReader reader = new StringReader(update);
+				Document document = builder.build(reader);
+				parseInput(document.getRootElement());
+			} catch (Exception e) {
+				e.printStackTrace();
+			}
+		}
+
+		public void clear() {
+			root = new Element("trace");
+			blockList = new ArrayList();
+			blockUpdate = new ArrayList();
+			offsetTime = -1;
+			latestTime = 0;
+		}
+		
+		/** 
+		 * Mark ending for all unfinished blocks
+		 */
+		public void endBlocks(int time) {
+            Iterator itr = blockList.iterator();
+            while (itr.hasNext()) {
+            	Object next = itr.next();
+            	if (next instanceof BlockModel) {
+            		BlockModel bm = (BlockModel) next;
+            		if (!bm.isFinish()) {
+            			bm.setEnd(time);
+            			
+            			Element evt = new Element("event");
+            			Element stop = new Element("statestop");
+            			stop.setAttribute("id", bm.getID());
+            			stop.setAttribute("time", ""+(bm.getEnd()+offsetTime));
+            			evt.addContent(stop);
+            			root.addContent(evt);            			
+            		}
+            	}
+            }
+		}
+		
+		public void endBlocks() {
+			endBlocks(latestTime);
+		}
+
+		/**
+		 * @param time
+		 *            (raw input from server)
+		 * @return time offset relative to the beginning of the trace
+		 */
+		private int getTime(int time) {
+			if (offsetTime == -1)
+				offsetTime = time;
+			time = time - offsetTime;
+			if (time > latestTime)
+				latestTime = time;
+			firePropertyChange(ModelConnector.EVENT_TRACE_UPDATE_TIME, null,
+					new Integer(time));
+			return time;
+		}
+
+		private void parseInput(Element e) {
+			Debugger.printDebug(Debugger.DEBUG_ALL, e.toString());
+			if (e.getName().equals("trace")) {
+				root = new Element("trace");
+
+				Iterator iter = e.getChildren().iterator();
+				while (iter.hasNext()) {
+					Element child = (Element) iter.next();
+					parseInput(child);
+				}
+			} else if (e.getName().equals("event")) {
+				root.addContent((Element) e.clone());
+				if ("image".equals(e.getAttributeValue("type"))) {
+					String sid = e.getAttributeValue("sid");
+					int time = getTime(Integer.parseInt(e
+							.getAttributeValue("time")));
+					String content = e.getChildText("image");
+					ImageModel img = new ImageModel(sid, time, content);
+					blockList.add(img);
+					blockUpdate.add(img);
+				} else if ("userlog".equals(e.getAttributeValue("type"))) {
+					// retrieve log interface
+					String sid = e.getAttributeValue("sid");
+					int time = getTime(Integer.parseInt(e
+							.getAttributeValue("time")));
+					String icon = e.getAttributeValue("icon");
+					String etid = e.getAttributeValue("etid");
+					String content = e.getText();
+					LogModel log = new LogModel(sid, time, icon, etid, content);
+					blockList.add(log);
+					blockUpdate.add(log);
+				} else if ("log".equals(e.getAttributeValue("type"))) {
+					// retrieve system log interface
+					String sid = e.getAttributeValue("sid");
+					int time = getTime(Integer.parseInt(e
+							.getAttributeValue("time")));
+					String content = "egid:" + e.getAttributeValue("egid")
+							+ "\n" + e.getText();
+					String egid = e.getAttributeValue("egid");
+					String etid = e.getAttributeValue("etid");
+					String filename = "flag.png";
+					// select icon map
+					String icon = (String) iconMap.get(egid);
+					if (icon != null)
+						filename = icon;
+					LogModel log = new LogModel(sid, time, filename, etid,
+							content);
+					blockList.add(log);
+					blockUpdate.add(log);
+				} else {
+					Iterator iter = e.getChildren().iterator();
+					while (iter.hasNext()) {
+						Element child = (Element) iter.next();
+						parseInput(child);
+					}
+				}
+			} else if (e.getName().equals("statestart")) {
+				String id = e.getAttributeValue("id");
+				int time = getTime(Integer
+						.parseInt(e.getAttributeValue("time")));
+				BlockModel bm = new BlockModel(id, time);
+
+				for (int i = blockList.size() - 1; i >= 0; i--) {
+					Object obj = blockList.get(i);
+					if (obj instanceof TransitionModel) {
+						TransitionModel tm = (TransitionModel) blockList.get(i);
+						if (tm.isDestNode(id)) {
+							tm.setEnd(time);
+							blockUpdate.add(tm);
+							break;
+						}
+					}
+				}
+				
+				blockList.add(bm);
+				blockUpdate.add(bm);
+			} else if (e.getName().equals("statestop")) {
+				String id = e.getAttributeValue("id");
+				int time = getTime(Integer
+						.parseInt(e.getAttributeValue("time")));
+				for (int i = blockList.size() - 1; i >= 0; i--) {
+					Object obj = blockList.get(i);
+					if (obj instanceof BlockModel) {
+						BlockModel bm = (BlockModel) blockList.get(i);
+						if (bm.getID().equals(id)) {
+							bm.setEnd(time);
+							blockUpdate.add(bm);
+							break;
+						}
+					} 					
+				}
+			} else if (e.getName().equals("fire")) {
+				String id = e.getAttributeValue("id");
+				int time = getTime(Integer
+						.parseInt(e.getAttributeValue("time")));
+				
+				
+				Object editor_obj = editor.getViewModel().getPartChild(id);
+                if (editor_obj instanceof MultiTransitionModel) {
+    				TransitionModel tm = new TransitionModel(id, time, (MultiTransitionModel)editor_obj);				
+    				blockList.add(tm);
+    				blockUpdate.add(tm);
+                }
+			}
+		}
+
+		public void inputChanged(Viewer v, Object oldInput, Object newInput) {
+		}
+
+		public void dispose() {
+		}
+
+		public Collection getElements() {
+			// sort by ending time first, then instant objects
+			SortedSet blockSet = new TreeSet(new Comparator() {
+				public int compare(Object arg0, Object arg1) {
+					if (arg0 instanceof AbstractModel && arg1 instanceof AbstractModel) {
+						AbstractModel obj0 = (AbstractModel)arg0, obj1 = (AbstractModel)arg1;
+						if (obj0.getEnd()==-1 && obj1.getEnd()>=0) return 1;
+						else if (obj1.getEnd()==-1 && obj0.getEnd()>=0) return -1;
+
+						int result = (obj0.getEnd()-obj1.getEnd());
+						if (result == 0) result = obj0.getStart()-obj1.getStart();
+						if (result == 0) result = obj0.getID().compareTo(obj1.getID());
+						return result;
+					} else throw new ClassCastException();
+				};
+			});
+			blockSet.addAll(blockList);
+			return blockSet;
+		}
+
+		public List getUpdate() {
+			List updateList = new ArrayList();
+			updateList.addAll(blockUpdate);
+			blockUpdate.clear();
+			return updateList;
+		}
+	}
+
+	class ViewLabelProvider extends LabelProvider implements
+			ITableLabelProvider {
+		public String getColumnText(Object obj, int index) {
+			return getText(obj);
+		}
+
+		public Image getColumnImage(Object obj, int index) {
+			return getImage(obj);
+		}
+
+		public Image getImage(Object obj) {
+			return PlatformUI.getWorkbench().getSharedImages().getImage(
+					ISharedImages.IMG_OBJ_ELEMENT);
+		}
+	}
+
+	class NameSorter extends ViewerSorter {
+	}
+
+	/**
+	 * The constructor.
+	 */
+	public StoryboardView() {
+	}
+
+	/**
+	 * This is a callback that will allow us to create the viewer and initialize
+	 * it.
+	 */
+	public void createPartControl(Composite parent) {
+		// viewer = new StoryboardViewer(parent, SWT.MULTI | SWT.H_SCROLL |
+		// SWT.V_SCROLL);
+		// viewer.setContentProvider(new ViewContentProvider());
+		// viewer.setLabelProvider(new ViewLabelProvider());
+		// viewer.setSorter(new NameSorter());
+
+		viewer = new StoryboardViewer(parent, this);
+		content = new ContentProvider();
+		// getSite().setSelectionProvider(viewer);
+		// content.readInput();
+		// viewer.setInput(getViewSite());
+		makeActions();
+		hookContextMenu();
+		// hookDoubleClickAction();
+		contributeToActionBars();
+		this.getViewSite().getWorkbenchWindow().getPartService()
+				.addPartListener(this);
+	}
+
+	private void hookContextMenu() {
+		MenuManager menuMgr = new MenuManager("#PopupMenu");
+		menuMgr.setRemoveAllWhenShown(true);
+		menuMgr.addMenuListener(new IMenuListener() {
+			public void menuAboutToShow(IMenuManager manager) {
+				StoryboardView.this.fillContextMenu(manager);
+			}
+		});
+		Menu menu = menuMgr.createContextMenu(viewer.getControl());
+		viewer.getControl().setMenu(menu);
+		getSite().registerContextMenu(menuMgr, viewer);
+	}
+
+	private void contributeToActionBars() {
+		IActionBars bars = getViewSite().getActionBars();
+		fillLocalPullDown(bars.getMenuManager());
+		fillLocalToolBar(bars.getToolBarManager());
+	}
+
+	private void fillLocalPullDown(IMenuManager manager) {
+		manager.add(redrawAction);
+		manager.add(loadTraceAction);
+		manager.add(saveTraceAction);
+	}
+
+	private void fillContextMenu(IMenuManager manager) {
+		manager.add(redrawAction);
+		manager.add(loadTraceAction);
+		manager.add(saveTraceAction);
+		manager.add(new Separator(IWorkbenchActionConstants.MB_ADDITIONS));
+	}
+
+	private void fillLocalToolBar(IToolBarManager manager) {
+		manager.add(redrawAction);
+		manager.add(loadTraceAction);
+		manager.add(saveTraceAction);
+	}
+
+	private void makeActions() {
+		redrawAction = new Action() {
+			public void run() {
+				// showMessage("Redraw storyboard");
+				viewer.setContent(content);
+				viewer.setInput(editor.getViewModel(), true);
+				viewer.refresh();
+
+				// ImageObject.test();
+			}
+		};
+		redrawAction.setText("Redraw Storyboard");
+		redrawAction.setToolTipText("Redraw current storyboard");
+		redrawAction.setImageDescriptor(ImageDescriptor
+				.createFromFile(
+						org.tekkotsu.ui.storyboard.icons.IconDummy.class,
+						"desktop.gif"));
+
+		loadTraceAction = new Action() {
+			private File queryFile() {
+				FileDialog dialog = new FileDialog(viewer.getControl()
+						.getShell(), SWT.OPEN);
+				dialog.setFilterExtensions(new String[] { "*.tse" });
+				dialog.setText("Open Trace File"); //$NON-NLS-1$
+				String path = dialog.open();
+				if (path != null && path.length() > 0)
+					return new File(path);
+				return null;
+			}
+
+			public void run() {
+				String filename = "";
+				ContentProvider oldContent = content;
+				try {
+					File file = queryFile();
+					filename = file.getName();
+					content.readInput(file);
+					content.endBlocks(viewer.timeline.getValue());
+					viewer.setContent(content);
+					viewer.setInput(editor.getViewModel(), true);
+					viewer.refresh();
+				} catch (Exception e) {
+					String msg = "Cannot open trace file " + filename;
+					MessageDialog.openError(viewer.getControl().getShell(),
+							"Problem", msg); //$NON-NLS-1$
+					content = oldContent;
+					viewer.setContent(content);
+					viewer.refresh();
+				}
+			}
+		};
+		loadTraceAction.setText("Load Trace");
+		loadTraceAction.setToolTipText("Load Execution Trace");
+		loadTraceAction.setImageDescriptor(ImageDescriptor.createFromFile(
+				org.tekkotsu.ui.storyboard.icons.IconDummy.class,
+				"fileopen.gif"));
+
+		saveTraceAction = new Action() {
+			private File queryFile() {
+				FileDialog dialog = new FileDialog(viewer.getControl()
+						.getShell(), SWT.SAVE);
+				dialog.setFilterExtensions(new String[] { "*.tse" });
+				dialog.setText("Save Trace File as"); //$NON-NLS-1$
+				String path = dialog.open();
+				if (path != null && path.length() > 0) {
+					if (!path.endsWith(".tse"))
+						path = path + ".tse";
+					return new File(path);
+				}
+				return null;
+			}
+
+			public void run() {
+				String filename="";
+				try {
+					File file = queryFile();
+					filename = file.getName();
+					viewer.setContent(content);
+					viewer.setInput(editor.getViewModel(), true);
+					viewer.refresh();
+					content.saveTrace(file);
+				} catch (Exception e) {
+					String msg = "Cannot write trace file " + filename;
+					MessageDialog.openError(viewer.getControl().getShell(), "Problem", msg);			
+				}
+			}
+		};
+		saveTraceAction.setText("Save Trace As");
+		saveTraceAction.setToolTipText("Save Execution Trace");
+		saveTraceAction.setImageDescriptor(ImageDescriptor.createFromFile(
+				org.tekkotsu.ui.storyboard.icons.IconDummy.class, "save.gif"));
+	}
+
+	/*
+	 * private void hookDoubleClickAction() { viewer.addDoubleClickListener(new
+	 * IDoubleClickListener() { public void doubleClick(DoubleClickEvent event) {
+	 * doubleClickAction.run(); } }); }
+	 */
+
+	private void showMessage(String message) {
+		MessageDialog.openInformation(viewer.getControl().getShell(),
+				"Storyboard View", message);
+	}
+
+	/**
+	 * Passing the focus request to the viewer's control.
+	 */
+	public void setFocus() {
+		viewer.getControl().setFocus();
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see java.beans.PropertyChangeListener#propertyChange(java.beans.PropertyChangeEvent)
+	 */
+	public void propertyChange(PropertyChangeEvent evt) {
+		// System.out.println(evt.getPropertyName());
+		if (evt.getPropertyName()
+				.equals(ModelConnector.EVENT_TRACE_UPDATE_TIME)) {
+			final PropertyChangeEvent ev = evt;
+			viewer.display.syncExec(new Runnable() {
+				public void run() {
+					int value = ((Integer) ev.getNewValue()).intValue();
+					// System.out.println("update evt: " + value);
+					viewer.timeline.setValue(value);
+					viewer.storyboard.setValue(value);
+					viewer.logBar.setValue(value);
+				}
+			});
+		} else if (evt.getPropertyName().equals(ViewModel.P_EXECUTION_TRACE)) {
+			// load trace from file
+			ContentProvider oldContent = content;
+			try {
+				String contentname = (String) evt.getNewValue();
+				content.readInput(contentname);
+				viewer.setContent(content);
+				viewer.setInput(editor.getViewModel(), true);
+				viewer.refresh();
+			} catch (Exception e) {
+				content = oldContent;
+				viewer.setContent(content);
+				viewer.setInput(editor.getViewModel(), true);
+				viewer.refresh();
+			}
+		} else if (evt.getPropertyName().equals(
+				ModelConnector.EVENT_TRACE_CLEAR)) {
+			// clear trace
+			content.clear();
+			viewer.setContent(content);
+			viewer.setInput(editor.getViewModel(), true);
+			viewer.refresh();
+		} else if (evt.getPropertyName().equals(
+				ModelConnector.EVENT_TRACE_REFRESH)) {
+			// refresh the board
+			// content.getUpdate((String)evt.getNewValue());
+			viewer.setContent(content);
+			viewer.setInput(editor.getViewModel(), true);
+			viewer.refresh();
+		} else if (evt.getPropertyName().equals(
+				ModelConnector.EVENT_TRACE_UPDATE)) {
+			// update trace
+			content.getUpdate((String) evt.getNewValue());
+			viewer.setContent(content);
+			viewer.setInput(editor.getViewModel(), false);
+			viewer.refresh();
+		} else if (evt.getPropertyName().equals(
+				ModelConnector.EVENT_TRACE_MODE_ENTER)) {
+			viewer.timeline.setLock(true);
+		} else if (evt.getPropertyName().equals(
+				ModelConnector.EVENT_TRACE_MODE_EXIT)) {
+			content.endBlocks(viewer.timeline.getValue());
+			viewer.timeline.setLock(false);			
+		}
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.ui.IPartListener#partActivated(org.eclipse.ui.IWorkbenchPart)
+	 */
+	public void partActivated(IWorkbenchPart part) {
+		// partOpened(part);
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.ui.IPartListener#partBroughtToTop(org.eclipse.ui.IWorkbenchPart)
+	 */
+	public void partBroughtToTop(IWorkbenchPart part) {
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.ui.IPartListener#partClosed(org.eclipse.ui.IWorkbenchPart)
+	 */
+	public void partClosed(IWorkbenchPart part) {
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.ui.IPartListener#partDeactivated(org.eclipse.ui.IWorkbenchPart)
+	 */
+	public void partDeactivated(IWorkbenchPart part) {
+		// partOpened(part);
+	}
+
+	/*
+	 * (non-Javadoc)
+	 * 
+	 * @see org.eclipse.ui.IPartListener#partOpened(org.eclipse.ui.IWorkbenchPart)
+	 */
+	public void partOpened(IWorkbenchPart part) {
+		if (part instanceof StateMachineEditor) {
+			editor = (StateMachineEditor) part;
+			String contentname = editor.getViewModel().getTracePath();
+			editor.getViewModel().addPropertyChangeListener(this);
+			editor.getModelConnector().addPropertyChangeListener(this);
+			this.addPropertyChangeListener(editor.getModelConnector());
+			viewer.addPropertyChangeListener(editor);
+			if (contentname != null) {
+				ContentProvider oldContent = content;
+				try {
+					content.readInput(contentname);
+					viewer.setContent(content);
+					viewer.setInput(editor.getViewModel());
+				} catch (Exception e) {
+					content = oldContent;
+					viewer.setContent(content);
+					viewer.setInput(editor.getViewModel());
+				}
+			}
+		} else if (part instanceof RuntimeView) {
+			runtime = (RuntimeView) part;
+			viewer.addPropertyChangeListener(runtime);
+		} else if (part instanceof ImageView) {
+			viewer.addPropertyChangeListener((ImageView) part);
+		}
+	}
+
+	private PropertyChangeSupport listeners = new PropertyChangeSupport(this);
+
+	public void addPropertyChangeListener(PropertyChangeListener listener) {
+		listeners.addPropertyChangeListener(listener);
+	}
+
+	public void firePropertyChange(String propName, Object oldValue,
+			Object newValue) {
+		listeners.firePropertyChange(propName, oldValue, newValue);
+	}
+
+	public void removePropertyChangeListener(PropertyChangeListener listener) {
+		listeners.removePropertyChangeListener(listener);
+	}
+
+}
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardViewer.java ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardViewer.java
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardViewer.java	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/src/org/tekkotsu/ui/storyboard/views/StoryboardViewer.java	2005-10-11 06:11:16.000000000 -0400
@@ -0,0 +1,414 @@
+/*
+ * Created on Nov 7, 2004
+ */
+package org.tekkotsu.ui.storyboard.views;
+
+import java.beans.PropertyChangeEvent;
+import java.beans.PropertyChangeListener;
+import java.beans.PropertyChangeSupport;
+import java.util.ArrayList;
+import java.util.Iterator;
+import java.util.List;
+
+import org.eclipse.draw2d.ColorConstants;
+import org.eclipse.draw2d.FigureCanvas;
+import org.eclipse.draw2d.LightweightSystem;
+import org.eclipse.draw2d.Panel;
+import org.eclipse.draw2d.XYLayout;
+import org.eclipse.draw2d.geometry.Rectangle;
+import org.eclipse.jface.viewers.ISelection;
+import org.eclipse.jface.viewers.StructuredSelection;
+import org.eclipse.jface.viewers.Viewer;
+import org.eclipse.swt.events.SelectionAdapter;
+import org.eclipse.swt.events.SelectionEvent;
+import org.eclipse.swt.widgets.Composite;
+import org.eclipse.swt.widgets.Control;
+import org.eclipse.swt.widgets.Display;
+import org.tekkotsu.ui.editor.model.MultiTransitionModel;
+import org.tekkotsu.ui.editor.model.StateNodeModel;
+import org.tekkotsu.ui.editor.model.ViewModel;
+import org.tekkotsu.ui.editor.resources.Debugger;
+import org.tekkotsu.ui.storyboard.ResourceRegistry;
+import org.tekkotsu.ui.storyboard.components.Block;
+import org.tekkotsu.ui.storyboard.components.ImageObject;
+import org.tekkotsu.ui.storyboard.components.LogBar;
+import org.tekkotsu.ui.storyboard.components.LogObject;
+import org.tekkotsu.ui.storyboard.components.Storyboard;
+import org.tekkotsu.ui.storyboard.components.TimeLine;
+import org.tekkotsu.ui.storyboard.components.Transition;
+import org.tekkotsu.ui.storyboard.model.AbstractModel;
+import org.tekkotsu.ui.storyboard.model.BlockModel;
+import org.tekkotsu.ui.storyboard.model.ImageModel;
+import org.tekkotsu.ui.storyboard.model.LogModel;
+import org.tekkotsu.ui.storyboard.model.TransitionModel;
+
+/**
+ * @author asangpet
+ *  
+ */
+public class StoryboardViewer extends Viewer {
+    Composite parent;
+
+    private PropertyChangeSupport listeners = new PropertyChangeSupport(this);
+
+    private ArrayList listenobjs = new ArrayList();
+
+    int timeLimit = TimeLine.TIMELINE_INIT_LIMIT;
+
+    StoryboardView host;
+
+    LightweightSystem lws;
+
+    Composite control = null;
+
+    FigureCanvas canvas = null;
+
+    StoryboardPanel panel = null;
+
+    TimeLine timeline;
+
+    LogBar logBar;
+
+    Storyboard storyboard;
+
+    ViewModel viewModel;
+
+    StoryboardView.ContentProvider content;
+
+    ISelection curSelect = null;
+
+    XYLayout contentsLayout = null;
+
+    Display display;
+
+    class StoryboardPanel extends Panel implements PropertyChangeListener {
+        public void setBounds(Rectangle rect) {
+            Rectangle old = getBounds();
+            super.setBounds(rect);
+            firePropertyChange(Storyboard.PROP_DIM_CHANGE, null, rect);
+        }
+
+        public void propertyChange(PropertyChangeEvent evt) {
+            if (TimeLine.TIMELINE_CURSOR_CHANGED.equals(evt.getPropertyName())) {
+                //System.out.println(evt.getNewValue().getClass()+" :
+                // "+evt.getNewValue());
+                /*
+                 * Integer value = (Integer)evt.getNewValue(); final int tcursor =
+                 * TimeLine.xoffset + value.intValue() * TimeLine.halfgap;
+                 * 
+                 * System.out.println("scroll to "+tcursor); final FigureCanvas
+                 * parent = (FigureCanvas)getParent(); display.syncExec(new
+                 * Runnable() { public void run() {
+                 * parent.scrollToX(tcursor+500); parent.update(); } });
+                 */
+            }
+        }
+    }
+
+    public StoryboardViewer(Composite parent, StoryboardView hostView) {
+        this.host = hostView;
+        this.parent = parent;
+
+        canvas = new FigureCanvas(parent);
+
+        display = canvas.getDisplay();
+        ResourceRegistry.init(display);
+
+        panel = new StoryboardPanel();
+        panel.setBackgroundColor(ColorConstants.white);
+        canvas.setContents(panel);
+
+        contentsLayout = new XYLayout();
+        panel.setLayoutManager(contentsLayout);
+
+        timeline = new TimeLine();
+        panel.add(timeline);
+        timeline.setLimit(TimeLine.TIMELINE_INIT_LIMIT);
+
+        canvas.getVerticalBar().addSelectionListener(new SelectionAdapter() {
+            public void widgetSelected(SelectionEvent event) {
+                panel.remove(timeline);
+                panel.add(timeline);
+                timeline.setVerticalOffset(canvas.getVerticalBar()
+                        .getSelection());
+
+                panel.remove(logBar);
+                panel.add(logBar);
+                logBar
+                        .setVerticalOffset(canvas.getVerticalBar()
+                                .getSelection());
+            }
+        });
+
+        storyboard = new Storyboard(this, timeline);
+        contentsLayout.setConstraint(storyboard, new Rectangle(0,
+                TimeLine.height + LogBar.height, timeline
+                        .getOffset(timeLimit), 200));
+        storyboard.setLayoutManager(new XYLayout());
+        panel.add(storyboard);
+
+        logBar = new LogBar(timeline);
+        logBar.setLayoutManager(new XYLayout());
+        panel.add(logBar);
+        logBar.setLimit(TimeLine.TIMELINE_INIT_LIMIT);
+
+        timeline.addPropertyChangeListener(storyboard);
+        timeline.addPropertyChangeListener(panel);
+        timeline.addPropertyChangeListener(logBar);
+
+        logBar.addPropertyChangeListener(storyboard);
+        logBar.addPropertyChangeListener(panel);
+        logBar.addPropertyChangeListener(timeline);
+
+        storyboard.addPropertyChangeListener(timeline);
+        storyboard.addPropertyChangeListener(logBar);
+
+        panel.addPropertyChangeListener(storyboard);
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#getControl()
+     */
+    public Control getControl() {
+        return canvas;
+    }
+
+    public void setContent(StoryboardView.ContentProvider content) {
+        this.content = content;
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.IInputProvider#getInput()
+     */
+    public Object getInput() {
+        return null;
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.ISelectionProvider#getSelection()
+     */
+    public ISelection getSelection() {
+        Debugger.printDebug(Debugger.DEBUG_ALL, "getting selection");
+        return curSelect;
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#refresh()
+     */
+    public void refresh() {
+        //storyboard.repaint();
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#setInput(java.lang.Object)
+     */
+    public void setInput(Object input) {
+        setInput(input, true);
+    }
+
+    public TimeLine getTimeLine() {
+        return timeline;
+    }
+
+    private void update(final Object newmodel) {
+        if (newmodel instanceof ImageModel) {
+            display.syncExec(new Runnable() {
+                public void run() {
+                    ImageModel obj = (ImageModel) newmodel;
+                    if (obj.getStart() >= timeline.getLimit() - 1) {
+                        timeline.setLimit(obj.getStart() + 100000);
+                        logBar.setLimit(timeline.getLimit());
+                        storyboard.setLimit(timeline.getLimit());
+                    }
+                    StateNodeModel state = (StateNodeModel) viewModel
+                            .getPartChild(obj.getID());
+                    // user in-state image object
+                    ImageObject img = new ImageObject(obj, state, timeline);
+                    storyboard.addChild(img);
+                    storyboard.getLayoutManager().setConstraint(img,
+                            img.getConstraint());
+                }
+            });
+        }
+        else if (newmodel instanceof LogModel) {
+            display.syncExec(new Runnable() {
+                public void run() {
+                    LogModel obj = (LogModel) newmodel;
+                    if (obj.getStart() >= timeline.getLimit() - 1) {
+                        timeline.setLimit(obj.getStart() + 100000);
+                        logBar.setLimit(timeline.getLimit());
+                        storyboard.setLimit(timeline.getLimit());
+                    }
+                    StateNodeModel state = (StateNodeModel) viewModel
+                            .getPartChild(obj.getID());
+                    if (state != null) {
+                        // user in-state log object
+                        LogObject log = new LogObject(obj, state, timeline);
+                        storyboard.addChild(log);
+                        storyboard.getLayoutManager().setConstraint(log,
+                                log.getConstraint());
+                    } else {
+                        // system log object
+                        LogObject log = new LogObject(obj, null, timeline);
+                        logBar.addChild(log);
+                        logBar.getLayoutManager().setConstraint(log,
+                                log.getConstraint());
+                    }
+                }
+            });
+        } else if (newmodel instanceof TransitionModel) {
+            display.syncExec(new Runnable() {
+                public void run() {
+                    TransitionModel obj = (TransitionModel) newmodel;
+                    if (obj.getStart() >= timeline.getLimit() - 1) {
+                        timeline.setLimit(obj.getStart() + 100000);
+                        logBar.setLimit(timeline.getLimit());
+                        storyboard.setLimit(timeline.getLimit());
+                    }
+                    Object editor_obj = viewModel.getPartChild(obj.getID());
+                    if (editor_obj instanceof MultiTransitionModel) {
+                        MultiTransitionModel trans = (MultiTransitionModel) editor_obj;
+                        Transition tr = new Transition(display, obj, trans,
+                                timeline);
+                        storyboard.addChild(tr);
+                        storyboard.getLayoutManager().setConstraint(tr,
+                                tr.getConstraint());
+                    }
+                }
+            });
+        } else if (newmodel instanceof BlockModel) {
+            display.syncExec(new Runnable() {
+                public void run() {
+                    BlockModel obj = (BlockModel) newmodel;
+                    // extends timeline limit for longer state
+                    if (obj.getEnd() >= timeline.getLimit() - 1) {
+                        timeline.setLimit(obj.getEnd() + 100000);
+                        logBar.setLimit(timeline.getLimit());
+                        storyboard.setLimit(timeline.getLimit());
+                    }
+                    StateNodeModel state = (StateNodeModel) viewModel
+                            .getPartChild(obj.getID());
+                    Block b = new Block(display, storyboard, obj, state,
+                            timeline);
+
+                    storyboard.addChild(b);
+                    storyboard.getLayoutManager().setConstraint(b,
+                            b.getConstraint());
+                }
+            });
+        }
+    }
+
+    public void setInput(Object input, boolean rebuild) {
+        Debugger.printDebug(Debugger.DEBUG_ALL, "Set input to model:" + input);
+        viewModel = (ViewModel) input;
+
+        if (rebuild) {
+            // redraw all elements
+            display.syncExec(new Runnable() {
+                public void run() {
+                    timeline.getMarker().clearMarker();
+                    timeline.repaint();
+                    storyboard.removeAll();
+                    logBar.removeAll();
+                }
+            });
+
+            Iterator iter = content.getElements().iterator();
+            while (iter.hasNext()) {
+                final Object next = iter.next();
+                update(next);
+            }
+        } else {
+            List elements = content.getUpdate();
+            //System.out.println("Update size "+elements.size()+" children
+            // "+storyboard.getChildren().size());
+
+            Iterator iter = elements.iterator();
+            while (iter.hasNext()) {
+                final Object next = iter.next();
+                update(next);
+            }
+        }
+
+        display.syncExec(new Runnable() {
+            public void run() {
+                int value = content.latestTime;
+                timeline.setValue(value);
+                storyboard.setValue(value);
+                logBar.setValue(value);
+                storyboard.validate();
+            }
+        });
+    }
+
+    /*
+     * (non-Javadoc)
+     * 
+     * @see org.eclipse.jface.viewers.Viewer#setSelection(org.eclipse.jface.viewers.ISelection,
+     *      boolean)
+     */
+    public void setSelection(ISelection selection, boolean reveal) {
+        Control control = getControl();
+        if (control == null || control.isDisposed()) {
+            return;
+        }
+
+        if (selection != null) {
+            if (selection instanceof StructuredSelection) {
+                StructuredSelection sselect = (StructuredSelection) selection;
+                Debugger.printDebug(Debugger.DEBUG_ALL, "Selection List:"
+                        + sselect.size());
+                Iterator iter = sselect.toList().iterator();
+                ArrayList nodes = new ArrayList();
+                ArrayList objnodes = new ArrayList();
+                // objnodes = integer node indicate current time + selected node
+                objnodes.add(new Integer(timeline.getValue()));
+                while (iter.hasNext()) {
+                    Object next = iter.next();
+                    if (next instanceof AbstractModel) {
+                        nodes.add(((AbstractModel) next).getID());
+                        objnodes.add(next);
+                    }
+                }
+                Debugger.printDebug(Debugger.DEBUG_ALL, "selections:" + nodes);
+
+                curSelect = sselect;
+                // SelectionChangedEvent evt = new
+                // SelectionChangedEvent(this,selection);
+                // fireSelectionChanged(evt);
+                this.firePropertyChange(ViewModel.P_ACTIVATE_CHANGE, null,
+                        nodes);
+                firePropertyChange("_BLOCK_INFO", null, objnodes);
+                // fireSelectionChanged(new SelectionChangedEvent(this,
+                // sselect));
+            }
+        }
+    }
+
+    public void addPropertyChangeListener(PropertyChangeListener listener) {
+        listeners.addPropertyChangeListener(listener);
+        listenobjs.add(listener);
+    }
+
+    public void firePropertyChange(String propName, Object oldValue,
+            Object newValue) {
+        listeners.firePropertyChange(propName, oldValue, newValue);
+    }
+
+    public void removePropertyChangeListener(PropertyChangeListener listener) {
+        listeners.removePropertyChangeListener(listener);
+        listenobjs.remove(listener);
+    }
+
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/storyboard.product ./tools/storyboard/org.tekkotsu.ui/storyboard.product
--- ../Tekkotsu_3.0/tools/storyboard/org.tekkotsu.ui/storyboard.product	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/org.tekkotsu.ui/storyboard.product	2007-03-01 15:27:11.000000000 -0500
@@ -0,0 +1,69 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<?pde version="3.1"?>
+
+<product name="Tekkotsu Storyboard Viewer" id="org.tekkotsu.ui.product" application="org.tekkotsu.ui.StoryboardApplication" useFeatures="false">
+
+   <aboutInfo>
+      <text>
+         Tekkotsu Storyboard Viewer
+      </text>
+   </aboutInfo>
+
+   <configIni use="default"/>
+
+   <launcherArgs>
+   </launcherArgs>
+
+   <windowImages i16="/org.tekkotsu.ui/icons/tekkotsu16.gif" i32="/org.tekkotsu.ui/icons/Storyboard32.gif"/>
+
+
+   <launcher name="Storyboard">
+      <linux icon="/org.tekkotsu.ui/icons/Storyboard128.xpm"/>
+      <macosx icon="Storyboard/icons/Storyboard.icns"/>
+      <solaris/>
+      <win useIco="true">
+         <ico path="/org.tekkotsu.ui/icons/Storyboard.ico"/>
+         <bmp/>
+      </win>
+   </launcher>
+
+
+   <plugins>
+      <plugin id="com.ibm.icu"/>
+      <plugin id="org.eclipse.core.commands"/>
+      <plugin id="org.eclipse.core.contenttype"/>
+      <plugin id="org.eclipse.core.expressions"/>
+      <plugin id="org.eclipse.core.filesystem"/>
+      <plugin id="org.eclipse.core.filesystem.macosx" fragment="true"/>
+      <plugin id="org.eclipse.core.filesystem.win32.x86"/>
+      <plugin id="org.eclipse.core.jobs"/>
+      <plugin id="org.eclipse.core.runtime"/>
+      <plugin id="org.eclipse.core.runtime.compatibility.auth"/>
+      <plugin id="org.eclipse.core.runtime.compatibility.registry" fragment="true"/>
+      <plugin id="org.eclipse.core.variables"/>
+      <plugin id="org.eclipse.draw2d"/>
+      <plugin id="org.eclipse.equinox.common"/>
+      <plugin id="org.eclipse.equinox.preferences"/>
+      <plugin id="org.eclipse.equinox.registry"/>
+      <plugin id="org.eclipse.gef"/>
+      <plugin id="org.eclipse.help"/>
+      <plugin id="org.eclipse.jface"/>
+      <plugin id="org.eclipse.jface.text"/>
+      <plugin id="org.eclipse.osgi"/>
+      <plugin id="org.eclipse.swt"/>
+      <plugin id="org.eclipse.swt.carbon.macosx" fragment="true"/>
+      <plugin id="org.eclipse.swt.carbon.macosx.ppc"/>
+      <plugin id="org.eclipse.swt.gtk.linux.x86"/>
+      <plugin id="org.eclipse.swt.win32.win32.x86"/>
+      <plugin id="org.eclipse.text"/>
+      <plugin id="org.eclipse.ui"/>
+      <plugin id="org.eclipse.ui.carbon" fragment="true"/>
+      <plugin id="org.eclipse.ui.console"/>
+      <plugin id="org.eclipse.ui.views"/>
+      <plugin id="org.eclipse.ui.workbench"/>
+      <plugin id="org.eclipse.ui.workbench.texteditor"/>
+      <plugin id="org.eclipse.update.configurator"/>
+      <plugin id="org.tekkotsu.ui"/>
+   </plugins>
+
+</product>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-layout.tsl ./tools/storyboard/samples/LogTestMachine/LogTest-layout.tsl
--- ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-layout.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/LogTestMachine/LogTest-layout.tsl	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,14 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="./LogTest-model.tsm">
+  <state id="Logging Test" label="Logging Test" color="#ffc400" top="32" left="67" width="168" height="20" shape="Rectangle" />
+  <state id="Waiting" label="Waiting" color="#00ff00" top="183" left="124" width="50" height="20" shape="Rectangle" />
+  <state id="Image" label="Image" color="#002fff" top="96" left="142" width="50" height="20" shape="Rectangle" />
+  <state id="Message" label="Message" color="#a020f0" top="95" left="52" width="73" height="20" shape="Rectangle" />
+  <state id="Webcam" label="Webcam" color="#ff0000" top="95" left="216" width="76" height="20" shape="Rectangle" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans" label="transition9" color="#000000" top="140" left="165" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans" label="transition13" color="#000000" top="127" left="125" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans" label="transition17" color="#000000" top="152" left="198" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition21" color="#000000" top="136" left="125" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition25" color="#000000" top="149" left="93" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans" label="transition29" color="#000000" top="124" left="170" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-model.tsm ./tools/storyboard/samples/LogTestMachine/LogTest-model.tsm
--- ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-model.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/LogTestMachine/LogTest-model.tsm	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,32 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Logging Test" class="LogTestMachine" />
+  <state id="Waiting" class="StateNode" />
+  <state id="Image" class="ImageLogTestNode" />
+  <state id="Message" class="MessageLogTestNode" />
+  <state id="Webcam" class="WebcamLogTestNode" />
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Image}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Image</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Message}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Message</destination>
+  </transition>
+  <transition id="{Waiting}--TextMsgTrans--&gt;{Webcam}" class="TextMsgTrans">
+    <source>Waiting</source>
+    <destination>Webcam</destination>
+  </transition>
+  <transition id="{Image}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Image</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Message}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Message</source>
+    <destination>Waiting</destination>
+  </transition>
+  <transition id="{Webcam}--NullTrans--&gt;{Waiting}" class="NullTrans">
+    <source>Webcam</source>
+    <destination>Waiting</destination>
+  </transition>
+</model>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-trace.tse ./tools/storyboard/samples/LogTestMachine/LogTest-trace.tse
--- ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-trace.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/LogTestMachine/LogTest-trace.tse	2005-10-18 12:16:00.000000000 -0400
@@ -0,0 +1,76 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="302429" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="302430" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="310856" />
+    <statestop id="Waiting" time="310859" />
+    <statestart id="Image" time="310860" />
+  </event>
+  <event type="image" sid="Image" time="310886">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="310923" />
+    <statestop id="Image" time="310924" />
+    <statestart id="Waiting" time="310924" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="320628" />
+    <statestop id="Waiting" time="320630" />
+    <statestart id="Webcam" time="320632" />
+  </event>
+  <event type="webcam" sid="Webcam" time="320632" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="320643" />
+    <statestop id="Webcam" time="320645" />
+    <statestart id="Waiting" time="320645" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="327596" />
+    <statestop id="Waiting" time="327598" />
+    <statestart id="Message" time="327602" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="327603">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="327604" />
+    <statestop id="Message" time="327605" />
+    <statestart id="Waiting" time="327605" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="338412" />
+    <statestop id="Waiting" time="338416" />
+    <statestart id="Message" time="338418" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="338419">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="338420" />
+    <statestop id="Message" time="338421" />
+    <statestart id="Waiting" time="338421" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="347770" />
+    <statestop id="Waiting" time="347773" />
+    <statestart id="Image" time="347774" />
+  </event>
+
+  <event type="image" sid="Image" time="347800">
+    <image>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</image>
+  </event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="347829" />
+    <statestop id="Image" time="347835" />
+    <statestart id="Waiting" time="347835" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="359629" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="359635" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-trace2.tse ./tools/storyboard/samples/LogTestMachine/LogTest-trace2.tse
--- ../Tekkotsu_3.0/tools/storyboard/samples/LogTestMachine/LogTest-trace2.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/LogTestMachine/LogTest-trace2.tse	2005-10-18 12:16:00.000000000 -0400
@@ -0,0 +1,93 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+  <event>
+    <statestart id="Logging Test" time="458806" />
+  </event>
+  <event>
+    <statestart id="Waiting" time="458808" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="467332" />
+    <statestop id="Waiting" time="467334" />
+    <statestart id="Webcam" time="467337" />
+  </event>
+  <event type="webcam" sid="Webcam" time="467338" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="467339" />
+    <statestop id="Webcam" time="467339" />
+    <statestart id="Waiting" time="467340" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="476586" />
+    <statestop id="Waiting" time="476588" />
+    <statestart id="Message" time="476589" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="476589">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="476601" />
+    <statestop id="Message" time="476603" />
+    <statestart id="Waiting" time="476603" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="483868" />
+    <statestop id="Waiting" time="483870" />
+    <statestart id="Message" time="483874" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="483874">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="483875" />
+    <statestop id="Message" time="483875" />
+    <statestart id="Waiting" time="483876" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="491562" />
+    <statestop id="Waiting" time="491564" />
+    <statestart id="Image" time="491565" />
+  </event>
+  <event type="image" sid="Image" time="491592"><image>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</image></event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="491626" />
+    <statestop id="Image" time="491628" />
+    <statestart id="Waiting" time="491628" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Message}" time="503628" />
+    <statestop id="Waiting" time="503630" />
+    <statestart id="Message" time="503634" />
+  </event>
+  <event type="userlog" sid="Message" voff="0" time="503634">Hello World!</event>
+  <event>
+    <fire id="{Message}--NullTrans--&gt;{Waiting}" time="503641" />
+    <statestop id="Message" time="503643" />
+    <statestart id="Waiting" time="503644" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Image}" time="512259" />
+    <statestop id="Waiting" time="512261" />
+    <statestart id="Image" time="512262" />
+  </event>
+  <event type="image" sid="Image" time="512290"><image>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</image></event>
+  <event>
+    <fire id="{Image}--NullTrans--&gt;{Waiting}" time="512322" />
+    <statestop id="Image" time="512323" />
+    <statestart id="Waiting" time="512323" />
+  </event>
+  <event>
+    <fire id="{Waiting}--TextMsgTrans--&gt;{Webcam}" time="524427" />
+    <statestop id="Waiting" time="524428" />
+    <statestart id="Webcam" time="524429" />
+  </event>
+  <event type="webcam" sid="Webcam" time="524429" />
+  <event>
+    <fire id="{Webcam}--NullTrans--&gt;{Waiting}" time="524441" />
+    <statestop id="Webcam" time="524443" />
+    <statestart id="Waiting" time="524444" />
+  </event>
+  <event>
+    <statestop id="Waiting" time="532750" />
+  </event>
+  <event>
+    <statestop id="Logging Test" time="532752" />
+  </event>
+</trace>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/abc/abc.tse ./tools/storyboard/samples/abc/abc.tse
--- ../Tekkotsu_3.0/tools/storyboard/samples/abc/abc.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/abc/abc.tse	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,187 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+<event>
+<statestart id="alpha" time="964925" />
+</event>
+<event>
+<statestop id="alpha" time="967930" />
+<statestart id="bravo" time="967930" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="967931" />
+</event>
+<event>
+<statestop id="bravo" time="970939" />
+<statestart id="charlie" time="970939" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="970939" />
+</event>
+<event type="userlog" sid="charlie" time="972000" voff="15">LogMe</event>
+<event>
+<statestop id="charlie" time="973947" />
+<statestart id="alpha" time="973947" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="973947" />
+</event>
+<event>
+<statestop id="alpha" time="976954" />
+<statestart id="bravo" time="976954" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="976955" />
+</event>
+<event>
+<statestop id="bravo" time="979962" />
+<statestart id="charlie" time="979963" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="979963" />
+</event>
+<event>
+<statestop id="charlie" time="981814" />
+<statestart id="alpha" time="981979" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="981979" />
+</event>
+<event>
+<statestop id="alpha" time="996794" />
+<statestart id="bravo" time="996794" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="996795" />
+</event>
+<event type="userlog" sid="bravo" time="998000" voff="15">LogMe2</event>
+<event>
+<statestop id="bravo" time="999803" />
+<statestart id="charlie" time="999803" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="999803" />
+</event>
+<event type="userlog" sid="charlie" time="1000000" voff="15">LogMe3</event>
+<event>
+<statestop id="charlie" time="1002810" />
+<statestart id="alpha" time="1002810" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1002811" />
+</event>
+<event>
+<statestop id="alpha" time="1005818" />
+<statestart id="bravo" time="1005818" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1005819" />
+</event>
+<event>
+<statestop id="bravo" time="1008826" />
+<statestart id="charlie" time="1008827" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1008827" />
+</event>
+<event>
+<statestop id="charlie" time="1011827" />
+<statestart id="alpha" time="1011827" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1011827" />
+</event>
+<event>
+<statestop id="alpha" time="1014842" />
+<statestart id="bravo" time="1014842" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1014843" />
+</event>
+<event>
+<statestop id="bravo" time="1017850" />
+<statestart id="charlie" time="1017850" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1017851" />
+</event>
+<event>
+<statestop id="charlie" time="1020860" />
+<statestart id="alpha" time="1020860" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1020860" />
+</event>
+<event>
+<statestop id="alpha" time="1023866" />
+<statestart id="bravo" time="1023867" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1023867" />
+</event>
+<event>
+<statestop id="bravo" time="1026874" />
+<statestart id="charlie" time="1026875" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1026875" />
+</event>
+<event>
+<statestop id="charlie" time="1029882" />
+<statestart id="alpha" time="1029883" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1029883" />
+</event>
+<event>
+<statestop id="alpha" time="1032890" />
+<statestart id="bravo" time="1032890" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1032891" />
+</event>
+<event>
+<statestop id="bravo" time="1035898" />
+<statestart id="charlie" time="1035899" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1035899" />
+</event>
+<event>
+<statestop id="charlie" time="1038906" />
+<statestart id="alpha" time="1038907" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1038907" />
+</event>
+<event>
+<statestop id="alpha" time="1041914" />
+<statestart id="bravo" time="1041915" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1041915" />
+</event>
+<event>
+<statestop id="bravo" time="1044922" />
+<statestart id="charlie" time="1044923" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1044923" />
+</event>
+<event>
+<statestop id="charlie" time="1047923" />
+<statestart id="alpha" time="1047923" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1047924" />
+</event>
+<event>
+<statestop id="alpha" time="1050930" />
+<statestart id="bravo" time="1050931" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1050931" />
+</event>
+<event>
+<statestop id="bravo" time="1053947" />
+<statestart id="charlie" time="1053947" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1053947" />
+</event>
+<event>
+<statestop id="charlie" time="1056954" />
+<statestart id="alpha" time="1056955" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1056955" />
+</event>
+<event>
+<statestop id="alpha" time="1059962" />
+<statestart id="bravo" time="1059962" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1059963" />
+</event>
+<event>
+<statestop id="bravo" time="1062971" />
+<statestart id="charlie" time="1062971" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1062971" />
+</event>
+<event>
+<statestop id="charlie" time="1065978" />
+<statestart id="alpha" time="1065979" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1065979" />
+</event>
+<event>
+<statestop id="alpha" time="1068986" />
+<statestart id="bravo" time="1068987" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1068987" />
+</event>
+<event>
+<statestop id="bravo" time="1071994" />
+<statestart id="charlie" time="1071995" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1071995" />
+</event>
+<event>
+<statestop id="charlie" time="1075003" />
+<statestart id="alpha" time="1075003" />
+<fire id="{charlie}--TimeOutTrans--&gt;{alpha}" time="1075003" />
+</event>
+<event>
+<statestop id="alpha" time="1078010" />
+<statestart id="bravo" time="1078011" />
+<fire id="{alpha}--TimeOutTrans--&gt;{bravo}" time="1078011" />
+</event>
+<event>
+<statestop id="bravo" time="1081018" />
+<statestart id="charlie" time="1081019" />
+<fire id="{bravo}--TimeOutTrans--&gt;{charlie}" time="1081019" />
+</event>
+<event>
+<statestop id="charlie" time="1084026" />
+</event>
+</trace>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/abc/abc.tsl ./tools/storyboard/samples/abc/abc.tsl
--- ../Tekkotsu_3.0/tools/storyboard/samples/abc/abc.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/abc/abc.tsl	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,9 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="./abc.tsm">
+  <state id="alpha" label="alpha" color="#ff0000" top="14" left="84" width="48" height="43" shape="Ellipse" />
+  <state id="bravo" label="bravo" color="#80ff00" top="70" left="184" width="43" height="43" shape="Ellipse" />
+  <state id="charlie" label="charlie" color="#004080" top="130" left="38" width="47" height="43" shape="Ellipse" />
+  <transition id="{alpha}--TimeOutTrans--&gt;{bravo}" class="t_ab" label="transition67" color="#000000" top="73" left="124" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{bravo}--TimeOutTrans--&gt;{charlie}" class="t_bc" label="transition71" color="#000000" top="88" left="112" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="{charlie}--TimeOutTrans--&gt;{alpha}" class="t_ca" label="transition75" color="#000000" top="85" left="87" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/abc/abc.tsm ./tools/storyboard/samples/abc/abc.tsm
--- ../Tekkotsu_3.0/tools/storyboard/samples/abc/abc.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/abc/abc.tsm	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,18 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="alpha" class="StateNode" />
+  <state id="bravo" class="StateNode" />
+  <state id="charlie" class="StateNode" />
+  <transition id="{alpha}--TimeOutTrans-->{bravo}" class="TimeOutTrans">
+  	<source>alpha</source>
+  	<destination>bravo</destination>
+  </transition>
+  <transition id="{bravo}--TimeOutTrans-->{charlie}" class="TimeOutTrans">
+  	<source>bravo</source>
+  	<destination>charlie</destination>
+  </transition>
+  <transition id="{charlie}--TimeOutTrans-->{alpha}" class="TimeOutTrans">
+  	<source>charlie</source>
+  	<destination>alpha</destination>
+  </transition>
+</model>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/bark/bark.tsl ./tools/storyboard/samples/bark/bark.tsl
--- ../Tekkotsu_3.0/tools/storyboard/samples/bark/bark.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/bark/bark.tsl	2005-10-18 12:16:00.000000000 -0400
@@ -0,0 +1,11 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="E:\tekkotsu\viewer\bark.tsm">
+  <state id="Bark" label="Bark" color="#ffc800" top="49" left="42" width="50" height="34" shape="Hexagon" />
+  <state id="Howl" label="Howl" color="#00ff00" top="141" left="110" width="50" height="34" shape="Rectangle" />
+  <state id="Wait" label="Wait" color="#ffafaf" top="47" left="185" width="42" height="42" shape="Ellipse" />
+  <transition id="timeout5" class="TimeOutTrans" label="transition11" color="#000000" top="106" left="68" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="btrans" class="EventTrans" label="transition37" color="#000000" top="87" left="157" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="timeout15" class="TimeOutTrans" label="transition45" color="#000000" top="87" left="237" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="complete" class="CompletionTrans" label="transition49" color="#000000" top="87" left="277" width="50" height="20" shape="Ellipse" linewidth="1" />
+</view>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/bark/bark.tsm ./tools/storyboard/samples/bark/bark.tsm
--- ../Tekkotsu_3.0/tools/storyboard/samples/bark/bark.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/bark/bark.tsm	2005-10-18 12:16:00.000000000 -0400
@@ -0,0 +1,23 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Bark" class="SoundNode" />
+  <state id="Howl" class="SoundNode" />
+  <state id="Wait" class="StateNode" />
+  <transition id="btrans" class="EventTrans">
+    <source>Bark</source>
+    <destination>Wait</destination>
+  </transition>
+  <transition id="timeout5" class="TimeOutTrans">
+    <source>Bark</source>
+    <destination>Howl</destination>
+  </transition>
+  <transition id="timeout15" class="TimeOutTrans">
+    <source>Wait</source>
+    <destination>Bark</destination>
+  </transition>
+  <transition id="complete" class="CompletionTrans">
+    <source>Howl</source>
+    <destination>Wait</destination>
+  </transition>
+</model>
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/drama/drama.tse ./tools/storyboard/samples/drama/drama.tse
--- ../Tekkotsu_3.0/tools/storyboard/samples/drama/drama.tse	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/drama/drama.tse	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,79 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<trace>
+<event>
+<statestart id="Funny" time="1000" />
+</event>
+<event>
+<statestop id="Funny" time="5000" />
+<statestart id="Pink" time="5002" />
+<fire id="Funny--&gt;Pink" time="5001" />
+</event>
+<event type="userlog" sid="Pink" time="7000" voff="15">Waiting</event>
+<event>
+<statestop id="Pink" time="9000" />
+<statestart id="Funny" time="9002" />
+<fire id="Pink--&gt;Funny" time="9001" />
+</event>
+<event>
+<statestop id="Funny" time="9500" />
+<statestart id="Pink" time="9502" />
+<fire id="Funny--&gt;Pink" time="9501" />
+</event>
+<event type="log" egid="button" sid="leftpaw" etid="D" time="9503">paw</event>
+<event type="log" egid="locomotion" sid="mot" etid="D" time="9504"></event>
+<event type="log" egid="locomotion" sid="mot" etid="S" time="9505"></event>
+<event type="log" egid="audio" sid="aud" etid="A" time="9506"></event>
+<event>
+<statestop id="Pink" time="9800" />
+<statestart id="Follow" time="9802" />
+<fire id="Pink--&gt;Follow" time="9801" />
+</event>
+<event type="log" egid="button" sid="mot" etid="A" time="9850"></event>
+<event>
+<statestop id="Follow" time="9883" />
+<statestart id="Timer" time="9885" />
+<fire id="Follow--&gt;Timer" time="9884" />
+</event>
+<event type="userlog" sid="Timer" time="21000" voff="15">more waiting</event>
+<event>
+<statestop id="Timer" time="28000" />
+<statestart id="Sit" time="28002" />
+<fire id="Timer--&gt;Sit" time="28001" />
+</event>
+<event type="log" egid="timer" sid="mot" etid="D" time="28500">time out</event>
+<event>
+<statestop id="Sit" time="28500" />
+<statestart id="Sound" time="28702" />
+<fire id="Sit--&gt;Sound" time="28601" />
+</event>
+<event type="log" egid="audio" sid="audi" etid="A" time="32000"></event>
+<event>
+<statestop id="Sound" time="35000" />
+<statestart id="Down" time="35002" />
+<fire id="Sound--&gt;Down" time="35001" />
+</event>
+<event>
+<statestop id="Down" time="38000" />
+<statestart id="Sniff" time="38002" />
+<fire id="Down--&gt;Sniff" time="38001" />
+</event>
+<event>
+<statestop id="Sniff" time="44000" />
+<statestart id="Up" time="44002" />
+<fire id="Sniff--&gt;Up" time="44001" />
+</event>
+<event type="log" egid="textmsg" sid="mot" etid="S" time="47000">Hello world</event>
+<event>
+<statestop id="Up" time="48000" />
+<statestart id="Punch" time="48002" />
+<statestart id="Look" time="48002" />
+<fire id="Up--&gt;PunchLook" time="48001" />
+</event>
+<event>
+<statestop id="Punch" time="52002" />
+</event>
+<event>
+<statestop id="Look" time="55002" />
+</event>
+<event type="log" egid="estop" sid="stop" etid="A" time="55003"></event>
+</trace>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/drama/drama.tsl ./tools/storyboard/samples/drama/drama.tsl
--- ../Tekkotsu_3.0/tools/storyboard/samples/drama/drama.tsl	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/drama/drama.tsl	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,24 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<view model="./drama.tsm">
+  <state id="Funny" label="Funny" color="#0000ff" top="68" left="47" width="52" height="34" shape="Rounded Rectangle" />
+  <state id="Pink" label="Pink" color="#ff80ff" top="14" left="37" width="50" height="20" shape="Rounded Rectangle" />
+  <state id="Follow" label="Follow" color="#02cc27" top="13" left="156" width="50" height="20" shape="Ellipse" />
+  <state id="Timer" label="Timer" color="#02cc95" top="77" left="165" width="50" height="20" shape="Rectangle" />
+  <state id="Sit" label="Sit" color="#0295cc" top="25" left="261" width="50" height="20" shape="Ellipse" />
+  <state id="Sound" label="Sound" color="#0227cc" top="99" left="229" width="50" height="20" shape="Ellipse" />
+  <state id="Down" label="Down" color="#4b02cc" top="168" left="270" width="50" height="20" shape="Ellipse" />
+  <state id="Sniff" label="Sniff" color="#ba02cc" top="186" left="167" width="50" height="20" shape="Ellipse" />
+  <state id="Up" label="Up" color="#cc0270" top="113" left="103" width="50" height="20" shape="Ellipse" />
+  <state id="Look" label="Look" color="#cc0202" top="202" left="59" width="50" height="20" shape="Ellipse" />
+  <state id="Punch" label="Punch" color="#cc7002" top="150" left="22" width="50" height="20" shape="Ellipse" />
+  <transition id="Funny--&gt;Pink" class="t_fp" label="transition15" color="#000000" top="33" left="65" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Pink--&gt;Funny" class="t_pf" label="transition19" color="#000000" top="47" left="27" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Pink--&gt;Follow" class="t_pfo" label="transition23" color="#000000" top="37" left="95" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Follow--&gt;Timer" class="t_ft" label="transition27" color="#000000" top="52" left="141" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Timer--&gt;Sit" class="t_ts" label="transition31" color="#000000" top="72" left="221" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Sit--&gt;Sound" class="t_ss" label="transition35" color="#000000" top="59" left="229" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Sound--&gt;Down" class="t_sd" label="transition39" color="#000000" top="146" left="241" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Down--&gt;Sniff" class="t_ds" label="transition43" color="#000000" top="157" left="228" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Sniff--&gt;Up" class="t_su" label="transition47" color="#000000" top="136" left="164" width="50" height="20" shape="Ellipse" linewidth="1" />
+  <transition id="Up--&gt;PunchLook" class="t_upl" label="" color="#000000" top="157" left="104" width="43" height="20" shape="Ellipse" linewidth="1" />
+</view>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/storyboard/samples/drama/drama.tsm ./tools/storyboard/samples/drama/drama.tsm
--- ../Tekkotsu_3.0/tools/storyboard/samples/drama/drama.tsm	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/storyboard/samples/drama/drama.tsm	2005-10-19 10:24:10.000000000 -0400
@@ -0,0 +1,55 @@
+<?xml version="1.0" encoding="UTF-8"?>
+<model>
+  <state id="Funny" class="c_funny" />
+  <state id="Pink" class="c_pink" />
+  <state id="Follow" class="c_follow" />
+  <state id="Timer" class="c_timer" />
+  <state id="Sit" class="c_sit" />
+  <state id="Sound" class="c_sound" />
+  <state id="Down" class="c_down" />
+  <state id="Sniff" class="c_sniff" />
+  <state id="Up" class="c_up" />
+  <state id="Look" class="c_look" />
+  <state id="Punch" class="c_punch" />
+  <transition id="Funny--&gt;Pink" class="t_fp">
+    <source>Funny</source>
+    <destination>Pink</destination>
+  </transition>
+  <transition id="Pink--&gt;Funny" class="t_pf">
+    <source>Pink</source>
+    <destination>Funny</destination>
+  </transition>
+  <transition id="Pink--&gt;Follow" class="t_pfo">
+    <source>Pink</source>
+    <destination>Follow</destination>
+  </transition>
+  <transition id="Follow--&gt;Timer" class="t_ft">
+    <source>Follow</source>
+    <destination>Timer</destination>
+  </transition>
+  <transition id="Timer--&gt;Sit" class="t_ts">
+    <source>Timer</source>
+    <destination>Sit</destination>
+  </transition>
+  <transition id="Sit--&gt;Sound" class="t_ss">
+    <source>Sit</source>
+    <destination>Sound</destination>
+  </transition>
+  <transition id="Sound--&gt;Down" class="t_sd">
+    <source>Sound</source>
+    <destination>Down</destination>
+  </transition>
+  <transition id="Down--&gt;Sniff" class="t_ds">
+    <source>Down</source>
+    <destination>Sniff</destination>
+  </transition>
+  <transition id="Sniff--&gt;Up" class="t_su">
+    <source>Sniff</source>
+    <destination>Up</destination>
+  </transition>
+  <transition id="Up--&gt;PunchLook" class="t_upl">
+    <source>Up</source>
+    <destination>Punch</destination>
+    <destination>Look</destination>
+  </transition>
+</model>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/base64/Makefile ./tools/test/base64/Makefile
--- ../Tekkotsu_3.0/tools/test/base64/Makefile	2006-03-28 12:08:24.000000000 -0500
+++ ./tools/test/base64/Makefile	2007-11-15 20:03:34.000000000 -0500
@@ -15,15 +15,17 @@
 SRCSUFFIX:=.cc
 PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
 
-# We use a hard-coded TEKKOTSU_ROOT so this tool is always linked against the
-# the framework directory which contains it
-TEKKOTSU_ROOT=../../..
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -33,21 +35,26 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
 CXXFLAGS:=-g -Wall -O2 \
          -I$(TEKKOTSU_ROOT) \
-         -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -75,17 +82,18 @@
 	test $$retval -eq 0; \
 
 clean:
-	rm -rf $(BIN) $(PROJECT_BUILDDIR) test-* *~
+	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
 
-test: $(BIN)
+test: ./$(BIN)
 	./$(BIN) encode binary.gif > test-encoded_b64.txt
 	./$(BIN) decode encoded_b64.txt > test-binary.gif
 	@for x in * ; do \
 		if [ -r "test-$$x" ] ; then \
-			if diff -u "test-$$x" "$$x" ; then \
+			if diff -q "test-$$x" "$$x" ; then \
 				echo "Test '$$x' passed"; \
 			else \
 				echo "Test output '$$x' does not match ideal"; \
+				exit 1; \
 			fi; \
 		fi; \
 	done
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/Makefile ./tools/test/config/Makefile
--- ../Tekkotsu_3.0/tools/test/config/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/Makefile	2007-11-21 23:09:20.000000000 -0500
@@ -0,0 +1,98 @@
+
+# This Makefile will handle most aspects of compiling and
+# linking a tool against the Tekkotsu framework.  You probably
+# won't need to make any modifications, but here's the major controls
+
+# Executable name, defaults to:
+#   `basename \`pwd\``-$(TEKKOTSU_TARGET_MODEL)
+TEKKOTSU_TARGET_MODEL?=TGT_ERS7
+BIN:=$(shell pwd | sed 's@.*/@@')-$(shell echo $(patsubst TGT_%,%,$(TEKKOTSU_TARGET_MODEL)))
+
+# Build directory
+PROJECT_BUILDDIR:=build
+
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
+
+# Source files, defaults to all files ending matching *$(SRCSUFFIX)
+SRCSUFFIX:=.cc
+PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)") \
+	$(addprefix $(TEKKOTSU_ROOT)/Shared/,Config.cc LoadSave.cc plist.cc plistBase.cc plistCollections.cc plistPrimitives.cc XMLLoadSave.cc string_util.cc RobotInfo.cc)
+
+.PHONY: all test
+
+TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
+TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+
+TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
+include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
+FILTERSYSWARN:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(FILTERSYSWARN))
+COLORFILT:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(COLORFILT))
+$(shell mkdir -p $(PROJ_BD))
+
+PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
+
+# this one doesn't actually need libtekkotsu.a
+LIBS:= 
+# $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+
+DEPENDS:=$(PROJ_OBJ:.o=.d)
+
+CXXFLAGS:=-g -Wall -O2 \
+         -I$(TEKKOTSU_ROOT) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
+
+
+all: $(BIN)
+
+$(BIN): $(PROJ_OBJ) $(LIBS)
+	@echo "Linking $@..."
+	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+
+ifeq ($(findstring clean,$(MAKECMDGOALS)),)
+-include $(DEPENDS)
+endif
+
+%.a :
+	@echo "ERROR: $@ was not found.  You may need to compile the Tekkotsu framework."
+	@echo "Press return to attempt to build it, ctl-C to cancel."
+	@read;
+	$(MAKE) -C $(TEKKOTSU_ROOT) compile
+
+%.d :
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.d,%.cc,$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "$@..." | sed 's@.*$(TGT_BD)/@Generating @'; \
+	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
+
+%.o:
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "Compiling $$src..."; \
+	$(CXX) $(CXXFLAGS) -o $@ -c $$src > $*.log 2>&1; \
+	retval=$$?; \
+	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
+	test $$retval -eq 0; \
+
+clean:
+	rm -rf $(BIN) $(PROJECT_BUILDDIR) Shared *~ tekkotsu*.plist test*.plist
+
+test: ./$(BIN)
+	./$(BIN)
+	@for x in * ; do \
+		if [ -r "ideal-$$x" ] ; then \
+			if diff -u -I '\$Date' \
+				-I '\$Revision' \
+				 "ideal-$$x" "$$x" ; then \
+				echo "Test '$$x' passed"; \
+			else \
+				echo "Test output '$$x' does not match ideal"; \
+				exit 1; \
+			fi; \
+		fi; \
+	done
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/config.xcodeproj/project.pbxproj ./tools/test/config/config.xcodeproj/project.pbxproj
--- ../Tekkotsu_3.0/tools/test/config/config.xcodeproj/project.pbxproj	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/config.xcodeproj/project.pbxproj	2007-01-30 17:56:26.000000000 -0500
@@ -0,0 +1,285 @@
+// !$*UTF8*$!
+{
+	archiveVersion = 1;
+	classes = {
+	};
+	objectVersion = 42;
+	objects = {
+
+/* Begin PBXBuildFile section */
+		69434C810AF70F1B00904297 /* plist.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69434C790AF70F1B00904297 /* plist.cc */; };
+		69434C830AF70F1B00904297 /* plistBase.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69434C7B0AF70F1B00904297 /* plistBase.cc */; };
+		69434C850AF70F1B00904297 /* plistCollections.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69434C7D0AF70F1B00904297 /* plistCollections.cc */; };
+		69434C870AF70F1B00904297 /* plistPrimitives.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69434C7F0AF70F1B00904297 /* plistPrimitives.cc */; };
+		69434C9D0AF7172800904297 /* XMLLoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69434C9B0AF7172800904297 /* XMLLoadSave.cc */; };
+		69434CA10AF7173500904297 /* LoadSave.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69434C9F0AF7173500904297 /* LoadSave.cc */; };
+		69A243DD0AFCFC62009A21D3 /* string_util.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69A243DB0AFCFC62009A21D3 /* string_util.cc */; };
+		69A248060B00612A009A21D3 /* tekkotsu.xml in CopyFiles */ = {isa = PBXBuildFile; fileRef = 69A247FF0B006109009A21D3 /* tekkotsu.xml */; };
+		69B98A000AFA421B00551955 /* libxml2.dylib in Frameworks */ = {isa = PBXBuildFile; fileRef = 69B989FF0AFA421B00551955 /* libxml2.dylib */; };
+		69B98A2C0AFA447700551955 /* tekkotsu.cfg in CopyFiles */ = {isa = PBXBuildFile; fileRef = 69434CF90AF7B6AD00904297 /* tekkotsu.cfg */; };
+		69CFCBB50B0557E1003F9A85 /* Config.cc in Sources */ = {isa = PBXBuildFile; fileRef = 69CFCBB30B0557E1003F9A85 /* Config.cc */; };
+		69CFCBB60B0557E1003F9A85 /* Config.h in CopyFiles */ = {isa = PBXBuildFile; fileRef = 69CFCBB40B0557E1003F9A85 /* Config.h */; };
+		69CFD15C0B058C65003F9A85 /* plistCollections.h in CopyFiles */ = {isa = PBXBuildFile; fileRef = 69CFD15B0B058C65003F9A85 /* plistCollections.h */; };
+		8DD76F650486A84900D96B5E /* main.cc in Sources */ = {isa = PBXBuildFile; fileRef = 08FB7796FE84155DC02AAC07 /* main.cc */; settings = {ATTRIBUTES = (); }; };
+/* End PBXBuildFile section */
+
+/* Begin PBXCopyFilesBuildPhase section */
+		8DD76F690486A84900D96B5E /* CopyFiles */ = {
+			isa = PBXCopyFilesBuildPhase;
+			buildActionMask = 12;
+			dstPath = "";
+			dstSubfolderSpec = 16;
+			files = (
+				69B98A2C0AFA447700551955 /* tekkotsu.cfg in CopyFiles */,
+				69A248060B00612A009A21D3 /* tekkotsu.xml in CopyFiles */,
+				69CFCBB60B0557E1003F9A85 /* Config.h in CopyFiles */,
+				69CFD15C0B058C65003F9A85 /* plistCollections.h in CopyFiles */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+/* End PBXCopyFilesBuildPhase section */
+
+/* Begin PBXFileReference section */
+		08FB7796FE84155DC02AAC07 /* main.cc */ = {isa = PBXFileReference; fileEncoding = 4; lastKnownFileType = sourcecode.cpp.cpp; path = main.cc; sourceTree = "<group>"; };
+		6918B66E0B6F2E11006B28E3 /* Makefile */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.make; path = Makefile; sourceTree = "<group>"; };
+		69434C790AF70F1B00904297 /* plist.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = plist.cc; sourceTree = "<group>"; };
+		69434C7A0AF70F1B00904297 /* plist.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = plist.h; sourceTree = "<group>"; };
+		69434C7B0AF70F1B00904297 /* plistBase.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = plistBase.cc; sourceTree = "<group>"; };
+		69434C7C0AF70F1B00904297 /* plistBase.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = plistBase.h; sourceTree = "<group>"; };
+		69434C7D0AF70F1B00904297 /* plistCollections.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = plistCollections.cc; sourceTree = "<group>"; };
+		69434C7F0AF70F1B00904297 /* plistPrimitives.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = plistPrimitives.cc; sourceTree = "<group>"; };
+		69434C800AF70F1B00904297 /* plistPrimitives.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = plistPrimitives.h; sourceTree = "<group>"; };
+		69434C9B0AF7172800904297 /* XMLLoadSave.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = XMLLoadSave.cc; sourceTree = "<group>"; };
+		69434C9C0AF7172800904297 /* XMLLoadSave.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = XMLLoadSave.h; sourceTree = "<group>"; };
+		69434C9F0AF7173500904297 /* LoadSave.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = LoadSave.cc; sourceTree = "<group>"; };
+		69434CA00AF7173500904297 /* LoadSave.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = LoadSave.h; sourceTree = "<group>"; };
+		69434CA40AF71D3600904297 /* attributes.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = attributes.h; sourceTree = "<group>"; };
+		69434CF90AF7B6AD00904297 /* tekkotsu.cfg */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = text; path = tekkotsu.cfg; sourceTree = "<group>"; };
+		69A243DB0AFCFC62009A21D3 /* string_util.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = string_util.cc; sourceTree = "<group>"; };
+		69A243DC0AFCFC62009A21D3 /* string_util.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = string_util.h; sourceTree = "<group>"; };
+		69A244F80AFD2A7C009A21D3 /* Cloneable.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Cloneable.h; sourceTree = "<group>"; };
+		69A247FF0B006109009A21D3 /* tekkotsu.xml */ = {isa = PBXFileReference; explicitFileType = text.plist; fileEncoding = 30; path = tekkotsu.xml; sourceTree = "<group>"; };
+		69B989FF0AFA421B00551955 /* libxml2.dylib */ = {isa = PBXFileReference; lastKnownFileType = "compiled.mach-o.dylib"; name = libxml2.dylib; path = /usr/lib/libxml2.dylib; sourceTree = "<absolute>"; };
+		69CFCBB30B0557E1003F9A85 /* Config.cc */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.cpp.cpp; path = Config.cc; sourceTree = "<group>"; };
+		69CFCBB40B0557E1003F9A85 /* Config.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = Config.h; sourceTree = "<group>"; };
+		69CFD15B0B058C65003F9A85 /* plistCollections.h */ = {isa = PBXFileReference; fileEncoding = 30; lastKnownFileType = sourcecode.c.h; path = plistCollections.h; sourceTree = "<group>"; };
+		8DD76F6C0486A84900D96B5E /* config */ = {isa = PBXFileReference; explicitFileType = "compiled.mach-o.executable"; includeInIndex = 0; path = config; sourceTree = BUILT_PRODUCTS_DIR; };
+/* End PBXFileReference section */
+
+/* Begin PBXFrameworksBuildPhase section */
+		8DD76F660486A84900D96B5E /* Frameworks */ = {
+			isa = PBXFrameworksBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				69B98A000AFA421B00551955 /* libxml2.dylib in Frameworks */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+/* End PBXFrameworksBuildPhase section */
+
+/* Begin PBXGroup section */
+		08FB7794FE84155DC02AAC07 /* config */ = {
+			isa = PBXGroup;
+			children = (
+				69434CF90AF7B6AD00904297 /* tekkotsu.cfg */,
+				69A247FF0B006109009A21D3 /* tekkotsu.xml */,
+				6918B66E0B6F2E11006B28E3 /* Makefile */,
+				69434C780AF70EEB00904297 /* Shared */,
+				08FB7795FE84155DC02AAC07 /* Source */,
+				69B989FB0AFA41DA00551955 /* Libraries */,
+				1AB674ADFE9D54B511CA2CBB /* Products */,
+			);
+			name = config;
+			sourceTree = "<group>";
+		};
+		08FB7795FE84155DC02AAC07 /* Source */ = {
+			isa = PBXGroup;
+			children = (
+				08FB7796FE84155DC02AAC07 /* main.cc */,
+			);
+			name = Source;
+			sourceTree = "<group>";
+		};
+		1AB674ADFE9D54B511CA2CBB /* Products */ = {
+			isa = PBXGroup;
+			children = (
+				8DD76F6C0486A84900D96B5E /* config */,
+			);
+			name = Products;
+			sourceTree = "<group>";
+		};
+		69434C780AF70EEB00904297 /* Shared */ = {
+			isa = PBXGroup;
+			children = (
+				69CFCBB30B0557E1003F9A85 /* Config.cc */,
+				69CFCBB40B0557E1003F9A85 /* Config.h */,
+				69434CA40AF71D3600904297 /* attributes.h */,
+				69A244F80AFD2A7C009A21D3 /* Cloneable.h */,
+				69434C9F0AF7173500904297 /* LoadSave.cc */,
+				69434CA00AF7173500904297 /* LoadSave.h */,
+				69434C790AF70F1B00904297 /* plist.cc */,
+				69434C7A0AF70F1B00904297 /* plist.h */,
+				69434C7B0AF70F1B00904297 /* plistBase.cc */,
+				69434C7C0AF70F1B00904297 /* plistBase.h */,
+				69434C7D0AF70F1B00904297 /* plistCollections.cc */,
+				69CFD15B0B058C65003F9A85 /* plistCollections.h */,
+				69434C7F0AF70F1B00904297 /* plistPrimitives.cc */,
+				69434C800AF70F1B00904297 /* plistPrimitives.h */,
+				69434C9B0AF7172800904297 /* XMLLoadSave.cc */,
+				69434C9C0AF7172800904297 /* XMLLoadSave.h */,
+				69A243DB0AFCFC62009A21D3 /* string_util.cc */,
+				69A243DC0AFCFC62009A21D3 /* string_util.h */,
+			);
+			name = Shared;
+			path = ../../../Shared;
+			sourceTree = SOURCE_ROOT;
+		};
+		69B989FB0AFA41DA00551955 /* Libraries */ = {
+			isa = PBXGroup;
+			children = (
+				69B989FF0AFA421B00551955 /* libxml2.dylib */,
+			);
+			name = Libraries;
+			sourceTree = "<group>";
+		};
+/* End PBXGroup section */
+
+/* Begin PBXNativeTarget section */
+		8DD76F620486A84900D96B5E /* config */ = {
+			isa = PBXNativeTarget;
+			buildConfigurationList = 1DEB923108733DC60010E9CD /* Build configuration list for PBXNativeTarget "config" */;
+			buildPhases = (
+				8DD76F640486A84900D96B5E /* Sources */,
+				8DD76F660486A84900D96B5E /* Frameworks */,
+				8DD76F690486A84900D96B5E /* CopyFiles */,
+			);
+			buildRules = (
+			);
+			dependencies = (
+			);
+			name = config;
+			productInstallPath = "$(HOME)/bin";
+			productName = config;
+			productReference = 8DD76F6C0486A84900D96B5E /* config */;
+			productType = "com.apple.product-type.tool";
+		};
+/* End PBXNativeTarget section */
+
+/* Begin PBXProject section */
+		08FB7793FE84155DC02AAC07 /* Project object */ = {
+			isa = PBXProject;
+			buildConfigurationList = 1DEB923508733DC60010E9CD /* Build configuration list for PBXProject "config" */;
+			hasScannedForEncodings = 1;
+			mainGroup = 08FB7794FE84155DC02AAC07 /* config */;
+			projectDirPath = "";
+			targets = (
+				8DD76F620486A84900D96B5E /* config */,
+			);
+		};
+/* End PBXProject section */
+
+/* Begin PBXSourcesBuildPhase section */
+		8DD76F640486A84900D96B5E /* Sources */ = {
+			isa = PBXSourcesBuildPhase;
+			buildActionMask = 2147483647;
+			files = (
+				8DD76F650486A84900D96B5E /* main.cc in Sources */,
+				69434C810AF70F1B00904297 /* plist.cc in Sources */,
+				69434C830AF70F1B00904297 /* plistBase.cc in Sources */,
+				69434C850AF70F1B00904297 /* plistCollections.cc in Sources */,
+				69434C870AF70F1B00904297 /* plistPrimitives.cc in Sources */,
+				69434C9D0AF7172800904297 /* XMLLoadSave.cc in Sources */,
+				69434CA10AF7173500904297 /* LoadSave.cc in Sources */,
+				69A243DD0AFCFC62009A21D3 /* string_util.cc in Sources */,
+				69CFCBB50B0557E1003F9A85 /* Config.cc in Sources */,
+			);
+			runOnlyForDeploymentPostprocessing = 0;
+		};
+/* End PBXSourcesBuildPhase section */
+
+/* Begin XCBuildConfiguration section */
+		1DEB923208733DC60010E9CD /* Debug */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				COPY_PHASE_STRIP = NO;
+				GCC_DYNAMIC_NO_PIC = NO;
+				GCC_ENABLE_FIX_AND_CONTINUE = YES;
+				GCC_MODEL_TUNING = G5;
+				GCC_OPTIMIZATION_LEVEL = 0;
+				INSTALL_PATH = "$(HOME)/bin";
+				PRODUCT_NAME = config;
+				ZERO_LINK = YES;
+			};
+			name = Debug;
+		};
+		1DEB923308733DC60010E9CD /* Release */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				ARCHS = (
+					ppc,
+					i386,
+				);
+				GCC_GENERATE_DEBUGGING_SYMBOLS = NO;
+				GCC_MODEL_TUNING = G5;
+				INSTALL_PATH = "$(HOME)/bin";
+				PRODUCT_NAME = config;
+			};
+			name = Release;
+		};
+		1DEB923608733DC60010E9CD /* Debug */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				GCC_PREPROCESSOR_DEFINITIONS = TGT_ERS7;
+				GCC_WARN_ABOUT_RETURN_TYPE = YES;
+				GCC_WARN_UNUSED_VARIABLE = YES;
+				HEADER_SEARCH_PATHS = (
+					/usr/include/libxml2,
+					/usr/local/include,
+					$TEKKOTSU_ROOT,
+				);
+				PREBINDING = NO;
+				SDKROOT = /Developer/SDKs/MacOSX10.4u.sdk;
+			};
+			name = Debug;
+		};
+		1DEB923708733DC60010E9CD /* Release */ = {
+			isa = XCBuildConfiguration;
+			buildSettings = {
+				GCC_PREPROCESSOR_DEFINITIONS = TGT_ERS7;
+				GCC_WARN_ABOUT_RETURN_TYPE = YES;
+				GCC_WARN_UNUSED_VARIABLE = YES;
+				HEADER_SEARCH_PATHS = (
+					/usr/include/libxml2,
+					/usr/local/include,
+					$TEKKOTSU_ROOT,
+				);
+				PREBINDING = NO;
+				SDKROOT = /Developer/SDKs/MacOSX10.4u.sdk;
+			};
+			name = Release;
+		};
+/* End XCBuildConfiguration section */
+
+/* Begin XCConfigurationList section */
+		1DEB923108733DC60010E9CD /* Build configuration list for PBXNativeTarget "config" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				1DEB923208733DC60010E9CD /* Debug */,
+				1DEB923308733DC60010E9CD /* Release */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = Release;
+		};
+		1DEB923508733DC60010E9CD /* Build configuration list for PBXProject "config" */ = {
+			isa = XCConfigurationList;
+			buildConfigurations = (
+				1DEB923608733DC60010E9CD /* Debug */,
+				1DEB923708733DC60010E9CD /* Release */,
+			);
+			defaultConfigurationIsVisible = 0;
+			defaultConfigurationName = Release;
+		};
+/* End XCConfigurationList section */
+	};
+	rootObject = 08FB7793FE84155DC02AAC07 /* Project object */;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-col.plist ./tools/test/config/ideal-col.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-col.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-col.plist	2007-11-15 12:26:53.000000000 -0500
@@ -0,0 +1,34 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><array>
+<!--0: Array of anything (but only adding strings)-->
+<array>
+	<string>4</string>
+	<string>1</string>
+	<string>2</string>
+	<string>3</string>
+	<string>1</string>
+	<string>2</string>
+	<string>3</string>
+</array>
+<!--1: Array of integers-->
+<array>
+	<integer>4</integer>
+	<integer>1</integer>
+	<integer>2</integer>
+	<integer>3</integer>
+	<integer>1</integer>
+	<integer>2</integer>
+	<integer>3</integer>
+</array>
+<!--2: Array of strings-->
+<array>
+	<string>4</string>
+	<string>1</string>
+	<string>2</string>
+	<string>3</string>
+	<string>1</string>
+	<string>2</string>
+	<string>3</string>
+</array>
+</array></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-tekkotsu.plist ./tools/test/config/ideal-tekkotsu.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-tekkotsu.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-tekkotsu.plist	2007-11-21 22:47:06.000000000 -0500
@@ -0,0 +1,446 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict><!--
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+#####################   $Revision: 1.2 $   ######################
+################   $Date: 2007/11/22 03:47:06 $   ################
+##################################################################
+
+This is an XML-based format using the Property List (plist) layout.
+
+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 in 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.
+
+You can change these settings at run time from the Controller
+by entering the command:
+   !set section_name.variable=value
+or by using the configuration editor found in the "File Access"
+menu.  Paths are assumed to be relative to the 'project/ms/'
+directory.  For example, the primary configuration file would be
+referenced as 'config/tekkotsu.xml'
+
+See also the 'simulator.xml' file, which provides you the ability
+to override settings when running in the simulator
+-->
+
+<!--======== behaviors ========-->
+<key>behaviors</key> <dict>
+	<!--flash_bytes: how many bytes of the address to flash
+	You probably already know the first 3 bytes for your network,
+	so you might only want the last byte for brevity.
+	(valid values are 1 through 4) -->
+	<key>flash_bytes</key> <integer>4</integer>
+	
+	<!--flash_on_start: whether or not to automatically trigger on boot
+	Will use a priority of kEmergencyPriority+1 in order to override
+	the emergency stop's status animation -->
+	<key>flash_on_start</key> <false/>
+</dict>
+
+<!--======== controller ========-->
+<key>controller</key> <dict>
+	<!--cancel_snd: sound file to use for "cancel" action-->
+	<key>cancel_snd</key> <string>whoop.wav</string>
+	
+	<!--error_snd: sound file to use to signal errors-->
+	<key>error_snd</key> <string>fart.wav</string>
+	
+	<!--gui_port: port to listen for the GUI to connect to aibo on-->
+	<key>gui_port</key> <integer>10020</integer>
+	
+	<!--next_snd: sound file to use for "next" action-->
+	<key>next_snd</key> <string>toc.wav</string>
+	
+	<!--prev_snd: sound file to use for "prev" action-->
+	<key>prev_snd</key> <string>tick.wav</string>
+	
+	<!--read_snd: sound file to use for "read from std-in" action-->
+	<key>read_snd</key> <string>ping.wav</string>
+	
+	<!--select_snd: sound file to use for "select" action-->
+	<key>select_snd</key> <string>whiip.wav</string>
+</dict>
+
+<!--======== main ========-->
+<key>main</key> <dict>
+	<!--aibo3d_port: port for send/receive of joint positions from Aibo 3D GUI-->
+	<key>aibo3d_port</key> <integer>10051</integer>
+	
+	<!--consoleMode: determines how input on console_port is interpreted
+	Value is one of: { controller | textmsg | auto } 
+	  'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
+	  'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
+	  'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise -->
+	<key>consoleMode</key> <string>controller</string>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10001</integer>
+	
+	<!--estopControl_port: port for receiving walk commands-->
+	<key>estopControl_port</key> <integer>10053</integer>
+	
+	<!--headControl_port: port for receiving head commands-->
+	<key>headControl_port</key> <integer>10052</integer>
+	
+	<!--seed_rng: if true, will call srand with timestamp data, mangled by current sensor data-->
+	<key>seed_rng</key> <true/>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10002</integer>
+	
+	<!--stewart_port: port for running a stewart platform style of control-->
+	<key>stewart_port</key> <integer>10055</integer>
+	
+	<!--use_VT100: if true, enables VT100 console codes (currently only in Controller menus - 1.3)-->
+	<key>use_VT100</key> <true/>
+	
+	<!--walkControl_port: port for receiving walk commands-->
+	<key>walkControl_port</key> <integer>10050</integer>
+	
+	<!--wmmonitor_port: port for monitoring Watchable Memory-->
+	<key>wmmonitor_port</key> <integer>10061</integer>
+	
+	<!--worldState_interval: time (in milliseconds) to wait between sending WorldState updates over wireless-->
+	<key>worldState_interval</key> <integer>0</integer>
+	
+	<!--wsjoints_port: port to send joint positions on-->
+	<key>wsjoints_port</key> <integer>10031</integer>
+	
+	<!--wspids_port: port to send pid info on-->
+	<key>wspids_port</key> <integer>10032</integer>
+</dict>
+
+<!--======== motion ========-->
+<key>motion</key> <dict>
+	<!--======== calibration_offset ========-->
+	<!--These values indicate 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.-->
+	<key>calibration_offset</key> <dict>
+		<key>LFr:rotor</key> <real>0</real>
+		<key>LFr:elvtr</key> <real>0</real>
+		<key>LFr:knee</key> <real>0</real>
+		<key>RFr:rotor</key> <real>0</real>
+		<key>RFr:elvtr</key> <real>0</real>
+		<key>RFr:knee</key> <real>0</real>
+		<key>LBk:rotor</key> <real>0</real>
+		<key>LBk:elvtr</key> <real>0</real>
+		<key>LBk:knee</key> <real>0</real>
+		<key>RBk:rotor</key> <real>0</real>
+		<key>RBk:elvtr</key> <real>0</real>
+		<key>RBk:knee</key> <real>0</real>
+		<key>NECK:tilt</key> <real>0</real>
+		<key>NECK:pan</key> <real>0</real>
+		<key>NECK:nod</key> <real>0</real>
+		<key>TAIL:tilt</key> <real>0</real>
+		<key>TAIL:pan</key> <real>0</real>
+		<key>MOUTH</key> <real>0</real>
+	</dict>
+	
+	<!--======== calibration_scale ========-->
+	<!--Multiplier from desired position to command for each PID joint, applied after calibration_offset.-->
+	<key>calibration_scale</key> <dict>
+		<key>LFr:rotor</key> <real>1</real>
+		<key>LFr:elvtr</key> <real>1</real>
+		<key>LFr:knee</key> <real>1</real>
+		<key>RFr:rotor</key> <real>1</real>
+		<key>RFr:elvtr</key> <real>1</real>
+		<key>RFr:knee</key> <real>1</real>
+		<key>LBk:rotor</key> <real>1</real>
+		<key>LBk:elvtr</key> <real>1</real>
+		<key>LBk:knee</key> <real>1</real>
+		<key>RBk:rotor</key> <real>1</real>
+		<key>RBk:elvtr</key> <real>1</real>
+		<key>RBk:knee</key> <real>1</real>
+		<key>NECK:tilt</key> <real>1</real>
+		<key>NECK:pan</key> <real>1</real>
+		<key>NECK:nod</key> <real>1</real>
+		<key>TAIL:tilt</key> <real>1</real>
+		<key>TAIL:pan</key> <real>1</real>
+		<key>MOUTH</key> <real>1</real>
+	</dict>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10003</integer>
+	
+	<!--estop_off_snd: sound file to use when e-stop turned off-->
+	<key>estop_off_snd</key> <string>yap.wav</string>
+	
+	<!--estop_on_snd: sound file to use when e-stop turned on-->
+	<key>estop_on_snd</key> <string>skid.wav</string>
+	
+	<!--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-->
+	<key>inf_walk_accel</key> <false/>
+	
+	<!--======== kinematic_chains ========-->
+	<!--list of chain names to load from the file specified by 'kinematics'-->
+	<key>kinematic_chains</key> <array>
+		<string>Body</string>
+		<string>Mouth</string>
+		<string>NearIR</string>
+		<string>FarIR</string>
+		<string>ChestIR</string>
+		<string>LFr</string>
+		<string>RFr</string>
+		<string>LBk</string>
+		<string>RBk</string>
+		<string>Camera</string>
+	</array>
+	
+	<!--kinematics: the ROBOOP format kinematics description file to load-->
+	<key>kinematics</key> <string>/config/ers7.kin</string>
+	
+	<!--max_head_pan_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_pan_speed</key> <real>5.7814</real>
+	
+	<!--max_head_roll_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_roll_speed</key> <real>5.7814</real>
+	
+	<!--max_head_tilt_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_tilt_speed</key> <real>3.18523</real>
+	
+	<!--root: path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
+	Any motion related paths which are not absolute (i.e. do not start with '/')
+	will be assumed to be relative to this directory -->
+	<key>root</key> <string>data/motion</string>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10004</integer>
+	
+	<!--the walk parameter file to load by default for new WalkMC's-->
+	<key>walk</key> <string>walk.prm</string>
+</dict>
+
+<!--======== sound ========-->
+<key>sound</key> <dict>
+	<!--pitchConfidenceThreshold: confidence threshold required to generate a pitch event [0-1]-->
+	<key>pitchConfidenceThreshold</key> <real>0.6</real>
+	
+	<!--======== preload ========-->
+	<!--list of sounds to preload at boot-->
+	<key>preload</key> <array>
+		<string>skid.wav</string>
+		<string>yap.wav</string>
+	</array>
+	
+	<!--root: path to sound clips-->
+	<key>root</key> <string>data/sound</string>
+	
+	<!--sample_bits: sample bit depth, either 8 or 16-->
+	<key>sample_bits</key> <integer>16</integer>
+	
+	<!--sample_rate: sample rate to send to system, currently only 8000 or 16000 supported-->
+	<key>sample_rate</key> <integer>16000</integer>
+	
+	<!--======== streaming ========-->
+	<key>streaming</key> <dict>
+		<!--mic_port: port for streaming microphone samples-->
+		<key>mic_port</key> <integer>10070</integer>
+		
+		<!--mic_sample_bits: sample bit depth from the microphone (either 8 or 16)-->
+		<key>mic_sample_bits</key> <integer>16</integer>
+		
+		<!--mic_sample_rate: sample rate from the microphone-->
+		<key>mic_sample_rate</key> <integer>16000</integer>
+		
+		<!--mic_stereo: whether to stream stereo or mono from the microphone-->
+		<key>mic_stereo</key> <true/>
+		
+		<!--speaker_frame_length: length of frame sent to the speaker (ms)-->
+		<key>speaker_frame_length</key> <integer>64</integer>
+		
+		<!--speaker_max_delay: maximum delay (ms) during playback-->
+		<key>speaker_max_delay</key> <integer>1000</integer>
+		
+		<!--speaker_port: port for streaming speaker samples-->
+		<key>speaker_port</key> <integer>10071</integer>
+	</dict>
+	
+	<!--volume in decibels - the value is interpreted as a signed short, where
+	0x8000 is mute, 0xFFFF is full volume (low=0xE700, mid=0xEE00, high=0xF600)
+	If you directly set the decibel level, be warned sony recommends against going above 0xF600
+	However, I believe the commercial software on the ERS-7 runs at 0xFF00.
+	Going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
+	Value is one of: { mute | low | mid | high | <integer_value> } -->
+	<key>volume</key> <string>high</string>
+</dict>
+
+<!--======== vision ========-->
+<key>vision</key> <dict>
+	<!--======== calibration ========-->
+	<!--Lens distortion correction parameters
+	Computated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet-->
+	<key>calibration</key> <dict>
+		<!--calibration_res_x: x resolution of images used during calibration-->
+		<key>calibration_res_x</key> <integer>208</integer>
+		
+		<!--calibration_res_y: y resolution of images used during calibration-->
+		<key>calibration_res_y</key> <integer>160</integer>
+		
+		<!--focal_len_x: focal length of camera, in pixels, K11-->
+		<key>focal_len_x</key> <real>198.807</real>
+		
+		<!--focal_len_y: focal length of camera, in pixels, K22-->
+		<key>focal_len_y</key> <real>200.333</real>
+		
+		<!--kc1_r2: r-squared radial distortion-->
+		<key>kc1_r2</key> <real>-0.147005</real>
+		
+		<!--kc2_r4: r to the 4 radial distortion-->
+		<key>kc2_r4</key> <real>0.38485</real>
+		
+		<!--kc3_tan1: first tangential correction term-->
+		<key>kc3_tan1</key> <real>-0.00347777</real>
+		
+		<!--kc4_tan2: second tangential correctiont term-->
+		<key>kc4_tan2</key> <real>0.00012873</real>
+		
+		<!--kc5_r6: r to the 6 radial distortion-->
+		<key>kc5_r6</key> <real>0</real>
+		
+		<!--principle_point_x: center of optical projection, K13-->
+		<key>principle_point_x</key> <real>102.689</real>
+		
+		<!--principle_point_y: center of optical projection, K23-->
+		<key>principle_point_y</key> <real>85.0399</real>
+		
+		<!--CCD skew, K12 = skew*focal_len_x-->
+		<key>skew</key> <real>0</real>
+	</dict>
+	
+	<!--The colors definition (.col) file gives names and a "typical" color for display.
+	The indexes numbers it contains correspond to indexes in the .tm file
+	This file is common to all .tm files; when doing new color segmentations,
+	make sure you define colors in the same order as listed here! -->
+	<key>colors</key> <string>config/default.col</string>
+	
+	<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+	Value is one of: { low | mid | high } -->
+	<key>gain</key> <string>mid</string>
+	
+	<!--jpeg_dct_method: pick between dct methods for jpeg compression
+	Value is one of: { islow | ifast | float } -->
+	<key>jpeg_dct_method</key> <string>ifast</string>
+	
+	<!--======== rawcam ========-->
+	<key>rawcam</key> <dict>
+		<!--channel: if encoding is single channel, this indicates the channel to send-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--compress_quality: 0-100, compression quality (currently only used by jpeg)-->
+		<key>compress_quality</key> <integer>85</integer>
+		
+		<!--compression: the type of compression to apply the image
+		Value is one of: { none | jpeg } -->
+		<key>compression</key> <string>jpeg</string>
+		
+		<!--encoding: holds whether to send color or single channel
+		Value is one of: { color | grayscale } -->
+		<key>encoding</key> <string>color</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10011</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+		
+		<!--uv_skip: resolution level to transmit uv channel at when using 'color' encoding mode-->
+		<key>uv_skip</key> <integer>3</integer>
+		
+		<!--y_skip: resolution level to transmit y channel
+		Also used as the resolution level when in single-channel encoding mode -->
+		<key>y_skip</key> <integer>2</integer>
+	</dict>
+	
+	<!--region_calc_total: When true, this will fill in the CMVision::color_class_state::total_area
+	field for each color following region labeling.  If false, the total_area
+	will stay 0 (or whatever the last value was), but you save a little CPU. -->
+	<key>region_calc_total</key> <true/>
+	
+	<!--======== regioncam ========-->
+	<key>regioncam</key> <dict>
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10013</integer>
+		
+		<!--skip: resolution level to extract regions from-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--the resolution that object recognition system will run at.
+	This counts down from the maximum resolution layer, so higher numbers mean lower resolution. -->
+	<key>resolution</key> <integer>1</integer>
+	
+	<!--restore_image: Apparently someone at Sony thought it would be a good idea to replace some
+	pixels in each camera image with information like the frame number and CDT count.
+	If non-zero, will replace those pixels with the actual image pixel value in RawCamGenerator -->
+	<key>restore_image</key> <true/>
+	
+	<!--======== segcam ========-->
+	<key>segcam</key> <dict>
+		<!--channel of RLEGenerator to send (i.e. which threshold map to use-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--what compression to use on the segmented imageValue is one of: { none | rle } -->
+		<key>compression</key> <string>rle</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10012</integer>
+		
+		<!--skip: resolution level to transmit segmented images at-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+	</dict>
+	
+	<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+	Value is one of: { slow | mid | fast } -->
+	<key>shutter_speed</key> <string>slow</string>
+	
+	<!--======== thresh ========-->
+	<!--Threshold (.tm) files define the mapping from full color to indexed color.
+	You can uncomment more than one of these - they will be loaded into separate
+	channels of the segmenter.  The only cost of loading multiple threshold files is
+	memory - the CPU cost of performing segmentation is only incurred if/when
+	the channel is actually accessed for the first time for a given frame. -->
+	<key>thresh</key> <array>
+		<string>config/7general.tm</string>
+	</array>
+	
+	<!--white_balance: white balance shifts color spectrum in the image
+	Value is one of: { indoor | outdoor | fluorescent } -->
+	<key>white_balance</key> <string>indoor</string>
+</dict>
+
+<!--======== wireless ========-->
+<key>wireless</key> <dict>
+	<!--id number (in case you have more than one AIBO)-->
+	<key>id</key> <integer>1</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-tekkotsu2.plist ./tools/test/config/ideal-tekkotsu2.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-tekkotsu2.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-tekkotsu2.plist	2007-11-21 22:47:07.000000000 -0500
@@ -0,0 +1,446 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict><!--
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+#####################   $Revision: 1.2 $   ######################
+################   $Date: 2007/11/22 03:47:07 $   ################
+##################################################################
+
+This is an XML-based format using the Property List (plist) layout.
+
+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 in 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.
+
+You can change these settings at run time from the Controller
+by entering the command:
+   !set section_name.variable=value
+or by using the configuration editor found in the "File Access"
+menu.  Paths are assumed to be relative to the 'project/ms/'
+directory.  For example, the primary configuration file would be
+referenced as 'config/tekkotsu.xml'
+
+See also the 'simulator.xml' file, which provides you the ability
+to override settings when running in the simulator
+-->
+
+<!--======== behaviors ========-->
+<key>behaviors</key> <dict>
+	<!--flash_bytes: how many bytes of the address to flash
+	You probably already know the first 3 bytes for your network,
+	so you might only want the last byte for brevity.
+	(valid values are 1 through 4) -->
+	<key>flash_bytes</key> <integer>4</integer>
+	
+	<!--flash_on_start: whether or not to automatically trigger on boot
+	Will use a priority of kEmergencyPriority+1 in order to override
+	the emergency stop's status animation -->
+	<key>flash_on_start</key> <false/>
+</dict>
+
+<!--======== controller ========-->
+<key>controller</key> <dict>
+	<!--cancel_snd: sound file to use for "cancel" action-->
+	<key>cancel_snd</key> <string>whoop.wav</string>
+	
+	<!--error_snd: sound file to use to signal errors-->
+	<key>error_snd</key> <string>fart.wav</string>
+	
+	<!--gui_port: port to listen for the GUI to connect to aibo on-->
+	<key>gui_port</key> <integer>10020</integer>
+	
+	<!--next_snd: sound file to use for "next" action-->
+	<key>next_snd</key> <string>toc.wav</string>
+	
+	<!--prev_snd: sound file to use for "prev" action-->
+	<key>prev_snd</key> <string>tick.wav</string>
+	
+	<!--read_snd: sound file to use for "read from std-in" action-->
+	<key>read_snd</key> <string>ping.wav</string>
+	
+	<!--select_snd: sound file to use for "select" action-->
+	<key>select_snd</key> <string>whiip.wav</string>
+</dict>
+
+<!--======== main ========-->
+<key>main</key> <dict>
+	<!--aibo3d_port: port for send/receive of joint positions from Aibo 3D GUI-->
+	<key>aibo3d_port</key> <integer>10051</integer>
+	
+	<!--consoleMode: determines how input on console_port is interpreted
+	Value is one of: { controller | textmsg | auto } 
+	  'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
+	  'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
+	  'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise -->
+	<key>consoleMode</key> <string>controller</string>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10001</integer>
+	
+	<!--estopControl_port: port for receiving walk commands-->
+	<key>estopControl_port</key> <integer>10053</integer>
+	
+	<!--headControl_port: port for receiving head commands-->
+	<key>headControl_port</key> <integer>10052</integer>
+	
+	<!--seed_rng: if true, will call srand with timestamp data, mangled by current sensor data-->
+	<key>seed_rng</key> <true/>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10002</integer>
+	
+	<!--stewart_port: port for running a stewart platform style of control-->
+	<key>stewart_port</key> <integer>10055</integer>
+	
+	<!--use_VT100: if true, enables VT100 console codes (currently only in Controller menus - 1.3)-->
+	<key>use_VT100</key> <true/>
+	
+	<!--walkControl_port: port for receiving walk commands-->
+	<key>walkControl_port</key> <integer>10050</integer>
+	
+	<!--wmmonitor_port: port for monitoring Watchable Memory-->
+	<key>wmmonitor_port</key> <integer>10061</integer>
+	
+	<!--worldState_interval: time (in milliseconds) to wait between sending WorldState updates over wireless-->
+	<key>worldState_interval</key> <integer>0</integer>
+	
+	<!--wsjoints_port: port to send joint positions on-->
+	<key>wsjoints_port</key> <integer>10031</integer>
+	
+	<!--wspids_port: port to send pid info on-->
+	<key>wspids_port</key> <integer>10032</integer>
+</dict>
+
+<!--======== motion ========-->
+<key>motion</key> <dict>
+	<!--======== calibration_offset ========-->
+	<!--These values indicate 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.-->
+	<key>calibration_offset</key> <dict>
+		<key>LFr:rotor</key> <real>0</real>
+		<key>LFr:elvtr</key> <real>0</real>
+		<key>LFr:knee</key> <real>0</real>
+		<key>RFr:rotor</key> <real>0</real>
+		<key>RFr:elvtr</key> <real>0</real>
+		<key>RFr:knee</key> <real>0</real>
+		<key>LBk:rotor</key> <real>0</real>
+		<key>LBk:elvtr</key> <real>0</real>
+		<key>LBk:knee</key> <real>0</real>
+		<key>RBk:rotor</key> <real>0</real>
+		<key>RBk:elvtr</key> <real>0</real>
+		<key>RBk:knee</key> <real>0</real>
+		<key>NECK:tilt</key> <real>0</real>
+		<key>NECK:pan</key> <real>0</real>
+		<key>NECK:nod</key> <real>0</real>
+		<key>TAIL:tilt</key> <real>0</real>
+		<key>TAIL:pan</key> <real>0</real>
+		<key>MOUTH</key> <real>0</real>
+	</dict>
+	
+	<!--======== calibration_scale ========-->
+	<!--Multiplier from desired position to command for each PID joint, applied after calibration_offset.-->
+	<key>calibration_scale</key> <dict>
+		<key>LFr:rotor</key> <real>1</real>
+		<key>LFr:elvtr</key> <real>1</real>
+		<key>LFr:knee</key> <real>1</real>
+		<key>RFr:rotor</key> <real>1</real>
+		<key>RFr:elvtr</key> <real>1</real>
+		<key>RFr:knee</key> <real>1</real>
+		<key>LBk:rotor</key> <real>1</real>
+		<key>LBk:elvtr</key> <real>1</real>
+		<key>LBk:knee</key> <real>1</real>
+		<key>RBk:rotor</key> <real>1</real>
+		<key>RBk:elvtr</key> <real>1</real>
+		<key>RBk:knee</key> <real>1</real>
+		<key>NECK:tilt</key> <real>1</real>
+		<key>NECK:pan</key> <real>1</real>
+		<key>NECK:nod</key> <real>1</real>
+		<key>TAIL:tilt</key> <real>1</real>
+		<key>TAIL:pan</key> <real>1</real>
+		<key>MOUTH</key> <real>1</real>
+	</dict>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10003</integer>
+	
+	<!--estop_off_snd: sound file to use when e-stop turned off-->
+	<key>estop_off_snd</key> <string>yap.wav</string>
+	
+	<!--estop_on_snd: sound file to use when e-stop turned on-->
+	<key>estop_on_snd</key> <string>skid.wav</string>
+	
+	<!--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-->
+	<key>inf_walk_accel</key> <false/>
+	
+	<!--======== kinematic_chains ========-->
+	<!--list of chain names to load from the file specified by 'kinematics'-->
+	<key>kinematic_chains</key> <array>
+		<string>Body</string>
+		<string>Mouth</string>
+		<string>NearIR</string>
+		<string>FarIR</string>
+		<string>ChestIR</string>
+		<string>LFr</string>
+		<string>RFr</string>
+		<string>LBk</string>
+		<string>RBk</string>
+		<string>Camera</string>
+	</array>
+	
+	<!--kinematics: the ROBOOP format kinematics description file to load-->
+	<key>kinematics</key> <string>/config/ers7.kin</string>
+	
+	<!--max_head_pan_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_pan_speed</key> <real>5.7814</real>
+	
+	<!--max_head_roll_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_roll_speed</key> <real>5.7814</real>
+	
+	<!--max_head_tilt_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_tilt_speed</key> <real>3.18523</real>
+	
+	<!--root: path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
+	Any motion related paths which are not absolute (i.e. do not start with '/')
+	will be assumed to be relative to this directory -->
+	<key>root</key> <string>data/motion</string>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10004</integer>
+	
+	<!--the walk parameter file to load by default for new WalkMC's-->
+	<key>walk</key> <string>walk.prm</string>
+</dict>
+
+<!--======== sound ========-->
+<key>sound</key> <dict>
+	<!--pitchConfidenceThreshold: confidence threshold required to generate a pitch event [0-1]-->
+	<key>pitchConfidenceThreshold</key> <real>0.6</real>
+	
+	<!--======== preload ========-->
+	<!--list of sounds to preload at boot-->
+	<key>preload</key> <array>
+		<string>skid.wav</string>
+		<string>yap.wav</string>
+	</array>
+	
+	<!--root: path to sound clips-->
+	<key>root</key> <string>data/sound</string>
+	
+	<!--sample_bits: sample bit depth, either 8 or 16-->
+	<key>sample_bits</key> <integer>16</integer>
+	
+	<!--sample_rate: sample rate to send to system, currently only 8000 or 16000 supported-->
+	<key>sample_rate</key> <integer>16000</integer>
+	
+	<!--======== streaming ========-->
+	<key>streaming</key> <dict>
+		<!--mic_port: port for streaming microphone samples-->
+		<key>mic_port</key> <integer>10070</integer>
+		
+		<!--mic_sample_bits: sample bit depth from the microphone (either 8 or 16)-->
+		<key>mic_sample_bits</key> <integer>16</integer>
+		
+		<!--mic_sample_rate: sample rate from the microphone-->
+		<key>mic_sample_rate</key> <integer>16000</integer>
+		
+		<!--mic_stereo: whether to stream stereo or mono from the microphone-->
+		<key>mic_stereo</key> <true/>
+		
+		<!--speaker_frame_length: length of frame sent to the speaker (ms)-->
+		<key>speaker_frame_length</key> <integer>64</integer>
+		
+		<!--speaker_max_delay: maximum delay (ms) during playback-->
+		<key>speaker_max_delay</key> <integer>1000</integer>
+		
+		<!--speaker_port: port for streaming speaker samples-->
+		<key>speaker_port</key> <integer>10071</integer>
+	</dict>
+	
+	<!--volume in decibels - the value is interpreted as a signed short, where
+	0x8000 is mute, 0xFFFF is full volume (low=0xE700, mid=0xEE00, high=0xF600)
+	If you directly set the decibel level, be warned sony recommends against going above 0xF600
+	However, I believe the commercial software on the ERS-7 runs at 0xFF00.
+	Going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
+	Value is one of: { mute | low | mid | high | <integer_value> } -->
+	<key>volume</key> <string>high</string>
+</dict>
+
+<!--======== vision ========-->
+<key>vision</key> <dict>
+	<!--======== calibration ========-->
+	<!--Lens distortion correction parameters
+	Computated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet-->
+	<key>calibration</key> <dict>
+		<!--calibration_res_x: x resolution of images used during calibration-->
+		<key>calibration_res_x</key> <integer>208</integer>
+		
+		<!--calibration_res_y: y resolution of images used during calibration-->
+		<key>calibration_res_y</key> <integer>160</integer>
+		
+		<!--focal_len_x: focal length of camera, in pixels, K11-->
+		<key>focal_len_x</key> <real>198.807</real>
+		
+		<!--focal_len_y: focal length of camera, in pixels, K22-->
+		<key>focal_len_y</key> <real>200.333</real>
+		
+		<!--kc1_r2: r-squared radial distortion-->
+		<key>kc1_r2</key> <real>-0.147005</real>
+		
+		<!--kc2_r4: r to the 4 radial distortion-->
+		<key>kc2_r4</key> <real>0.38485</real>
+		
+		<!--kc3_tan1: first tangential correction term-->
+		<key>kc3_tan1</key> <real>-0.00347777</real>
+		
+		<!--kc4_tan2: second tangential correctiont term-->
+		<key>kc4_tan2</key> <real>0.00012873</real>
+		
+		<!--kc5_r6: r to the 6 radial distortion-->
+		<key>kc5_r6</key> <real>0</real>
+		
+		<!--principle_point_x: center of optical projection, K13-->
+		<key>principle_point_x</key> <real>102.689</real>
+		
+		<!--principle_point_y: center of optical projection, K23-->
+		<key>principle_point_y</key> <real>85.0399</real>
+		
+		<!--CCD skew, K12 = skew*focal_len_x-->
+		<key>skew</key> <real>0</real>
+	</dict>
+	
+	<!--The colors definition (.col) file gives names and a "typical" color for display.
+	The indexes numbers it contains correspond to indexes in the .tm file
+	This file is common to all .tm files; when doing new color segmentations,
+	make sure you define colors in the same order as listed here! -->
+	<key>colors</key> <string>config/default.col</string>
+	
+	<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+	Value is one of: { low | mid | high } -->
+	<key>gain</key> <string>mid</string>
+	
+	<!--jpeg_dct_method: pick between dct methods for jpeg compression
+	Value is one of: { islow | ifast | float } -->
+	<key>jpeg_dct_method</key> <string>ifast</string>
+	
+	<!--======== rawcam ========-->
+	<key>rawcam</key> <dict>
+		<!--channel: if encoding is single channel, this indicates the channel to send-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--compress_quality: 0-100, compression quality (currently only used by jpeg)-->
+		<key>compress_quality</key> <integer>85</integer>
+		
+		<!--compression: the type of compression to apply the image
+		Value is one of: { none | jpeg } -->
+		<key>compression</key> <string>jpeg</string>
+		
+		<!--encoding: holds whether to send color or single channel
+		Value is one of: { color | grayscale } -->
+		<key>encoding</key> <string>color</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10011</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+		
+		<!--uv_skip: resolution level to transmit uv channel at when using 'color' encoding mode-->
+		<key>uv_skip</key> <integer>3</integer>
+		
+		<!--y_skip: resolution level to transmit y channel
+		Also used as the resolution level when in single-channel encoding mode -->
+		<key>y_skip</key> <integer>2</integer>
+	</dict>
+	
+	<!--region_calc_total: When true, this will fill in the CMVision::color_class_state::total_area
+	field for each color following region labeling.  If false, the total_area
+	will stay 0 (or whatever the last value was), but you save a little CPU. -->
+	<key>region_calc_total</key> <true/>
+	
+	<!--======== regioncam ========-->
+	<key>regioncam</key> <dict>
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10013</integer>
+		
+		<!--skip: resolution level to extract regions from-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--the resolution that object recognition system will run at.
+	This counts down from the maximum resolution layer, so higher numbers mean lower resolution. -->
+	<key>resolution</key> <integer>1</integer>
+	
+	<!--restore_image: Apparently someone at Sony thought it would be a good idea to replace some
+	pixels in each camera image with information like the frame number and CDT count.
+	If non-zero, will replace those pixels with the actual image pixel value in RawCamGenerator -->
+	<key>restore_image</key> <true/>
+	
+	<!--======== segcam ========-->
+	<key>segcam</key> <dict>
+		<!--channel of RLEGenerator to send (i.e. which threshold map to use-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--what compression to use on the segmented imageValue is one of: { none | rle } -->
+		<key>compression</key> <string>rle</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10012</integer>
+		
+		<!--skip: resolution level to transmit segmented images at-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+	</dict>
+	
+	<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+	Value is one of: { slow | mid | fast } -->
+	<key>shutter_speed</key> <string>slow</string>
+	
+	<!--======== thresh ========-->
+	<!--Threshold (.tm) files define the mapping from full color to indexed color.
+	You can uncomment more than one of these - they will be loaded into separate
+	channels of the segmenter.  The only cost of loading multiple threshold files is
+	memory - the CPU cost of performing segmentation is only incurred if/when
+	the channel is actually accessed for the first time for a given frame. -->
+	<key>thresh</key> <array>
+		<string>config/7general.tm</string>
+	</array>
+	
+	<!--white_balance: white balance shifts color spectrum in the image
+	Value is one of: { indoor | outdoor | fluorescent } -->
+	<key>white_balance</key> <string>indoor</string>
+</dict>
+
+<!--======== wireless ========-->
+<key>wireless</key> <dict>
+	<!--id number (in case you have more than one AIBO)-->
+	<key>id</key> <integer>1</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-tekkotsu3.plist ./tools/test/config/ideal-tekkotsu3.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-tekkotsu3.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-tekkotsu3.plist	2007-11-21 22:47:07.000000000 -0500
@@ -0,0 +1,565 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict><!--
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+#########################   $Name: tekkotsu-4_0 $   ##########################
+#####################   $Revision: 1.2 $   ######################
+################   $Date: 2007/11/22 03:47:07 $   ################
+##################################################################
+
+This is an XML-based format using the Property List (plist) layout.
+
+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 in 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.
+
+You can change these settings at run time from the Controller
+by entering the command:
+   !set section_name.variable=value
+or by using the configuration editor found in the "File Access"
+menu.  Paths are assumed to be relative to the 'project/ms/'
+directory.  For example, this file would be referenced as
+'config/tekkotsu.xml'
+
+See also the 'simulator.xml' file, which provides you the ability
+to override settings when running in the simulator
+-->
+
+<!--======== behaviors ========-->
+<key>behaviors</key> <dict>
+	<!--flash_bytes: how many bytes of the address to flash
+	You probably already know the first 3 bytes for your network,
+	so you might only want the last byte for brevity.
+	(valid values are 1 through 4) -->
+	<key>flash_bytes</key> <integer>4</integer>
+	
+	<!--flash_on_start: whether or not to automatically trigger on boot
+	Will use a priority of kEmergencyPriority+1 in order to override
+	the emergency stop's status animation -->
+	<key>flash_on_start</key> <false/>
+</dict>
+
+<!--======== controller ========-->
+<key>controller</key> <dict>
+	<!--gui_port: port to listen for the GUI to connect to aibo on-->
+	<key>gui_port</key> <integer>10020</integer>
+	
+	<!--cancel_snd: sound file to use for "cancel" action-->
+	<key>cancel_snd</key> <string>whoop.wav</string>
+	
+	<!--error_snd: sound file to use to signal errors-->
+	<key>error_snd</key> <string>fart.wav</string>
+	
+	<!--next_snd: sound file to use for "next" action-->
+	<key>next_snd</key> <string>toc.wav</string>
+	
+	<!--prev_snd: sound file to use for "prev" action-->
+	<key>prev_snd</key> <string>tick.wav</string>
+	
+	<!--read_snd: sound file to use for "read from std-in" action-->
+	<key>read_snd</key> <string>ping.wav</string>
+	
+	<!--select_snd: sound file to use for "select" action-->
+	<key>select_snd</key> <string>whiip.wav</string>
+</dict>
+
+<!--======== main ========-->
+<key>main</key> <dict>
+	<!--aibo3d_port: port for send/receive of joint positions from Aibo 3D GUI-->
+	<key>aibo3d_port</key> <integer>10051</integer>
+	
+	<!--consoleMode: determines how input on console_port is interpreted
+	Value is one of: { controller | textmsg | auto } 
+	  'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
+	  'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
+	  'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise -->
+	<key>consoleMode</key> <string>controller</string>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10001</integer>
+	
+	<!--estopControl_port: port for receiving walk commands-->
+	<key>estopControl_port</key> <integer>10053</integer>
+	
+	<!--headControl_port: port for receiving head commands-->
+	<key>headControl_port</key> <integer>10052</integer>
+	
+	<!--seed_rng: if true, will call srand with timestamp data, mangled by current sensor data-->
+	<key>seed_rng</key> <true/>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10002</integer>
+	
+	<!--stewart_port: port for running a stewart platform style of control-->
+	<key>stewart_port</key> <integer>10055</integer>
+	
+	<!--use_VT100: if true, enables VT100 console codes (currently only in Controller menus - 1.3)-->
+	<key>use_VT100</key> <false/>
+	
+	<!--walkControl_port: port for receiving walk commands-->
+	<key>walkControl_port</key> <integer>10050</integer>
+	
+	<!--wmmonitor_port: port for monitoring Watchable Memory-->
+	<key>wmmonitor_port</key> <integer>10061</integer>
+	
+	<!--worldState_interval: time (in milliseconds) to wait between sending WorldState updates over wireless-->
+	<key>worldState_interval</key> <integer>0</integer>
+	
+	<!--wsjoints_port: port to send joint positions on-->
+	<key>wsjoints_port</key> <integer>10031</integer>
+	
+	<!--wspids_port: port to send pid info on-->
+	<key>wspids_port</key> <integer>10032</integer>
+</dict>
+
+<!--======== motion ========-->
+<key>motion</key> <dict>
+	<!--======== calibration_offset ========-->
+	<!--These values indicate the offset from user specified zero point to the
+	physical system's zero point.  Applied before calibration_scale when
+	converting from user's desired position to command to send to hardware. -->
+	<key>Model:ERS-7:calibration_offset</key> <dict>
+		<key>LFr:rotor</key> <real>0</real>
+		<key>LFr:elvtr</key> <real>0</real>
+		<key>LFr:knee</key> <real>0</real>
+		<!-- ... -->
+		<key>RFr:rotor</key> <real>0</real>
+		<key>RFr:elvtr</key> <real>0</real>
+		<key>RFr:knee</key> <real>0</real>
+		<key>LBk:rotor</key> <real>0</real>
+		<key>LBk:elvtr</key> <real>0</real>
+		<key>LBk:knee</key> <real>0</real>
+		<key>RBk:rotor</key> <real>0</real>
+		<key>RBk:elvtr</key> <real>0</real>
+		<key>RBk:knee</key> <real>0</real>
+		<key>NECK:tilt</key> <real>0</real>
+		<key>NECK:pan</key> <real>0</real>
+		<key>NECK:nod</key> <real>0</real>
+		<key>TAIL:tilt</key> <real>0</real>
+		<key>TAIL:pan</key> <real>0</real>
+		<key>MOUTH</key> <real>0</real>
+	</dict>
+	<!--======== calibration_scale ========-->
+	<!--Multiplier from desired position to command for each PID joint, applied after calibration_offset. -->
+	<key>Model:ERS-7:calibration_scale</key> <dict>
+		<key>LFr:rotor</key> <real>1</real>
+		<key>LFr:elvtr</key> <real>1</real>
+		<key>LFr:knee</key> <real>1</real>
+		<!-- ... -->
+		<key>RFr:rotor</key> <real>1</real>
+		<key>RFr:elvtr</key> <real>1</real>
+		<key>RFr:knee</key> <real>1</real>
+		<key>LBk:rotor</key> <real>1</real>
+		<key>LBk:elvtr</key> <real>1</real>
+		<key>LBk:knee</key> <real>1</real>
+		<key>RBk:rotor</key> <real>1</real>
+		<key>RBk:elvtr</key> <real>1</real>
+		<key>RBk:knee</key> <real>1</real>
+		<key>NECK:tilt</key> <real>1</real>
+		<key>NECK:pan</key> <real>1</real>
+		<key>NECK:nod</key> <real>1</real>
+		<key>TAIL:tilt</key> <real>1</real>
+		<key>TAIL:pan</key> <real>1</real>
+		<key>MOUTH</key> <real>1</real>
+	</dict>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10003</integer>
+	
+	<!--estop_off_snd: sound file to use when e-stop turned off-->
+	<key>estop_off_snd</key> <string>yap.wav</string>
+	
+	<!--estop_on_snd: sound file to use when e-stop turned on-->
+	<key>estop_on_snd</key> <string>skid.wav</string>
+	
+	<!--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-->
+	<key>inf_walk_accel</key> <false/>
+	
+    <key>Model:ERS-7</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers7.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Mouth</string>
+            <string>NearIR</string>
+            <string>FarIR</string>
+            <string>ChestIR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:ERS-210</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers210.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Mouth</string>
+            <string>IR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:ERS-220</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers220.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>IR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+	<key>Model:QBotPlus</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/QBotPlus.kin</string>
+
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:Regis1</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/Regis1.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Arm</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+	
+	<!--max_head_pan_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_pan_speed</key> <real>5.7814</real>
+	
+	<!--max_head_roll_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_roll_speed</key> <real>5.7814</real>
+	
+	<!--max_head_tilt_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_tilt_speed</key> <real>3.18523</real>
+	
+	<!--root: path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
+	Any motion related paths which are not absolute (i.e. do not start with '/')
+	will be assumed to be relative to this directory -->
+	<key>root</key> <string>data/motion</string>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10004</integer>
+	
+	<!--the walk parameter file to load by default for new WalkMC's-->
+	<key>walk</key> <string>walk.prm</string>
+</dict>
+
+<!--======== sound ========-->
+<key>sound</key> <dict>
+	<!--pitchConfidenceThreshold: confidence threshold required to generate a pitch event [0-1]-->
+	<key>pitchConfidenceThreshold</key> <real>0.6</real>
+	
+	<!--======== preload ========-->
+	<!--list of sounds to preload at boot-->
+	<key>preload</key> <array>
+		<string>skid.wav</string>
+		<string>yap.wav</string>
+	</array>
+	
+	<!--root: path to sound clips-->
+	<key>root</key> <string>data/sound</string>
+	
+	<!--sample_bits: sample bit depth, either 8 or 16-->
+	<key>sample_bits</key> <integer>16</integer>
+	
+	<!--sample_rate: sample rate to send to system, currently only 8000 or 16000 supported-->
+	<key>sample_rate</key> <integer>16000</integer>
+	
+	<!--======== streaming ========-->
+	<key>streaming</key> <dict>
+		<!--mic_port: port for streaming microphone samples-->
+		<key>mic_port</key> <integer>10070</integer>
+		
+		<!--mic_sample_bits: sample bit depth from the microphone (either 8 or 16)-->
+		<key>mic_sample_bits</key> <integer>16</integer>
+		
+		<!--mic_sample_rate: sample rate from the microphone-->
+		<key>mic_sample_rate</key> <integer>16000</integer>
+		
+		<!--mic_stereo: whether to stream stereo or mono from the microphone-->
+		<key>mic_stereo</key> <true/>
+		
+		<!--speaker_frame_length: length of frame sent to the speaker (ms)-->
+		<key>speaker_frame_length</key> <integer>64</integer>
+		
+		<!--speaker_max_delay: maximum delay (ms) during playback-->
+		<key>speaker_max_delay</key> <integer>1000</integer>
+		
+		<!--speaker_port: port for streaming speaker samples-->
+		<key>speaker_port</key> <integer>10071</integer>
+	</dict>
+	
+	<!--volume in decibels - the value is interpreted as a signed short, where
+	0x8000 is mute, 0xFFFF is full volume (low=0xE700, mid=0xEE00, high=0xF600)
+	If you directly set the decibel level, be warned sony recommends against going above 0xF600
+	However, I believe the commercial software on the ERS-7 runs at 0xFF00.
+	Going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
+	Value is one of: { mute | low | mid | high | <integer_value> } -->
+	<key>volume</key> <string>high</string>
+</dict>
+
+<!--======== vision ========-->
+<key>vision</key> <dict>
+	<key>Model:ERS-7</key> <dict>
+		<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+		Value is one of: { low | mid | high } -->
+		<key>gain</key> <string>mid</string>
+		
+		<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+		Value is one of: { slow | mid | fast } -->
+		<key>shutter_speed</key> <string>slow</string>
+		
+		<!--white_balance: white balance shifts color spectrum in the image
+		Value is one of: { indoor | outdoor | fluorescent } -->
+		<key>white_balance</key> <string>indoor</string>
+		
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	<key>Model:ERS-2*</key> <dict>
+		<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+		Value is one of: { low | mid | high } -->
+		<key>gain</key> <string>mid</string>
+		
+		<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+		Value is one of: { slow | mid | fast } -->
+		<key>shutter_speed</key> <string>mid</string>
+		
+		<!--white_balance: white balance shifts color spectrum in the image
+		Value is one of: { indoor | outdoor | fluorescent } -->
+		<key>white_balance</key> <string>fluorescent</string>
+		
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+		<!--<string>210pb.tm</string>  just pink and blue -->
+			<string>config/210phb.tm</string> <!-- pink, skin (hand), and blue -->
+			<!--   note: "skin" is just of people who work in our lab - not a general sampling... :( -->
+			<string>config/210genrl.tm</string> <!-- general colors for the ERS-210 -->
+			<string>config/ball.tm</string> <!-- standard Sony pink ball definition -->
+		</array>
+	</dict>
+	<key>Model:Regis1</key> <dict>
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	
+	<key>Model:QBotPlus</key> <dict>
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	
+	<!--The colors definition (.col) file gives names and a "typical" color for display.
+	The indexes numbers it contains correspond to indexes in the .tm file
+	This file is common to all .tm files; when doing new color segmentations,
+	make sure you define colors in the same order as listed here! -->
+	<key>colors</key> <string>config/default.col</string>
+	
+	<!--jpeg_dct_method: pick between dct methods for jpeg compression
+	Value is one of: { islow | ifast | float } -->
+	<key>jpeg_dct_method</key> <string>ifast</string>
+	
+	<!--region_calc_total: When true, this will fill in the CMVision::color_class_state::total_area
+	field for each color following region labeling.  If false, the total_area
+	will stay 0 (or whatever the last value was), but you save a little CPU. -->
+	<key>region_calc_total</key> <true/>
+	
+	<!--the resolution that object recognition system will run at.
+	This counts down from the maximum resolution layer, so higher numbers mean lower resolution. -->
+	<key>resolution</key> <integer>1</integer>
+	
+	<!--restore_image: Apparently someone at Sony thought it would be a good idea to replace some
+	pixels in each camera image with information like the frame number and CDT count.
+	If non-zero, will replace those pixels with the actual image pixel value in RawCamGenerator -->
+	<key>restore_image</key> <true/>
+	
+	<!--======== rawcam ========-->
+	<key>rawcam</key> <dict>
+		<!--channel: if encoding is single channel, this indicates the channel to send-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--compress_quality: 0-100, compression quality (currently only used by jpeg)-->
+		<key>compress_quality</key> <integer>85</integer>
+		
+		<!--compression: the type of compression to apply the image
+		Value is one of: { none | jpeg } -->
+		<key>compression</key> <string>jpeg</string>
+		
+		<!--encoding: holds whether to send color or single channel
+		Value is one of: { color | grayscale } -->
+		<key>encoding</key> <string>color</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10011</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+		
+		<!--uv_skip: resolution level to transmit uv channel at when using 'color' encoding mode
+		"skip" is the log_2 of number of pixels to increment, 0 sends reconstructed double
+		resolution (mainly useful for Y channel, others are just resampled).
+		Our eyes are more sensitive to intensity (y channel) so you might
+		want to send the UV channels at a lower resolution (higher skip) as
+		a form of compression.
+		Valid values on the Aibo are 0-5-->
+		<key>uv_skip</key> <integer>3</integer>
+		
+		<!--y_skip: resolution level to transmit y channel
+		Also used as the resolution level when in single-channel encoding mode -->
+		<key>y_skip</key> <integer>2</integer>
+	</dict>
+	
+	<!--======== regioncam ========-->
+	<key>regioncam</key> <dict>
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10013</integer>
+		
+		<!--skip: resolution level to extract regions from-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--======== segcam ========-->
+	<key>segcam</key> <dict>
+		<!--channel of RLEGenerator to send (i.e. which threshold map to use-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--what compression to use on the segmented imageValue is one of: { none | rle } -->
+		<key>compression</key> <string>rle</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10012</integer>
+		
+		<!--skip: resolution level to transmit segmented images at-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+	</dict>
+	
+	<!--======== calibration ========-->
+	<!--Lens distortion correction parameters
+	Computated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet-->
+	<key>Model:ERS-7:calibration</key> <dict>
+		<!--calibration_res_x: x resolution of images used during calibration-->
+		<key>calibration_res_x</key> <integer>208</integer>
+		
+		<!--calibration_res_y: y resolution of images used during calibration-->
+		<key>calibration_res_y</key> <integer>160</integer>
+		
+		<!--focal_len_x: focal length of camera, in pixels, K11-->
+		<key>focal_len_x</key> <real>198.807</real>
+		
+		<!--focal_len_y: focal length of camera, in pixels, K22-->
+		<key>focal_len_y</key> <real>200.333</real>
+		
+		<!--kc1_r2: r-squared radial distortion-->
+		<key>kc1_r2</key> <real>-0.147005</real>
+		
+		<!--kc2_r4: r to the 4 radial distortion-->
+		<key>kc2_r4</key> <real>0.38485</real>
+		
+		<!--kc3_tan1: first tangential correction term-->
+		<key>kc3_tan1</key> <real>-0.00347777</real>
+		
+		<!--kc4_tan2: second tangential correctiont term-->
+		<key>kc4_tan2</key> <real>0.00012873</real>
+		
+		<!--kc5_r6: r to the 6 radial distortion-->
+		<key>kc5_r6</key> <real>0</real>
+		
+		<!--principle_point_x: center of optical projection, K13-->
+		<key>principle_point_x</key> <real>102.689</real>
+		
+		<!--principle_point_y: center of optical projection, K23-->
+		<key>principle_point_y</key> <real>85.0399</real>
+		
+		<!--CCD skew, K12 = skew*focal_len_x-->
+		<key>skew</key> <real>0</real>
+	</dict>
+</dict>
+
+<!--======== wireless ========-->
+<key>wireless</key> <dict>
+	<!--id number (in case you have more than one AIBO)-->
+	<key>id</key> <integer>1</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-test1.plist ./tools/test/config/ideal-test1.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-test1.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-test1.plist	2007-11-15 12:26:54.000000000 -0500
@@ -0,0 +1,11 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><array>
+<string>4</string>
+<string>1</string>
+<string>2</string>
+<string>3</string>
+<string>1</string>
+<string>2</string>
+<string>3</string>
+</array></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-test2.plist ./tools/test/config/ideal-test2.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-test2.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-test2.plist	2007-11-15 12:26:54.000000000 -0500
@@ -0,0 +1,11 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><array>
+<integer>4</integer>
+<integer>1</integer>
+<integer>2</integer>
+<integer>3</integer>
+<integer>1</integer>
+<integer>2</integer>
+<integer>3</integer>
+</array></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/ideal-test3.plist ./tools/test/config/ideal-test3.plist
--- ../Tekkotsu_3.0/tools/test/config/ideal-test3.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/ideal-test3.plist	2007-11-15 12:26:54.000000000 -0500
@@ -0,0 +1,11 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><array>
+<string>4</string>
+<string>1</string>
+<string>2</string>
+<string>3</string>
+<string>1</string>
+<string>2</string>
+<string>3</string>
+</array></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/main.cc ./tools/test/config/main.cc
--- ../Tekkotsu_3.0/tools/test/config/main.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/main.cc	2007-11-16 14:19:38.000000000 -0500
@@ -0,0 +1,67 @@
+#include "Shared/Config.h"
+#include <iostream>
+
+using namespace std;
+
+int main (int argc, char * const argv[]) {
+#ifndef TGT_ERS7
+	// we have different default settings for different models
+	// so the 'ideal' file is only going to match ERS7
+	std::cout << "Skipping config load test on non-ERS7" << std::endl;
+#else
+	std::cout << "Loading old format" << std::endl;
+	config=new Config("tekkotsu.cfg");
+	std::cout << "Saving 1" << std::endl;
+	config->saveFile("tekkotsu.plist");
+	std::cout << "Reloading 1" << std::endl;
+	Config config2("tekkotsu.plist");
+	//config2.clearParseTree();
+	std::cout << "Saving 2" << std::endl;
+	config2.saveFile("tekkotsu2.plist");
+	std::cout << "Loading current" << std::endl;
+	Config config3("tekkotsu.xml");
+	std::cout << "Saving 3" << std::endl;
+	config3.saveFile("tekkotsu3.plist");
+	delete config;
+#endif
+	
+	char * v1 = "1";
+	const char * v2 = "2";
+	const char * const v3 = "3";
+	char v4[] = "1";
+	const char v5[] = "2";
+	std::string v6 = "3";
+	
+	//const size_t outbufSize=1000;
+	//char outbuf[outbufSize];
+	
+	plist::Array test1;
+	test1.addValue("4"); test1.addValue(v1); test1.addValue(v2); test1.addValue(v3); test1.addValue(v4); test1.addValue(v5); test1.addValue(v6);
+	test1.saveFile("test1.plist");
+	/*size_t used=test1.saveBuffer(outbuf,outbufSize);
+	if(used==0)
+		return 1;
+	outbuf[used]='\0';
+	cout << outbuf << endl;*/
+	
+	plist::ArrayOf<plist::Primitive<int> > test2;
+	test2.addValue("4"); test2.addValue(v1); test2.addValue(v2); test2.addValue(v3); test2.addValue(v4); test2.addValue(v5); test2.addValue(v6);
+	test2.saveFile("test2.plist");
+	
+	plist::ArrayOf<plist::Primitive<std::string> > test3;
+	test3.addValue("4"); test3.addValue(v1); test3.addValue(v2); test3.addValue(v3); test3.addValue(v4); test3.addValue(v5); test3.addValue(v6);
+	test3.saveFile("test3.plist");
+	
+	plist::ArrayOf<plist::Collection> col;
+	col.addEntry(test1,"Array of anything (but only adding strings)");
+	col.addEntry(test2,"Array of integers");
+	col.addEntry(test3,"Array of strings");
+	/*size_t used=col.saveBuffer(outbuf,outbufSize);
+	if(used==0)
+		return 1;
+	outbuf[used]='\0';
+	cout << outbuf << endl;*/
+	col.saveFile("col.plist");
+	
+	return 0;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/tekkotsu.cfg ./tools/test/config/tekkotsu.cfg
--- ../Tekkotsu_3.0/tools/test/config/tekkotsu.cfg	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/tekkotsu.cfg	2007-01-30 17:56:26.000000000 -0500
@@ -0,0 +1,420 @@
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+##################### $Name: tekkotsu-4_0 $ ######################
+####################### $Revision: 1.1 $ ########################
+################## $Date: 2007/01/30 22:56:26 $ ##################
+##################################################################
+#
+# Format:
+#
+# * Comments are any line beginning with '#'
+#
+# * Model specific regions can be denoted with <MODELNAME>...</MODELNAME>
+#   - Wildcards can also be used: <ERS-2*>...</ERS-2*>
+#   - Anything not within a model region is read by all models (i.e. <*>..</*>)
+#   - Don't get fancy with the "tags" - one per line, the parser's not that smart
+#     (feel free to hack it if you want - it's in Config.cc)
+#
+# * Sections are demarcated with [SECTIONNAME]
+#   - A section is only ended by another section beginning
+#   - Section transitions within a model region will only be read by that model
+#   - Section names are case insensitive
+#
+# * Otherwise, each line is interpreted as: variable=value
+#   - this should correspond to Config::curSectionName_config::variable
+#   - interpretation is up to the code in Config.cc
+#   - some variables are lists (additional assignments push on the list),
+#     others are simply overwritten if a new value is assigned.
+#   - variable names are case insensitive
+#
+# * You can override these at run time from the Controller using the command:
+#   !set section_name.variable=value
+#   - Of course, whether or not the new value will be picked up depends on
+#     how it is being used...
+#
+# * Paths are assumed to be relative to the project/ms/ directory.
+#   For example, this file would be referenced as config/tekkotsu.cfg
+#
+##################################################################
+
+
+
+##################################################################
+##################################################################
+[Wireless]
+##################################################################
+##################################################################
+# unique id for Aibo (not used by Tekkotsu, but you might want it...)
+id=1
+
+
+
+##################################################################
+##################################################################
+[Vision]
+##################################################################
+##################################################################
+
+# white_balance  indoor | flourescent | outdoor
+<ERS-2*>
+white_balance=flourescent
+</ERS-2*>
+<ERS-7>
+white_balance=indoor
+</ERS-7>
+
+# gain           low | mid | high
+# higher gain will brighten the image, but increases noise
+gain=mid
+
+# shutter_speed  slow | mid | fast
+# slower shutter will brighten image, but increases motion blur
+<ERS-2*>
+shutter_speed=mid
+</ERS-2*>
+<ERS-7>
+shutter_speed=slow
+</ERS-7>
+
+# resolution     quarter | half | full
+# this is the resolution vision's object recognition system will run at
+resolution=full
+
+
+### Color Segmentation Threshold files ###
+# Threshold (.tm) files define the mapping from full color to indexed color
+# You can uncomment more than one of these - they will be loaded into
+# separate channels of the segmenter.  The only cost of loading multiple
+# threshold files is memory - the CPU cost of performing segmentation is
+# only done if/when the channel is actually accessed.
+
+# Included options for color threshold file:
+<ERS-2*>
+# 210pb.tm - pink and blue
+# 210phb.tm - pink, skin (hand), and blue
+#   note: "skin" is just of people who work in our lab - not a general sampling... :(
+# 210genrl.tm - general colors for the ERS-210
+# ball.tm - standard Sony pink ball definition
+thresh=config/210phb.tm
+thresh=config/210genrl.tm
+thresh=config/ball.tm
+</ERS-2*>
+<ERS-7>
+# 7general.tm - a general classification of a variety of colors for the ERS-7
+# 7red.tm - just a very broad pink/red/purple => "pink" color detection
+# ball.tm - standard Sony pink ball definition
+thresh=config/7general.tm
+</ERS-7>
+
+# the .col file gives names and a "typical" color for display
+# the indexes numbers it contains correspond to indexes in the .tm file
+# This file is common to all .tm files -- when doing new color segmentations,
+# make sure you define colors in the same order as listed here!
+colors=config/default.col
+
+
+### Image Streaming Format ###
+# These parameters control the video stream over wireless ethernet
+# transport can be either 'udp' or 'tcp'
+rawcam_port=10011
+rawcam_transport=udp
+segcam_port=10012
+segcam_transport=udp
+region_port=10013
+region_transport=tcp
+
+# pause between raw image grabs: 0 for fast-as-possible, 100 for 10 FPS, etc
+# in milliseconds
+segcam_interval=0
+
+# rawcam_encoding   color | y_only | uv_only | u_only | v_only | y_dx_only | y_dy_only | y_dxdy_only
+rawcam_encoding=color
+
+# compression       none | jpeg
+rawcam_compression=jpeg
+
+# quality of jpeg compression 0-100
+rawcam_compress_quality=85
+
+# pause between raw image grabs: 0 for fast-as-possible, 100 for 10 FPS
+# in milliseconds
+rawcam_interval=0
+
+# apparently someone at sony thinks it's a good idea to replace some
+# pixels in each camera image with information like the frame number
+# and CDT count.  if non-zero, will replace those pixels with the
+# actual image pixel value in RawCamGenerator
+restore_image=1
+
+# When true, this will fill in the CMVision::color_class_state::total_area
+# field for each color following region labeling.  If false, the total_area
+# will stay 0 (or whatever the last value was), but you save a little CPU.
+region_calc_total=1;
+
+# jpeg algorithm: 'islow' (integer, slow, but quality), 'ifast' (integer, fast, but rough), 'float' (floating point)
+jpeg_dct_method=ifast
+
+# log_2 of number of pixels to skip, 0 sends reconstructed double
+#   resolution (mainly useful for Y channel, others are just resampled)
+#   our eyes are more sensitive to intensity (y channel) so you might
+#   want to send the UV channels at a lower resolution (higher skip) as
+#   a form of compression
+# rawcam_y_skip is used when in sending single channel, regardless of
+#   which channel
+# valid values are 0-5
+rawcam_y_skip=2
+rawcam_uv_skip=3
+
+# you can send the original segmented image
+# or an RLE compressed version (which includes some noise removal)
+#segcam_compression   none | rle
+segcam_compression=rle
+
+# this is the channel of the seg cam which should be sent.
+# corresponds to the index of the .tm file you want in thresh
+segcam_channel=0
+
+# this is the log_2 of pixels to skip when sending
+# segmented camera images, same idea as rawcam_*_skip
+segcam_skip=1
+
+# this is the log_2 of pixels to skip when sending Region information,
+# same idea as rawcam_*_skip (added by nvh 21-04-05)
+regioncam_skip=1
+
+
+### Camera Calibration ###
+# see Config::vision_config::{computeRay,computePixel} to convert
+# between world coordinates and pixel coordinates using these values
+  
+# focal length (in pixels)
+focal_len_x = 198.807
+focal_len_y = 200.333
+  
+# center of optical projection (in pixels)
+principle_point_x = 102.689
+principle_point_y = 85.0399
+  
+# skew of CCD
+skew = 0
+  
+# Radial distortion terms
+kc1_r2 = -0.147005
+kc2_r4 = 0.38485
+kc5_r6 = 0
+  
+# Tangential distortion terms
+kc3_tan1 = -0.00347777
+kc4_tan2 = 0.00012873
+
+# resolution at which calibration images were taken
+calibration_res_x = 208
+calibration_res_y = 160
+
+
+##################################################################
+##################################################################
+[Main]
+##################################################################
+##################################################################
+
+# if non-zero, will call srand() with a high-precision timestamp, mangled by sensor data
+seed_rng=1
+
+# this mode parameter determines how input on console_port is handled
+# 'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
+# 'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
+# 'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise
+consoleMode=controller
+console_port=10001
+
+stderr_port=10002
+error_level=0
+debug_level=0
+verbose_level=0
+wsjoints_port=10031
+wspids_port=10032
+walkControl_port=10050
+aibo3d_port=10051
+headControl_port=10052
+estopControl_port=10053
+#stewart_port=10055
+wmmonitor_port=10061
+use_VT100=true
+# pause between writes: 0 for fast-as-possible, 100 for 10 FPS, etc.
+# in milliseconds
+#worldState_interval=0
+
+
+##################################################################
+##################################################################
+[Behaviors]
+##################################################################
+##################################################################
+
+### FlashIPAddrBehavior ###
+
+# You probably already know the first 3 bytes for your network
+# so you might only want the last byte for brevity
+# (valid values are 1 through 4)
+flash_bytes=4
+
+# Do you want to automatically trigger this on boot?
+# Will use a priority of kEmergencyPriority+1 in order to override
+# the emergency stop's status animation
+flash_on_start=0
+
+
+# your-stuff-here?
+
+##################################################################
+##################################################################
+[Controller]
+##################################################################
+##################################################################
+gui_port=10020
+select_snd=whiip.wav
+next_snd=toc.wav
+prev_snd=tick.wav
+read_snd=ping.wav
+cancel_snd=whoop.wav
+error_snd=fart.wav
+
+
+
+##################################################################
+##################################################################
+[Motion]
+##################################################################
+##################################################################
+
+# Any motion related paths which are not absolute (i.e. do not
+# start with '/') will be assumed to be relative to this directory
+root=data/motion
+
+# This is the default set of walk parameters
+walk=walk.prm
+
+# The file specified by "kinematics" should define the kinematic
+# chains which form your robot.
+# "kinematic_chains" lists the names of the chains which should be
+# loaded from that file
+<ERS-2*>
+<ERS-210>
+kinematics=/config/ers210.kin
+kinematic_chains=Body
+kinematic_chains=Mouth
+</ERS-210>
+<ERS-220>
+kinematics=/config/ers220.kin
+kinematic_chains=Body
+</ERS-220>
+kinematic_chains=IR
+</ERS-2*>
+<ERS-7>
+kinematics=/config/ers7.kin
+kinematic_chains=Body
+kinematic_chains=Mouth
+kinematic_chains=NearIR
+kinematic_chains=FarIR
+kinematic_chains=ChestIR
+</ERS-7>
+kinematic_chains=LFr
+kinematic_chains=RFr
+kinematic_chains=LBk
+kinematic_chains=RBk
+kinematic_chains=Camera
+
+# These values indicate the ratio of actual movement to commanded
+# So .9 means it moves 90% as far as it was supposed to.
+# This is then used both to calibrate joint values sent to the
+# system, as well as sensor values which are received back.
+# An unspecified joint is by default '1' which will then pass values
+# through unmodified.  Only PID joints are calibrated (i.e. LEDs and
+# ears are not)
+<ERS-7>
+calibrate:LFr:rotor=1.0
+calibrate:LFr:elvtr=1.0
+calibrate:LFr:knee~=1.0
+#...
+#The calibration I performed doesn't seem to hold up well, so
+#I'm leaving these all at 1.0.  Perhaps there is a constant
+#offset involved?  To be continued...
+</ERS-7>
+<ERS-2*>
+#ERS-2xx seems to be fairly well calibrated by system, but
+#you can always try to do better...
+</ERS-2*>
+
+# Sounds to play when turning estop on and off
+estop_on_snd=skid.wav
+estop_off_snd=yap.wav
+
+# These values are used by some behaviors to limit the
+# speed of the head to reduce wear on the joints
+# Units: radians per second
+<ERS-2*>
+max_head_tilt_speed=2.1
+max_head_pan_speed=3.0
+max_head_roll_speed=3.0
+</ERS-2*>
+<ERS-7>
+#the pan speed is revised down from Sony's maximum a bit
+max_head_tilt_speed=3.18522588
+max_head_pan_speed=5.78140315
+max_head_roll_speed=5.78140315
+</ERS-7>
+
+# If non-zero, robot should attempt to change directions instantaniously
+# If zero, robot should change directions more fluidly (following some internal acceleration calibration)
+inf_walk_accel=0
+
+console_port=10003
+stderr_port=10004
+
+
+
+##################################################################
+##################################################################
+[Sound]
+##################################################################
+##################################################################
+root=data/sound
+# volume = mute | level_1 | level_2 | level_3 | <direct dB setting: 0x8000 - 0xFFFF>
+# if you directly set the decibel level, be warned sony recommends against going above 0xF600
+# However, I believe the commercial software on the ERS-7 runs at 0xFF00
+# going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
+volume=level_3
+
+# Sound playback currently requires all sounds to be the same bit
+# rate.  Aperios further requires only either 8bit/8KHz or 16bit/16KHz
+# formats
+sample_rate=16000
+sample_bits=16
+
+# Preload is a list of sounds to cache at boot
+# can be either root relative or full path
+preload=skid.wav
+preload=yap.wav
+
+# Pitch detection confidence threshold [0-1]
+# Determines how liberal the pitch detector is at generating PitchEvents
+pitchConfidenceThreshold=0.6
+
+# Audio streaming settings
+# Audio from the AIBO's microphones
+streaming.mic_port=10070
+streaming.mic_sample_rate=16000
+streaming.mic_bits=16
+streaming.mic_stereo=true
+
+# Audio to the AIBO's speakers
+streaming.speaker_port=10071
+# Length of the speaker streaming buffer (ms)
+# Streamed samples are sent to the sound manager in packets of this length
+streaming.speaker_frame_len=64
+# Maximum delay (ms) during playback of received samples
+# If the playback queue gets longer it is emptied.
+streaming.speaker_max_delay=1000
+
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/config/tekkotsu.xml ./tools/test/config/tekkotsu.xml
--- ../Tekkotsu_3.0/tools/test/config/tekkotsu.xml	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/config/tekkotsu.xml	2007-11-21 22:47:07.000000000 -0500
@@ -0,0 +1,535 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict><!--
+##################################################################
+######################   Tekkotsu config   #######################
+##################################################################
+#########################   $Name: tekkotsu-4_0 $   ##########################
+#####################   $Revision: 1.2 $   ######################
+################   $Date: 2007/11/22 03:47:07 $   ################
+##################################################################
+
+This is an XML-based format using the Property List (plist) layout.
+
+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 in 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.
+
+You can change these settings at run time from the Controller
+by entering the command:
+   !set section_name.variable=value
+or by using the configuration editor found in the "File Access"
+menu.  Paths are assumed to be relative to the 'project/ms/'
+directory.  For example, this file would be referenced as
+'config/tekkotsu.xml'
+
+See also the 'simulator.xml' file, which provides you the ability
+to override settings when running in the simulator
+-->
+
+<!--======== behaviors ========-->
+<key>behaviors</key> <dict>
+	<!--flash_bytes: how many bytes of the address to flash
+	You probably already know the first 3 bytes for your network,
+	so you might only want the last byte for brevity.
+	(valid values are 1 through 4) -->
+	<key>flash_bytes</key> <integer>4</integer>
+	
+	<!--flash_on_start: whether or not to automatically trigger on boot
+	Will use a priority of kEmergencyPriority+1 in order to override
+	the emergency stop's status animation -->
+	<key>flash_on_start</key> <false/>
+</dict>
+
+<!--======== controller ========-->
+<key>controller</key> <dict>
+	<!--gui_port: port to listen for the GUI to connect to aibo on-->
+	<key>gui_port</key> <integer>10020</integer>
+	
+	<!--cancel_snd: sound file to use for "cancel" action-->
+	<key>cancel_snd</key> <string>whoop.wav</string>
+	
+	<!--error_snd: sound file to use to signal errors-->
+	<key>error_snd</key> <string>fart.wav</string>
+	
+	<!--next_snd: sound file to use for "next" action-->
+	<key>next_snd</key> <string>toc.wav</string>
+	
+	<!--prev_snd: sound file to use for "prev" action-->
+	<key>prev_snd</key> <string>tick.wav</string>
+	
+	<!--read_snd: sound file to use for "read from std-in" action-->
+	<key>read_snd</key> <string>ping.wav</string>
+	
+	<!--select_snd: sound file to use for "select" action-->
+	<key>select_snd</key> <string>whiip.wav</string>
+</dict>
+
+<!--======== main ========-->
+<key>main</key> <dict>
+	<!--aibo3d_port: port for send/receive of joint positions from Aibo 3D GUI-->
+	<key>aibo3d_port</key> <integer>10051</integer>
+	
+	<!--consoleMode: determines how input on console_port is interpreted
+	Value is one of: { controller | textmsg | auto } 
+	  'controller' will pass it as input to the Controller (assumes same syntax as ControllerGUI)
+	  'textmsg' will broadcast it as a TextMsgEvent (textmsgEGID)
+	  'auto' is the original mode, which uses 'textmsg' if the ControllerGUI is connected, and 'controller' otherwise -->
+	<key>consoleMode</key> <string>controller</string>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10001</integer>
+	
+	<!--estopControl_port: port for receiving walk commands-->
+	<key>estopControl_port</key> <integer>10053</integer>
+	
+	<!--headControl_port: port for receiving head commands-->
+	<key>headControl_port</key> <integer>10052</integer>
+	
+	<!--seed_rng: if true, will call srand with timestamp data, mangled by current sensor data-->
+	<key>seed_rng</key> <true/>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10002</integer>
+	
+	<!--stewart_port: port for running a stewart platform style of control-->
+	<key>stewart_port</key> <integer>10055</integer>
+	
+	<!--use_VT100: if true, enables VT100 console codes (currently only in Controller menus - 1.3)-->
+	<key>use_VT100</key> <false/>
+	
+	<!--walkControl_port: port for receiving walk commands-->
+	<key>walkControl_port</key> <integer>10050</integer>
+	
+	<!--wmmonitor_port: port for monitoring Watchable Memory-->
+	<key>wmmonitor_port</key> <integer>10061</integer>
+	
+	<!--worldState_interval: time (in milliseconds) to wait between sending WorldState updates over wireless-->
+	<key>worldState_interval</key> <integer>0</integer>
+	
+	<!--wsjoints_port: port to send joint positions on-->
+	<key>wsjoints_port</key> <integer>10031</integer>
+	
+	<!--wspids_port: port to send pid info on-->
+	<key>wspids_port</key> <integer>10032</integer>
+</dict>
+
+<!--======== motion ========-->
+<key>motion</key> <dict>
+	<!--======== calibration_offset ========-->
+	<!--These values indicate the offset from user specified zero point to the
+	physical system's zero point.  Applied before calibration_scale when
+	converting from user's desired position to command to send to hardware. -->
+	<key>Model:ERS-7:calibration_offset</key> <dict>
+		<key>LFr:rotor</key> <real>0</real>
+		<key>LFr:elvtr</key> <real>0</real>
+		<key>LFr:knee</key> <real>0</real>
+		<!-- ... -->
+	</dict>
+	<!--======== calibration_scale ========-->
+	<!--Multiplier from desired position to command for each PID joint, applied after calibration_offset. -->
+	<key>Model:ERS-7:calibration_scale</key> <dict>
+		<key>LFr:rotor</key> <real>1</real>
+		<key>LFr:elvtr</key> <real>1</real>
+		<key>LFr:knee</key> <real>1</real>
+		<!-- ... -->
+	</dict>
+	
+	<!--console_port: port to send/receive "console" information on (separate from system console)-->
+	<key>console_port</key> <integer>10003</integer>
+	
+	<!--estop_off_snd: sound file to use when e-stop turned off-->
+	<key>estop_off_snd</key> <string>yap.wav</string>
+	
+	<!--estop_on_snd: sound file to use when e-stop turned on-->
+	<key>estop_on_snd</key> <string>skid.wav</string>
+	
+	<!--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-->
+	<key>inf_walk_accel</key> <false/>
+	
+    <key>Model:ERS-7</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers7.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Mouth</string>
+            <string>NearIR</string>
+            <string>FarIR</string>
+            <string>ChestIR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:ERS-210</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers210.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Mouth</string>
+            <string>IR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:ERS-220</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/ers220.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>IR</string>
+            <string>LFr</string>
+            <string>RFr</string>
+            <string>LBk</string>
+            <string>RBk</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+	<key>Model:QBotPlus</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/QBotPlus.kin</string>
+
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+    <key>Model:Regis1</key> <dict>
+        <!--kinematics: the ROBOOP format kinematics description file to load-->
+        <key>kinematics</key> <string>/config/Regis1.kin</string>
+        
+        <!--list of chain names to load from the file specified by 'kinematics'-->
+        <key>kinematic_chains</key> <array>
+            <string>Body</string>
+            <string>Arm</string>
+            <string>Camera</string>
+        </array>
+    </dict>
+	
+	<!--max_head_pan_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_pan_speed</key> <real>5.7814</real>
+	
+	<!--max_head_roll_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_roll_speed</key> <real>5.7814</real>
+	
+	<!--max_head_tilt_speed: max speed for the head joints, used by HeadPointerMC; rad/s-->
+	<key>max_head_tilt_speed</key> <real>3.18523</real>
+	
+	<!--root: path on memory stick to "motion" files - for instance, position (.pos) and motion sequence (.mot)
+	Any motion related paths which are not absolute (i.e. do not start with '/')
+	will be assumed to be relative to this directory -->
+	<key>root</key> <string>data/motion</string>
+	
+	<!--stderr_port: port to send error information to-->
+	<key>stderr_port</key> <integer>10004</integer>
+	
+	<!--the walk parameter file to load by default for new WalkMC's-->
+	<key>walk</key> <string>walk.prm</string>
+</dict>
+
+<!--======== sound ========-->
+<key>sound</key> <dict>
+	<!--pitchConfidenceThreshold: confidence threshold required to generate a pitch event [0-1]-->
+	<key>pitchConfidenceThreshold</key> <real>0.6</real>
+	
+	<!--======== preload ========-->
+	<!--list of sounds to preload at boot-->
+	<key>preload</key> <array>
+		<string>skid.wav</string>
+		<string>yap.wav</string>
+	</array>
+	
+	<!--root: path to sound clips-->
+	<key>root</key> <string>data/sound</string>
+	
+	<!--sample_bits: sample bit depth, either 8 or 16-->
+	<key>sample_bits</key> <integer>16</integer>
+	
+	<!--sample_rate: sample rate to send to system, currently only 8000 or 16000 supported-->
+	<key>sample_rate</key> <integer>16000</integer>
+	
+	<!--======== streaming ========-->
+	<key>streaming</key> <dict>
+		<!--mic_port: port for streaming microphone samples-->
+		<key>mic_port</key> <integer>10070</integer>
+		
+		<!--mic_sample_bits: sample bit depth from the microphone (either 8 or 16)-->
+		<key>mic_sample_bits</key> <integer>16</integer>
+		
+		<!--mic_sample_rate: sample rate from the microphone-->
+		<key>mic_sample_rate</key> <integer>16000</integer>
+		
+		<!--mic_stereo: whether to stream stereo or mono from the microphone-->
+		<key>mic_stereo</key> <true/>
+		
+		<!--speaker_frame_length: length of frame sent to the speaker (ms)-->
+		<key>speaker_frame_length</key> <integer>64</integer>
+		
+		<!--speaker_max_delay: maximum delay (ms) during playback-->
+		<key>speaker_max_delay</key> <integer>1000</integer>
+		
+		<!--speaker_port: port for streaming speaker samples-->
+		<key>speaker_port</key> <integer>10071</integer>
+	</dict>
+	
+	<!--volume in decibels - the value is interpreted as a signed short, where
+	0x8000 is mute, 0xFFFF is full volume (low=0xE700, mid=0xEE00, high=0xF600)
+	If you directly set the decibel level, be warned sony recommends against going above 0xF600
+	However, I believe the commercial software on the ERS-7 runs at 0xFF00.
+	Going above 0xF800 on a ERS-210 causes distortion (clipping) - full volume on a ERS-7 sounds fine though.
+	Value is one of: { mute | low | mid | high | <integer_value> } -->
+	<key>volume</key> <string>high</string>
+</dict>
+
+<!--======== vision ========-->
+<key>vision</key> <dict>
+	<key>Model:ERS-7</key> <dict>
+		<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+		Value is one of: { low | mid | high } -->
+		<key>gain</key> <string>mid</string>
+		
+		<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+		Value is one of: { slow | mid | fast } -->
+		<key>shutter_speed</key> <string>slow</string>
+		
+		<!--white_balance: white balance shifts color spectrum in the image
+		Value is one of: { indoor | outdoor | fluorescent } -->
+		<key>white_balance</key> <string>indoor</string>
+		
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	<key>Model:ERS-2*</key> <dict>
+		<!--gain: Increasing gain will brighten the image, at the expense of more graininess/noise
+		Value is one of: { low | mid | high } -->
+		<key>gain</key> <string>mid</string>
+		
+		<!--shutter_speed: slower shutter will brighten image, but increases motion blur
+		Value is one of: { slow | mid | fast } -->
+		<key>shutter_speed</key> <string>mid</string>
+		
+		<!--white_balance: white balance shifts color spectrum in the image
+		Value is one of: { indoor | outdoor | fluorescent } -->
+		<key>white_balance</key> <string>fluorescent</string>
+		
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+		<!--<string>210pb.tm</string>  just pink and blue -->
+			<string>config/210phb.tm</string> <!-- pink, skin (hand), and blue -->
+			<!--   note: "skin" is just of people who work in our lab - not a general sampling... :( -->
+			<string>config/210genrl.tm</string> <!-- general colors for the ERS-210 -->
+			<string>config/ball.tm</string> <!-- standard Sony pink ball definition -->
+		</array>
+	</dict>
+	<key>Model:Regis1</key> <dict>
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	
+	<key>Model:QBotPlus</key> <dict>
+		<!--======== thresh ========-->
+		<!--Threshold (.tm) files define the mapping from full color to indexed color.
+		You can uncomment more than one of these - they will be loaded into separate
+		channels of the segmenter.  The only cost of loading multiple threshold files is
+		memory - the CPU cost of performing segmentation is only incurred if/when
+		the channel is actually accessed for the first time for a given frame. -->
+		<key>thresh</key> <array>
+			<string>config/7general.tm</string> <!-- a general classification of a variety of colors for the ERS-7 -->
+		<!--<string>7red.tm</string>  just a very broad pink/red/purple => "pink" color detection -->
+		<!--<string>ball.tm</string>  standard Sony pink ball definition -->
+		</array>
+	</dict>
+	
+	<!--The colors definition (.col) file gives names and a "typical" color for display.
+	The indexes numbers it contains correspond to indexes in the .tm file
+	This file is common to all .tm files; when doing new color segmentations,
+	make sure you define colors in the same order as listed here! -->
+	<key>colors</key> <string>config/default.col</string>
+	
+	<!--jpeg_dct_method: pick between dct methods for jpeg compression
+	Value is one of: { islow | ifast | float } -->
+	<key>jpeg_dct_method</key> <string>ifast</string>
+	
+	<!--region_calc_total: When true, this will fill in the CMVision::color_class_state::total_area
+	field for each color following region labeling.  If false, the total_area
+	will stay 0 (or whatever the last value was), but you save a little CPU. -->
+	<key>region_calc_total</key> <true/>
+	
+	<!--the resolution that object recognition system will run at.
+	This counts down from the maximum resolution layer, so higher numbers mean lower resolution. -->
+	<key>resolution</key> <integer>1</integer>
+	
+	<!--restore_image: Apparently someone at Sony thought it would be a good idea to replace some
+	pixels in each camera image with information like the frame number and CDT count.
+	If non-zero, will replace those pixels with the actual image pixel value in RawCamGenerator -->
+	<key>restore_image</key> <true/>
+	
+	<!--======== rawcam ========-->
+	<key>rawcam</key> <dict>
+		<!--channel: if encoding is single channel, this indicates the channel to send-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--compress_quality: 0-100, compression quality (currently only used by jpeg)-->
+		<key>compress_quality</key> <integer>85</integer>
+		
+		<!--compression: the type of compression to apply the image
+		Value is one of: { none | jpeg } -->
+		<key>compression</key> <string>jpeg</string>
+		
+		<!--encoding: holds whether to send color or single channel
+		Value is one of: { color | grayscale } -->
+		<key>encoding</key> <string>color</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10011</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+		
+		<!--uv_skip: resolution level to transmit uv channel at when using 'color' encoding mode
+		"skip" is the log_2 of number of pixels to increment, 0 sends reconstructed double
+		resolution (mainly useful for Y channel, others are just resampled).
+		Our eyes are more sensitive to intensity (y channel) so you might
+		want to send the UV channels at a lower resolution (higher skip) as
+		a form of compression.
+		Valid values on the Aibo are 0-5-->
+		<key>uv_skip</key> <integer>3</integer>
+		
+		<!--y_skip: resolution level to transmit y channel
+		Also used as the resolution level when in single-channel encoding mode -->
+		<key>y_skip</key> <integer>2</integer>
+	</dict>
+	
+	<!--======== regioncam ========-->
+	<key>regioncam</key> <dict>
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10013</integer>
+		
+		<!--skip: resolution level to extract regions from-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>TCP</string>
+	</dict>
+	
+	<!--======== segcam ========-->
+	<key>segcam</key> <dict>
+		<!--channel of RLEGenerator to send (i.e. which threshold map to use-->
+		<key>channel</key> <integer>0</integer>
+		
+		<!--what compression to use on the segmented imageValue is one of: { none | rle } -->
+		<key>compression</key> <string>rle</string>
+		
+		<!--interval: minimum amount of time (in milliseconds) which must pass between frames
+		E.g. 200 yields just under 5 frames per second, 0 is as fast as possible-->
+		<key>interval</key> <integer>0</integer>
+		
+		<!--the port number to open for sending data over-->
+		<key>port</key> <integer>10012</integer>
+		
+		<!--skip: resolution level to transmit segmented images at-->
+		<key>skip</key> <integer>1</integer>
+		
+		<!--transport: the IP protocol to use when sending data-->
+		<key>transport</key> <string>UDP</string>
+	</dict>
+	
+	<!--======== calibration ========-->
+	<!--Lens distortion correction parameters
+	Computated by 'Camera Calibration Toolbox for Matlab', by Jean-Yves Bouguet-->
+	<key>Model:ERS-7:calibration</key> <dict>
+		<!--calibration_res_x: x resolution of images used during calibration-->
+		<key>calibration_res_x</key> <integer>208</integer>
+		
+		<!--calibration_res_y: y resolution of images used during calibration-->
+		<key>calibration_res_y</key> <integer>160</integer>
+		
+		<!--focal_len_x: focal length of camera, in pixels, K11-->
+		<key>focal_len_x</key> <real>198.807</real>
+		
+		<!--focal_len_y: focal length of camera, in pixels, K22-->
+		<key>focal_len_y</key> <real>200.333</real>
+		
+		<!--kc1_r2: r-squared radial distortion-->
+		<key>kc1_r2</key> <real>-0.147005</real>
+		
+		<!--kc2_r4: r to the 4 radial distortion-->
+		<key>kc2_r4</key> <real>0.38485</real>
+		
+		<!--kc3_tan1: first tangential correction term-->
+		<key>kc3_tan1</key> <real>-0.00347777</real>
+		
+		<!--kc4_tan2: second tangential correctiont term-->
+		<key>kc4_tan2</key> <real>0.00012873</real>
+		
+		<!--kc5_r6: r to the 6 radial distortion-->
+		<key>kc5_r6</key> <real>0</real>
+		
+		<!--principle_point_x: center of optical projection, K13-->
+		<key>principle_point_x</key> <real>102.689</real>
+		
+		<!--principle_point_y: center of optical projection, K23-->
+		<key>principle_point_y</key> <real>85.0399</real>
+		
+		<!--CCD skew, K12 = skew*focal_len_x-->
+		<key>skew</key> <real>0</real>
+	</dict>
+</dict>
+
+<!--======== wireless ========-->
+<key>wireless</key> <dict>
+	<!--id number (in case you have more than one AIBO)-->
+	<key>id</key> <integer>1</integer>
+</dict>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/kinematics/Makefile ./tools/test/kinematics/Makefile
--- ../Tekkotsu_3.0/tools/test/kinematics/Makefile	2006-03-28 12:08:24.000000000 -0500
+++ ./tools/test/kinematics/Makefile	2007-11-15 20:03:35.000000000 -0500
@@ -15,15 +15,17 @@
 SRCSUFFIX:=.cc
 PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
 
-# We use a hard-coded TEKKOTSU_ROOT so this tool is always linked against the
-# the framework directory which contains it
-TEKKOTSU_ROOT=../../..
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -33,21 +35,26 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
 CXXFLAGS:=-g -Wall -O2 \
          -I$(TEKKOTSU_ROOT) \
-         -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -77,7 +84,7 @@
 clean:
 	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
 
-test: $(BIN)
+test: ./$(BIN)
 	@for x in * ; do \
 		if [ -r "ideal-$$x" ] ; then \
 			if diff -u "ideal-$$x" "$$x" ; then \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/kinematics/set_q.m ./tools/test/kinematics/set_q.m
--- ../Tekkotsu_3.0/tools/test/kinematics/set_q.m	2004-09-20 18:54:21.000000000 -0400
+++ ./tools/test/kinematics/set_q.m	2006-10-20 13:53:39.000000000 -0400
@@ -1,8 +1,18 @@
 function dh = set_q(origdh,type,q)
+% this function returns a Denavit-Hartenberg parameter set with the
+% specified joint position, handling both rotational and prismatic joints
+% origdh - the DH parameterization, which may contain a position offset
+% type - indicates 0 for rotational or 1 for prismatic for each joint
+% q - the vector of joint positions, relative to position specified in origdh
+% 
+% the idea is the origdh position is the hardware zero point, and
+% q is the position relative to that zero point, so the position in q
+% corresponds to the same position on the actual hardware
+
 len=min([size(origdh,1) size(q,1)]);
 rot_idxs=find(type(1:len)==0);
 prism_idxs=find(type(1:len)==1);
 
 dh=origdh;
 dh(rot_idxs,1)=dh(rot_idxs,1)+q(rot_idxs,1);
-dh(prism_idxs,2)=dh(prism_idxs,2)+q(prism_idxs,1);
\ No newline at end of file
+dh(prism_idxs,2)=dh(prism_idxs,2)+q(prism_idxs,1);
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/kinematics/test_kinematics.cc ./tools/test/kinematics/test_kinematics.cc
--- ../Tekkotsu_3.0/tools/test/kinematics/test_kinematics.cc	2005-06-01 01:48:09.000000000 -0400
+++ ./tools/test/kinematics/test_kinematics.cc	2007-11-16 12:18:45.000000000 -0500
@@ -3,10 +3,11 @@
 #define TK_ENABLE_KINEMATICS
 #include "local/minisim.h"
 
-#include <iostream>
-#include <stdlib.h>
 #include "Motion/PostureEngine.h"
 #include "Shared/newmat/newmatio.h"
+#include <iostream>
+#include <stdlib.h>
+#include <unistd.h>
 
 namespace ROBOOP {
 void serrprintf(const char* msg, int x, int y, int z) {
@@ -19,17 +20,10 @@
 using namespace minisim;
 
 int main(int /*argc*/, char** /*argv*/) {
-	config=new Config("../../../project/ms/config/tekkotsu.cfg");
-	config->setValue(Config::sec_motion,"root","../../../project/ms/data/motion");
-#if defined( TGT_ERS7 )
-	config->setValue(Config::sec_motion,"kinematics","../../../project/ms/config/ers7.kin");
-#elif defined( TGT_ERS210 ) || defined( TGT_ERS2xx )
-	config->setValue(Config::sec_motion,"kinematics","../../../project/ms/config/ers210.kin");
-#elif defined( TGT_ERS220 )
-	config->setValue(Config::sec_motion,"kinematics","../../../project/ms/config/ers220.kin");
-#else
-#  error Unknown target model
-#endif
+	if(chdir("../../../project")!=0) {
+		perror("could not cd to project directory ../../../project (need config files)");
+		return 1;
+	}
 	initialize();
 
 	
@@ -54,6 +48,8 @@
 	Plink(3)=10;
 	Plink(4)=1;
 
+#ifdef TGT_HAS_LEGS
+
 	cout << pose.getLinkInterestPoint(BaseFrameOffset,"LFrPaw");
 	
 	/*for(unsigned int i=LFrLegOffset; i<LFrLegOffset+JointsPerLeg; i++)
@@ -112,6 +108,8 @@
 	cout << pose.getTransformLinks(LFrLegOffset+KneeOffset,BaseFrameOffset) << endl;
 	cout << pose.getTransformLinks(PawFrameOffset+LFrLegOrder,BaseFrameOffset) << endl; */
 	
+#endif
+	
 	destruct();
 	return 0;
 }
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/netstream/Makefile ./tools/test/netstream/Makefile
--- ../Tekkotsu_3.0/tools/test/netstream/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/netstream/Makefile	2007-11-15 20:03:35.000000000 -0500
@@ -0,0 +1,93 @@
+
+# This Makefile will handle most aspects of compiling and
+# linking a tool against the Tekkotsu framework.  You probably
+# won't need to make any modifications, but here's the major controls
+
+# Executable name, defaults to:
+#   `basename \`pwd\``-$(TEKKOTSU_TARGET_MODEL)
+TEKKOTSU_TARGET_MODEL?=TGT_ERS7
+BIN:=$(shell pwd | sed 's@.*/@@')-$(shell echo $(patsubst TGT_%,%,$(TEKKOTSU_TARGET_MODEL)))
+
+# Build directory
+PROJECT_BUILDDIR:=build
+
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
+
+# Source files, defaults to all files ending matching *$(SRCSUFFIX)
+SRCSUFFIX:=.cc
+PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)") $(TEKKOTSU_ROOT)/Wireless/netstream.cc
+
+.PHONY: all test
+
+TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
+TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+
+TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
+include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
+FILTERSYSWARN:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(FILTERSYSWARN))
+COLORFILT:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(COLORFILT))
+$(shell mkdir -p $(PROJ_BD))
+
+PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
+
+# this one doesn't actually need libtekkotsu.a
+LIBS:= 
+# $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+
+DEPENDS:=$(PROJ_OBJ:.o=.d)
+
+CXXFLAGS:=-g -Wall \
+         -I$(TEKKOTSU_ROOT) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
+
+
+all: $(BIN)
+
+$(BIN): $(PROJ_OBJ) $(LIBS)
+	@echo "Linking $@..."
+	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+
+ifeq ($(findstring clean,$(MAKECMDGOALS)),)
+-include $(DEPENDS)
+endif
+
+%.a :
+	@echo "ERROR: $@ was not found.  You may need to compile the Tekkotsu framework."
+	@echo "Press return to attempt to build it, ctl-C to cancel."
+	@read;
+	$(MAKE) -C $(TEKKOTSU_ROOT) compile
+
+%.d :
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.d,%.cc,$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "$@..." | sed 's@.*$(TGT_BD)/@Generating @'; \
+	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
+
+%.o:
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "Compiling $$src..."; \
+	$(CXX) $(CXXFLAGS) -o $@ -c $$src > $*.log 2>&1; \
+	retval=$$?; \
+	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
+	test $$retval -eq 0; \
+
+clean:
+	rm -rf $(BIN) $(PROJECT_BUILDDIR) Shared *~
+
+test: ./$(BIN)
+	@for x in * ; do \
+		if [ -r "ideal-$$x" ] ; then \
+			if diff -u "ideal-$$x" "$$x" ; then \
+				echo "Test '$$x' passed"; \
+			else \
+				echo "Test output '$$x' does not match ideal"; \
+			fi; \
+		fi; \
+	done
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/netstream/netstream.cc ./tools/test/netstream/netstream.cc
--- ../Tekkotsu_3.0/tools/test/netstream/netstream.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/netstream/netstream.cc	2007-11-15 12:26:54.000000000 -0500
@@ -0,0 +1,158 @@
+#include "Wireless/netstream.h"
+#include <pthread.h>
+#include <semaphore.h>
+
+using namespace std;
+
+sem_t* done;
+int verbose=0;
+
+void thread_setup() {
+	pthread_setcancelstate(PTHREAD_CANCEL_ENABLE,NULL);
+	pthread_setcanceltype(PTHREAD_CANCEL_DEFERRED,NULL);
+}
+
+void* reader(void* p) {
+	thread_setup();
+	string x;
+	ionetstream& io=*(ionetstream*)p;
+	getline(io,x);
+	while(io || io.getReconnect()) {
+		cout << x << endl;
+		io.clear();
+		getline(io,x);
+		pthread_testcancel();
+	}
+	//cout << "Read posting done" << endl;
+	if(sem_post(done)!=0) {
+		perror("sem_post");
+		exit(1);
+	}
+	//cout << "Read done" << endl;
+	return NULL;
+}
+
+void* writer(void* p) {
+	thread_setup();
+	string x;
+	ionetstream& io=*(ionetstream*)p;
+	getline(cin,x);
+	while(cin) {
+		io << x << endl;
+		if(!io) {
+			if(verbose)
+				cerr << "Remote closed" << endl;
+			if(!io.getReconnect())
+				break;
+			io.clear();
+			//io.seekp(0); // to avoid buffering when closed...
+		}
+		pthread_testcancel();
+		getline(cin,x);
+	}
+	//cout << "Write posting done" << endl;
+	if(sem_post(done)!=0) {
+		perror("sem_post");
+		exit(1);
+	}
+	//cout << "Write done" << endl;
+	return NULL;
+}
+
+void test_cancel(int) { pthread_testcancel(); }
+
+int main(int argc, const char* argv[]) {
+	std::ios::sync_with_stdio(false);  // optional, only affects cout, etc.
+	
+	IPaddr a;
+	IPaddr::ipport_t localport=0;
+	bool datagram=false;
+	bool server=false;
+	bool reconnect=false;
+	int i=1;
+	for(; i<argc; i++) {
+		if(argv[i][0]!='-')
+			break;
+		else {
+			string flags = argv[i]+1;
+			for(string::size_type j=0; j<flags.size(); ++j) {
+				if(flags[j]=='u') { datagram=true; }
+				else if(flags[j]=='l') { server=true; }
+				else if(flags[j]=='p' && i+1<argc) { localport=atoi(argv[++i]); }
+				else if(flags[j]=='v') { verbose++; }
+				else if(flags[j]=='r') { reconnect=true; }
+				else {
+					cerr << "unknown flag " << flags[j] << endl;
+					return 2;
+				}
+			}
+		}
+	}
+	if(i<argc)
+		a.set_name(argv[i++]);
+	if(i<argc) {
+		int p=atoi(argv[i++]);
+		a.set_port(p);
+	}
+	//cout << datagram << ' ' << server << endl;
+	ionetstream io;
+	io.setReconnect(reconnect);
+	if(server) {
+		if(verbose)
+			cout << "Listening on port " << localport << "..." << flush;
+		io.listen(localport,datagram);
+	} else {
+		if(verbose)
+			cout << "Connecting to " << a.get_rname() << ' ' << a.get_display_num() << ' ' << a.get_port() << "..." << flush;
+		io.open(a,datagram);
+	}
+	io.setEcho(verbose>1);
+	if(verbose)
+		cout << "connected to " << io.getPeerAddress().get_display_num() << ":" << io.getPeerAddress().get_port()
+			<< " from " << io.getLocalAddress().get_display_num() << ":" << io.getLocalAddress().get_port() << endl;
+	string x;
+	if(!io.is_open())
+		return 1;
+	done=sem_open("done",O_CREAT|O_EXCL,0777,0);
+	if((size_t)done==(size_t)SEM_FAILED) {
+		perror("sem_open");
+		if(sem_unlink("done")!=0) {
+			perror("sem_unlink");
+			return 1;
+		}
+		return 1;
+	}
+	if(sem_unlink("done")!=0) {
+		perror("sem_unlink");
+		return 1;
+	}
+	pthread_t rt;
+	pthread_create(&rt,NULL,reader,&io);
+	pthread_t wt;
+	pthread_create(&wt,NULL,writer,&io);
+	
+	do {
+		if(sem_wait(done)!=0 && errno!=EINTR) {
+			perror("sem_wait");
+			return 1;
+		}
+	} while(errno==EINTR);
+	
+	//cout << "Cancelling..." << endl;
+	pthread_cancel(rt);
+	pthread_cancel(wt);
+	signal(SIGUSR1,test_cancel);
+	pthread_kill(rt,SIGUSR1);
+	pthread_kill(wt,SIGUSR1);
+	//cout << "Joining read..." << endl;
+	pthread_join(rt,NULL);
+	//cout << "Joining write..." << endl;
+	pthread_join(wt,NULL);
+	pthread_detach(rt);
+	pthread_detach(wt);
+	if(sem_close(done)!=0) {
+		perror("sem_close");
+		return 1;
+	}
+	return 0;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/network/Makefile ./tools/test/network/Makefile
--- ../Tekkotsu_3.0/tools/test/network/Makefile	2006-03-28 12:08:24.000000000 -0500
+++ ./tools/test/network/Makefile	2007-11-15 20:03:36.000000000 -0500
@@ -15,15 +15,17 @@
 SRCSUFFIX:=.cc
 PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
 
-# We use a hard-coded TEKKOTSU_ROOT so this tool is always linked against the
-# the framework directory which contains it
-TEKKOTSU_ROOT=../../..
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -33,21 +35,26 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
 CXXFLAGS:=-g -Wall -O2 \
          -I$(TEKKOTSU_ROOT) \
-         -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -77,7 +84,7 @@
 clean:
 	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
 
-test: $(BIN)
+test: ./$(BIN)
 	@for x in * ; do \
 		if [ -r "ideal-$$x" ] ; then \
 			if diff -u "ideal-$$x" "$$x" ; then \
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/pf-motion_model/Makefile ./tools/test/pf-motion_model/Makefile
--- ../Tekkotsu_3.0/tools/test/pf-motion_model/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/pf-motion_model/Makefile	2007-11-15 20:03:36.000000000 -0500
@@ -0,0 +1,93 @@
+
+# This Makefile will handle most aspects of compiling and
+# linking a tool against the Tekkotsu framework.  You probably
+# won't need to make any modifications, but here's the major controls
+
+# Executable name, defaults to:
+#   `basename \`pwd\``-$(TEKKOTSU_TARGET_MODEL)
+TEKKOTSU_TARGET_MODEL?=TGT_ERS7
+BIN:=$(shell pwd | sed 's@.*/@@')-$(shell echo $(patsubst TGT_%,%,$(TEKKOTSU_TARGET_MODEL)))
+
+# Build directory
+PROJECT_BUILDDIR:=build
+
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
+
+# Source files, defaults to all files ending matching *$(SRCSUFFIX)
+SRCSUFFIX:=.cc
+PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)") $(TEKKOTSU_ROOT)/Shared/zignor.cc $(TEKKOTSU_ROOT)/Shared/zigrandom.cc $(TEKKOTSU_ROOT)/Motion/HolonomicMotionModel.cc $(TEKKOTSU_ROOT)/Shared/Measures.cc
+
+.PHONY: all test
+
+TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
+TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+
+TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
+include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
+FILTERSYSWARN:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(FILTERSYSWARN))
+COLORFILT:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(COLORFILT))
+$(shell mkdir -p $(PROJ_BD))
+
+PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
+
+# this one doesn't actually need libtekkotsu.a
+LIBS:= 
+# $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+
+DEPENDS:=$(PROJ_OBJ:.o=.d)
+
+CXXFLAGS:=-g -Wall -O2 \
+         -I$(TEKKOTSU_ROOT) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
+
+
+all: $(BIN)
+
+$(BIN): $(PROJ_OBJ) $(LIBS)
+	@echo "Linking $@..."
+	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+
+ifeq ($(findstring clean,$(MAKECMDGOALS)),)
+-include $(DEPENDS)
+endif
+
+%.a :
+	@echo "ERROR: $@ was not found.  You may need to compile the Tekkotsu framework."
+	@echo "Press return to attempt to build it, ctl-C to cancel."
+	@read;
+	$(MAKE) -C $(TEKKOTSU_ROOT) compile
+
+%.d :
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.d,%.cc,$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "$@..." | sed 's@.*$(TGT_BD)/@Generating @'; \
+	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
+
+%.o:
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "Compiling $$src..."; \
+	$(CXX) $(CXXFLAGS) -o $@ -c $$src > $*.log 2>&1; \
+	retval=$$?; \
+	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
+	test $$retval -eq 0; \
+
+clean:
+	rm -rf $(BIN) $(PROJECT_BUILDDIR) Motion Shared *~
+
+test: ./$(BIN)
+	@for x in * ; do \
+		if [ -r "ideal-$$x" ] ; then \
+			if diff -u "ideal-$$x" "$$x" ; then \
+				echo "Test '$$x' passed"; \
+			else \
+				echo "Test output '$$x' does not match ideal"; \
+			fi; \
+		fi; \
+	done
\ No newline at end of file
Binary files ../Tekkotsu_3.0/tools/test/pf-motion_model/output.png and ./tools/test/pf-motion_model/output.png differ
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/pf-motion_model/output.txt ./tools/test/pf-motion_model/output.txt
--- ../Tekkotsu_3.0/tools/test/pf-motion_model/output.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/pf-motion_model/output.txt	2007-01-27 16:12:08.000000000 -0500
@@ -0,0 +1,104 @@
+0 0 0 0 0
+0.275664 -0.159155 0 100 0
+0.551329 -0.31831 0 200 0
+0.826993 -0.477465 0 300 0
+1.10266 -0.63662 0 400 0
+1.37832 -0.795775 0 500 0
+1.65399 -0.95493 0 600 0
+1.92965 -1.11408 0 700 0
+2.20532 -1.27324 0 800 0
+2.48098 -1.43239 0 900 0
+2.75664 -1.59155 0 1000 0
+3.03231 -1.7507 0 1100 0
+3.30797 -1.90986 0 1200 0
+3.58364 -2.06901 0 1300 0
+3.8593 -2.22817 0 1400 0
+4.13497 -2.38732 0 1500 0
+4.41063 -2.54648 0 1600 0
+4.6863 -2.70563 0 1700 0
+4.96196 -2.86479 0 1800 0
+5.23762 -3.02394 0 1900 0
+5.51329 -3.1831 0 2000 0
+5.51329 -3.1831 0 2000 1
+5.72832 -2.73227 0.15708 2050 1
+5.87018 -2.25335 0.314159 2100 1
+5.93538 -1.75814 0.471239 2150 1
+5.92231 -1.25882 0.628319 2200 1
+5.83128 -0.767702 0.785398 2250 1
+5.66455 -0.296866 0.942478 2300 1
+5.42622 0.142091 1.09956 2350 1
+5.12215 0.53836 1.25664 2400 1
+4.75983 0.882183 1.41372 2450 1
+4.34819 1.16509 1.5708 2500 1
+3.89736 1.38013 1.72788 2550 1
+3.41845 1.52199 1.88496 2600 1
+2.92324 1.58719 2.04204 2650 1
+2.42392 1.57411 2.19911 2700 1
+1.9328 1.48309 2.35619 2750 1
+1.46196 1.31636 2.51327 2800 1
+1.023 1.07802 2.67035 2850 1
+0.626736 0.773955 2.82743 2900 1
+0.282913 0.41164 2.98451 2950 1
+2.87282e-07 4.93998e-07 3.14159 3000 1
+2.87282e-07 4.93998e-07 3.14159 3000 2
+-0.282912 -0.411639 2.98451 3050 2
+-0.626735 -0.773954 2.82743 3100 2
+-1.023 -1.07802 2.67035 3150 2
+-1.46196 -1.31636 2.51327 3200 2
+-1.9328 -1.48309 2.35619 3250 2
+-2.42392 -1.57411 2.19911 3300 2
+-2.92323 -1.58719 2.04204 3350 2
+-3.41845 -1.52199 1.88496 3400 2
+-3.89736 -1.38013 1.72788 3450 2
+-4.34819 -1.16509 1.5708 3500 2
+-4.75983 -0.882183 1.41372 3550 2
+-5.12215 -0.538359 1.25664 3600 2
+-5.42622 -0.142091 1.09956 3650 2
+-5.66455 0.296866 0.942478 3700 2
+-5.83128 0.767703 0.785398 3750 2
+-5.92231 1.25883 0.628319 3800 2
+-5.93538 1.75814 0.471239 3850 2
+-5.87018 2.25335 0.314159 3900 2
+-5.72832 2.73227 0.15708 3950 2
+-5.51329 3.1831 0 4000 2
+-5.23038 3.59474 -0.157079 4050 2
+-4.88655 3.95705 -0.314159 4100 2
+-4.49028 4.26112 -0.471239 4150 2
+-4.05133 4.49946 -0.628319 4200 2
+-3.58049 4.66619 -0.785398 4250 2
+-3.08937 4.75721 -0.942477 4300 2
+-2.59005 4.77029 -1.09956 4350 2
+-2.09484 4.70509 -1.25664 4400 2
+-1.61592 4.56323 -1.41372 4450 2
+-1.1651 4.34819 -1.5708 4500 2
+-0.753455 4.06528 -1.72788 4550 2
+-0.391141 3.72146 -1.88496 4600 2
+-0.0870729 3.32519 -2.04204 4650 2
+0.151261 2.88623 -2.19912 4700 2
+0.317993 2.4154 -2.35619 4750 2
+0.409017 1.92427 -2.51327 4800 2
+0.422092 1.42496 -2.67035 4850 2
+0.356896 0.929746 -2.82743 4900 2
+0.215034 0.450829 -2.98451 4950 2
+9.00671e-09 1.20109e-08 -3.14159 5000 2
+9.00671e-09 1.20109e-08 -3.14159 5000 3
+-0.215034 -0.450829 -2.98451 5050 3
+-0.356896 -0.929746 -2.82743 5100 3
+-0.422092 -1.42496 -2.67035 5150 3
+-0.409017 -1.92427 -2.51327 5200 3
+-0.317993 -2.4154 -2.35619 5250 3
+-0.151261 -2.88623 -2.19911 5300 3
+0.0870729 -3.32519 -2.04204 5350 3
+0.391141 -3.72146 -1.88496 5400 3
+0.753455 -4.06528 -1.72788 5450 3
+1.1651 -4.34819 -1.5708 5500 3
+1.61592 -4.56323 -1.41372 5550 3
+2.09484 -4.70509 -1.25664 5600 3
+2.59005 -4.77029 -1.09956 5650 3
+3.08937 -4.75721 -0.942478 5700 3
+3.58049 -4.66619 -0.785398 5750 3
+4.05133 -4.49945 -0.628319 5800 3
+4.49028 -4.26112 -0.471239 5850 3
+4.88655 -3.95705 -0.314159 5900 3
+5.23038 -3.59474 -0.15708 5950 3
+5.51329 -3.1831 0 6000 3
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/pf-motion_model/pf-motion_model.cc ./tools/test/pf-motion_model/pf-motion_model.cc
--- ../Tekkotsu_3.0/tools/test/pf-motion_model/pf-motion_model.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/pf-motion_model/pf-motion_model.cc	2007-01-27 16:12:08.000000000 -0500
@@ -0,0 +1,61 @@
+#include <iostream>
+#include <cmath>
+#include "Motion/HolonomicMotionModel.h"
+
+namespace project_get_time {
+	unsigned int simulation_time=0;
+	unsigned int (*get_time_callback)()=NULL;
+}
+
+using namespace std;
+using namespace project_get_time;
+
+int main(int argc, char** argv) {
+	const float speed=10;
+	const float bearing=M_PI/3;
+	const float avel=M_PI;
+	const float time=1000;
+	const float dt=50;
+	
+	unsigned int& t=simulation_time;
+	float x=0, y=0, a=0;
+	HolonomicMotionModel<LocalizationParticle> mm;
+	
+	// straight line (blue segment in output.png)
+	mm.setVelocity((speed/avel)*cos(bearing-M_PI/2), (speed/avel)*sin(bearing-M_PI/2), 0, t);
+	for(; t<time*2; t+=dt*2) {
+		mm.getPosition(x,y,a,t);
+		cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 0 << endl;
+	}
+    mm.getPosition(x,y,a,t);
+    cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 0 << endl;
+	
+	// half circle curving left/counter-clockwise (pink segment in output.png)
+	mm.setVelocity(speed*cos(bearing), speed*sin(bearing), avel, t);
+	for(; t<time*3; t+=dt) {
+		mm.getPosition(x,y,a,t);
+		cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 1 << endl;
+	}
+    mm.getPosition(x,y,a,t);
+    cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 1 << endl;
+    
+    // full circle turning right/clockwise (red segment)
+	mm.setVelocity(speed*cos(bearing), speed*sin(bearing), -avel, t);
+	for(; t<time*5; t+=dt) {
+		mm.getPosition(x,y,a,t);
+		cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 2 << endl;
+	}
+    mm.getPosition(x,y,a,t);
+    cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 2 << endl;
+	
+	// half circle turning left/counter-clockwise (green segment)
+	mm.setVelocity(speed*cos(bearing), speed*sin(bearing), avel, t);
+	for(; t<time*6; t+=dt) {
+		mm.getPosition(x,y,a,t);
+		cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 3 << endl;
+	}
+    mm.getPosition(x,y,a,t);
+    cout << x << ' ' << y << ' ' << a << ' ' << t << ' ' << 3 << endl;
+	
+	return 0;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/pf-resampling/Makefile ./tools/test/pf-resampling/Makefile
--- ../Tekkotsu_3.0/tools/test/pf-resampling/Makefile	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/pf-resampling/Makefile	2007-11-15 20:03:37.000000000 -0500
@@ -0,0 +1,93 @@
+
+# This Makefile will handle most aspects of compiling and
+# linking a tool against the Tekkotsu framework.  You probably
+# won't need to make any modifications, but here's the major controls
+
+# Executable name, defaults to:
+#   `basename \`pwd\``-$(TEKKOTSU_TARGET_MODEL)
+TEKKOTSU_TARGET_MODEL?=TGT_ERS7
+BIN:=$(shell pwd | sed 's@.*/@@')-$(shell echo $(patsubst TGT_%,%,$(TEKKOTSU_TARGET_MODEL)))
+
+# Build directory
+PROJECT_BUILDDIR:=build
+
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT:=./../../..
+
+# Source files, defaults to all files ending matching *$(SRCSUFFIX)
+SRCSUFFIX:=.cc
+PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)") $(TEKKOTSU_ROOT)/Shared/zignor.cc $(TEKKOTSU_ROOT)/Shared/zigrandom.cc
+
+.PHONY: all test
+
+TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
+TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+
+TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
+include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
+FILTERSYSWARN:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(FILTERSYSWARN))
+COLORFILT:=$(patsubst $(TEKKOTSU_ROOT)/%,$(TEKKOTSU_ROOT)/%,$(COLORFILT))
+$(shell mkdir -p $(PROJ_BD))
+
+PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
+
+# this one doesn't actually need libtekkotsu.a
+LIBS:= 
+# $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+
+DEPENDS:=$(PROJ_OBJ:.o=.d)
+
+CXXFLAGS:=-g -Wall \
+         -I$(TEKKOTSU_ROOT) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
+
+
+all: $(BIN)
+
+$(BIN): $(PROJ_OBJ) $(LIBS)
+	@echo "Linking $@..."
+	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+
+ifeq ($(findstring clean,$(MAKECMDGOALS)),)
+-include $(DEPENDS)
+endif
+
+%.a :
+	@echo "ERROR: $@ was not found.  You may need to compile the Tekkotsu framework."
+	@echo "Press return to attempt to build it, ctl-C to cancel."
+	@read;
+	$(MAKE) -C $(TEKKOTSU_ROOT) compile
+
+%.d :
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.d,%.cc,$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "$@..." | sed 's@.*$(TGT_BD)/@Generating @'; \
+	$(CXX) $(CXXFLAGS) -MP -MG -MT "$@" -MT "$(@:.d=.o)" -MM "$$src" > $@
+
+%.o:
+	@mkdir -p $(dir $@)
+	@src=$(patsubst %.o,%$(SRCSUFFIX),$(patsubst $(PROJ_BD)/%,%,$@)); \
+	echo "Compiling $$src..."; \
+	$(CXX) $(CXXFLAGS) -o $@ -c $$src > $*.log 2>&1; \
+	retval=$$?; \
+	cat $*.log | $(FILTERSYSWARN) | $(COLORFILT) | $(TEKKOTSU_LOGVIEW); \
+	test $$retval -eq 0; \
+
+clean:
+	rm -rf $(BIN) $(PROJECT_BUILDDIR) Shared *~
+
+test: ./$(BIN)
+	@for x in * ; do \
+		if [ -r "ideal-$$x" ] ; then \
+			if diff -u "ideal-$$x" "$$x" ; then \
+				echo "Test '$$x' passed"; \
+			else \
+				echo "Test output '$$x' does not match ideal"; \
+			fi; \
+		fi; \
+	done
\ No newline at end of file
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/pf-resampling/pf-resampling.cc ./tools/test/pf-resampling/pf-resampling.cc
--- ../Tekkotsu_3.0/tools/test/pf-resampling/pf-resampling.cc	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/pf-resampling/pf-resampling.cc	2007-11-15 12:26:55.000000000 -0500
@@ -0,0 +1,91 @@
+#include "Shared/ParticleFilter.h"
+#include "Shared/zignor.h"
+#include <iostream>
+#include <cmath>
+#include <sys/time.h>
+
+namespace project_get_time {
+	unsigned int simulation_time=0;
+	unsigned int (*get_time_callback)()=NULL;
+}
+
+using namespace std;
+using namespace project_get_time;
+
+class Particle : public ParticleBase {
+public:
+	typedef class ParticleDistributionPolicy DistributionPolicy;
+	Particle() : ParticleBase(), pos() { }
+	template<typename ParticleT>  float sumSqErr(const ParticleT& p) const { 
+		float x=p.pos-pos; return x*x;
+	}
+	float pos;
+};
+
+typedef ParticleFilter<Particle> PF;
+typedef PF::LowVarianceResamplingPolicy Resampler;
+
+class ParticleDistributionPolicy : public PF::DistributionPolicy {
+	typedef PF::index_t index_t;
+	virtual void randomize(particle_type* begin, index_t num) {
+		particle_type* end=&begin[num]; 
+		cerr << "RANDOMIZED" << endl;
+		while(begin!=end)
+			(begin++)->pos = (float(random())/(-1U>>1)*M_PI*2);
+	}
+	virtual void jiggle(float var, particle_type* begin, index_t num) {
+		particle_type* end=&begin[num]; 
+		while(begin!=end) {
+			begin->pos = (begin->pos+DRanNormalZig32()*.1*var);
+			++begin;
+		}
+	}
+};
+
+class SinSensorModel : public PF::SensorModel {
+	typedef PF::particle_collection particle_collection;
+	typedef PF::index_t index_t;
+	virtual void evaluate(particle_collection& particles, index_t& bestIndex) {
+		for(index_t i=0; i<particles.size(); ++i) {
+			if(particles[i].pos<0 || particles[i].pos>M_PI*2)
+				particles[i].weight += -FLT_MAX;
+			else {
+				particles[i].weight += std::log(std::sin(particles[i].pos)/2+.5);
+				//particles[i].weight += std::log((std::cos(particles[i].pos)/2+.5)*(1-particles[i].pos/M_PI/10));
+				if(particles[i].weight>particles[bestIndex].weight)
+					bestIndex=i;
+			}
+		}
+	}
+};
+
+void doPlot(unsigned int i, const PF::particle_collection& p) {
+	cout << "plot '-' smooth frequency title 'distribution " << i << "' with boxes" << endl;
+	for(unsigned int i=0; i<p.size(); i++)
+		cout << floor(p[i].pos*10)/10 << " 1" << endl;
+	cout << "e" << endl << "pause 1" << endl;
+}
+
+int main(int argc, char** argv) {
+	struct timeval tp;
+	gettimeofday(&tp,NULL);
+	tp.tv_sec+=tp.tv_usec;
+	cerr << "seeds are " << tp.tv_sec << ", " << tp.tv_usec << endl;
+	RanNormalSetSeedZig32((int*)&tp.tv_sec,tp.tv_usec);
+	
+	PF filter(1000);
+	cout << "# output can be piped into gnuplot to produce plots" << endl;
+	cout << "set yrange [0:]" << endl;
+	cout << "set xrange [0:3*pi]" << endl;
+	doPlot(0,filter.getParticles());
+	SinSensorModel eval;
+	Resampler& r = dynamic_cast<Resampler&>(*filter.getResamplingPolicy());
+	for(unsigned int i=1; i<=15; i++) {
+		for(unsigned int j=0; j<1; j++) {
+			r.varianceScale=std::pow(0.75f,(float)j);
+			filter.updateSensors(eval);
+		}
+		doPlot(i,filter.getParticles());
+	}
+	return 0;
+}
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/Makefile ./tools/test/plist/Makefile
--- ../Tekkotsu_3.0/tools/test/plist/Makefile	2006-03-28 12:08:24.000000000 -0500
+++ ./tools/test/plist/Makefile	2007-11-15 20:03:37.000000000 -0500
@@ -15,15 +15,17 @@
 SRCSUFFIX:=.cc
 PROJ_SRC:=$(shell find . -name "*$(SRCSUFFIX)")
 
-# We use a hard-coded TEKKOTSU_ROOT so this tool is always linked against the
-# the framework directory which contains it
-TEKKOTSU_ROOT=../../..
+# Other default values are drawn from the template project's
+# Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
+# Remove the '?' if you want to override an environment variable
+# with a value of your own.
+TEKKOTSU_ROOT=./../../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -33,21 +35,26 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
 CXXFLAGS:=-g -Wall -O2 \
          -I$(TEKKOTSU_ROOT) \
-         -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -76,15 +83,21 @@
 
 clean:
 	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
+	@for x in * ; do \
+		if [ -r "ideal-$$x" ] ; then \
+			rm "$$x"; \
+		fi; \
+	done
 
-test: $(BIN)
-	./$(BIN)
+test: ./$(BIN)
+	./$(BIN) > output.txt
 	@for x in * ; do \
 		if [ -r "ideal-$$x" ] ; then \
 			if diff -u "ideal-$$x" "$$x" ; then \
 				echo "Test '$$x' passed"; \
 			else \
 				echo "Test output '$$x' does not match ideal"; \
+				exit 1; \
 			fi; \
 		fi; \
-	done
\ No newline at end of file
+	done
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-output.txt ./tools/test/plist/ideal-output.txt
--- ../Tekkotsu_3.0/tools/test/plist/ideal-output.txt	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/plist/ideal-output.txt	2007-11-08 22:31:07.000000000 -0500
@@ -0,0 +1,36 @@
+Original r, width: 3
+lower.0 = 1
+lower.1 = 2.5
+upper.0 = 4
+upper.1 = 5
+
+Negated r, width: 5
+lower.0 = -4
+lower.1 = 2.5
+upper.0 = 1
+upper.1 = 5
+
+Mixed.0           = 0
+Mixed.1           = 1
+Mixed.2           = 2
+Mixed.3           = This is item 1
+Mixed.4           = item 2: arrays can contain mixed types
+Mixed.5           = 123
+Mixed.6           = true
+map.0^2           = 0
+map.1^2           = 1
+map.2^2           = 4
+map.3^2           = 9
+map.4^2           = 16
+map.tada          = mixed types -- no surprise
+numeric.char-num  = 97
+numeric.char-text = a
+numeric.fooF      = 3.14159
+numeric.fooI      = 42
+test str          = Hello world!
+vector.0          = 0
+vector.1          = 1
+vector.2          = 4
+vector.3          = 9
+vector.4          = 16
+vector.5          = can also handle mixed
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-point.plist ./tools/test/plist/ideal-point.plist
--- ../Tekkotsu_3.0/tools/test/plist/ideal-point.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/plist/ideal-point.plist	2007-11-08 22:31:08.000000000 -0500
@@ -0,0 +1,6 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><array>
+<real>1</real>
+<real>2.5</real>
+</array></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-poly.plist ./tools/test/plist/ideal-poly.plist
--- ../Tekkotsu_3.0/tools/test/plist/ideal-poly.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/plist/ideal-poly.plist	2007-11-08 22:31:08.000000000 -0500
@@ -0,0 +1,16 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><array>
+<array>
+	<real>1</real>
+	<real>2</real>
+</array>
+<array>
+	<real>3</real>
+	<real>4</real>
+</array>
+<array>
+	<real>5</real>
+	<real>0</real>
+</array>
+</array></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-rectangle.plist ./tools/test/plist/ideal-rectangle.plist
--- ../Tekkotsu_3.0/tools/test/plist/ideal-rectangle.plist	1969-12-31 19:00:00.000000000 -0500
+++ ./tools/test/plist/ideal-rectangle.plist	2007-11-08 22:31:08.000000000 -0500
@@ -0,0 +1,15 @@
+<?xml version="1.0"?>
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<plist version="1.0"><dict>
+<!--======== lower ========-->
+<key>lower</key> <array>
+	<real>1</real>
+	<real>2.5</real>
+</array>
+
+<!--======== upper ========-->
+<key>upper</key> <array>
+	<real>4</real>
+	<real>5</real>
+</array>
+</dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-savetest.plist ./tools/test/plist/ideal-savetest.plist
--- ../Tekkotsu_3.0/tools/test/plist/ideal-savetest.plist	2006-09-27 17:20:26.000000000 -0400
+++ ./tools/test/plist/ideal-savetest.plist	2007-11-08 22:31:08.000000000 -0500
@@ -1,5 +1,5 @@
 <?xml version="1.0"?>
-<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
 <plist version="1.0">
   <dict>
 	<!--numeric contains two numeric values,
@@ -9,59 +9,52 @@
     <dict>
       <key>fooF</key>
       <real>1.5</real>
-      
-<!--fooI: This is an integer value, the other is a float-->
-    <key>fooI</key>
+	
+	<!--fooI: This is an integer value, the other is a float-->
+	<key>fooI</key>
       <integer>16</integer>
-    
-    <key>char-num</key> <integer>97</integer>
-
-    <key>char-text</key> <string>a</string>
+	<key>char-num</key> <integer>97</integer>
+	<key>char-text</key> <string>a</string>
 </dict>
 
 <!--This is a common string-->
     <key>test str</key>
     <string>Hello World, again!</string>
-  
+
 <!--======== Mixed ========-->
 <!--A collection of mixed types of specified length-->
 <key>Mixed</key> <array>
-    <integer>0</integer>
-    <integer>1</integer>
-    <integer>2</integer>
-    <string>This is item 1</string>
-    <string>item 2: arrays can contain mixed types</string>
-<!--5: like this int-->
-    <real>123</real>
-<!--6: or this bool-->
-    <true/>
+	<integer>0</integer>
+	<integer>1</integer>
+	<integer>2</integer>
+	<string>This is item 1</string>
+	<string>item 2: arrays can contain mixed types</string>
+	<!--5: like this int-->
+	<real>123</real>
+	<!--6: or this bool-->
+	<true/>
 </array>
 
 <!--======== map ========-->
 <!--The squares, from 0 to 5, but with keys-->
 <key>map</key> <dict>
-    <key>0^2</key> <integer>0</integer>
-
-    <key>1^2</key> <integer>1</integer>
-
-    <key>2^2</key> <integer>4</integer>
-
-    <key>3^2</key> <integer>9</integer>
-
-    <key>4^2</key> <integer>16</integer>
-
-    <key>tada</key> <string>mixed types -- no surprise</string>
+	<key>0^2</key> <integer>0</integer>
+	<key>1^2</key> <integer>1</integer>
+	<key>2^2</key> <integer>4</integer>
+	<key>3^2</key> <integer>9</integer>
+	<key>4^2</key> <integer>16</integer>
+	<key>tada</key> <string>mixed types -- no surprise</string>
 </dict>
 
 <!--======== vector ========-->
 <!--The squares, from 0 to 5-->
 <key>vector</key> <array>
-    <integer>0</integer>
-    <integer>1</integer>
-    <integer>4</integer>
-    <integer>9</integer>
-    <integer>16</integer>
-    <string>can also handle mixed</string>
+	<integer>0</integer>
+	<integer>1</integer>
+	<integer>4</integer>
+	<integer>9</integer>
+	<integer>16</integer>
+	<string>can also handle mixed</string>
 </array>
 </dict>
 </plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-virgin.plist ./tools/test/plist/ideal-virgin.plist
--- ../Tekkotsu_3.0/tools/test/plist/ideal-virgin.plist	2006-09-27 17:20:27.000000000 -0400
+++ ./tools/test/plist/ideal-virgin.plist	2007-11-08 22:31:08.000000000 -0500
@@ -1,34 +1,29 @@
 <?xml version="1.0"?>
-<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
 <plist version="1.0"><dict>
 <!--======== Mixed ========-->
 <!--A collection of mixed types of specified length-->
 <key>Mixed</key> <array>
-    <integer>0</integer>
-    <integer>1</integer>
-    <integer>2</integer>
-    <string>This is item 1</string>
-    <string>item 2: arrays can contain mixed types</string>
-<!--5: like this int-->
-    <real>123</real>
-<!--6: or this bool-->
-    <true/>
+	<integer>0</integer>
+	<integer>1</integer>
+	<integer>2</integer>
+	<string>This is item 1</string>
+	<string>item 2: arrays can contain mixed types</string>
+	<!--5: like this int-->
+	<real>123</real>
+	<!--6: or this bool-->
+	<true/>
 </array>
 
 <!--======== map ========-->
 <!--The squares, from 0 to 5, but with keys-->
 <key>map</key> <dict>
-    <key>0^2</key> <integer>0</integer>
-
-    <key>1^2</key> <integer>1</integer>
-
-    <key>2^2</key> <integer>4</integer>
-
-    <key>3^2</key> <integer>9</integer>
-
-    <key>4^2</key> <integer>16</integer>
-
-    <key>tada</key> <string>mixed types -- no surprise</string>
+	<key>0^2</key> <integer>0</integer>
+	<key>1^2</key> <integer>1</integer>
+	<key>2^2</key> <integer>4</integer>
+	<key>3^2</key> <integer>9</integer>
+	<key>4^2</key> <integer>16</integer>
+	<key>tada</key> <string>mixed types -- no surprise</string>
 </dict>
 
 <!--======== numeric ========-->
@@ -37,14 +32,12 @@
 	The other is an int
 	...and a char as text for good measure-->
 <key>numeric</key> <dict>
-    <key>char-num</key> <integer>97</integer>
-
-    <key>char-text</key> <string>a</string>
-
-    <key>fooF</key> <real>3.1415927410125732421875</real>
-
-<!--fooI: This is an integer value, the other is a float-->
-    <key>fooI</key> <integer>42</integer>
+	<key>char-num</key> <integer>97</integer>
+	<key>char-text</key> <string>a</string>
+	<key>fooF</key> <real>3.14159</real>
+	
+	<!--fooI: This is an integer value, the other is a float-->
+	<key>fooI</key> <integer>42</integer>
 </dict>
 
 <!--test str: Seen this one before?-->
@@ -53,11 +46,11 @@
 <!--======== vector ========-->
 <!--The squares, from 0 to 5-->
 <key>vector</key> <array>
-    <integer>0</integer>
-    <integer>1</integer>
-    <integer>4</integer>
-    <integer>9</integer>
-    <integer>16</integer>
-    <string>can also handle mixed</string>
+	<integer>0</integer>
+	<integer>1</integer>
+	<integer>4</integer>
+	<integer>9</integer>
+	<integer>16</integer>
+	<string>can also handle mixed</string>
 </array>
 </dict></plist>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/ideal-vision.event ./tools/test/plist/ideal-vision.event
--- ../Tekkotsu_3.0/tools/test/plist/ideal-vision.event	2005-08-16 16:16:15.000000000 -0400
+++ ./tools/test/plist/ideal-vision.event	2007-11-08 22:31:08.000000000 -0500
@@ -1,5 +1,5 @@
 <?xml version="1.0"?>
-<event egid="visObjEGID" sid="0" etid="A" time="0" duration="0" magnitude="1">
+<event egid="visObjEGID" sid="0" hid="4294967295" etid="A" time="0" duration="0" magnitude="1">
   <param name="x1" value="0"/>
   <param name="y1" value="0"/>
   <param name="x2" value="0"/>
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/loadtest.plist ./tools/test/plist/loadtest.plist
--- ../Tekkotsu_3.0/tools/test/plist/loadtest.plist	2005-07-26 14:05:35.000000000 -0400
+++ ./tools/test/plist/loadtest.plist	2007-11-08 22:31:08.000000000 -0500
@@ -1,5 +1,5 @@
 <?xml version="1.0"?>
-<!DOCTYPE plist PUBLIC "-//Apple Computer//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
+<!DOCTYPE plist PUBLIC "-//Apple//DTD PLIST 1.0//EN" "http://www.apple.com/DTDs/PropertyList-1.0.dtd">
 <plist version="1.0">
   <dict>
 	<!--numeric contains two numeric values,
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/plist/plist.cc ./tools/test/plist/plist.cc
--- ../Tekkotsu_3.0/tools/test/plist/plist.cc	2006-09-27 18:15:41.000000000 -0400
+++ ./tools/test/plist/plist.cc	2007-11-08 23:58:10.000000000 -0500
@@ -6,7 +6,125 @@
 using namespace plist;
 using namespace std;
 
+/* Generic base class for "shapes"... we specify a generic Collection,
+ * as its base, allows either Dictionary or Array-based! */
+class Shape : virtual public plist::Collection {};
+
+
+/* We will use a float for coordinates, wrapped by a plist::Primitive<>
+ * The Primitive class provides transparent conversions and operations,
+ * so we can usually pretend this is just a regular float! */
+typedef plist::Primitive<float> coord_t;
+
+
+/* A point is defined as an array of coordinates, one for each dimension.
+ * We'll assume 2D points unless otherwise directed.
+ * An alternative definition could use explicit 'x' and 'y' members, and/or
+ * use a Dictionary with labels instead of an Array with subscripts... */
+class Point : public Shape, virtual public plist::ArrayOf<coord_t> {
+public:
+	explicit Point(size_t n=2) : plist::ArrayOf<coord_t>(n,0), Shape() { }
+	Point(float xVal, float yVal) : plist::ArrayOf<coord_t>(2,0), Shape() {
+		getEntry(0)=xVal;
+		getEntry(1)=yVal;
+	}
+};
+
+
+/* We'll define a rectangle by the lower-left point and the upper-right point.
+ * Further, we'll set up an accessor to maintain this invariant. */
+class Rectangle : public Shape, public virtual plist::DictionaryOf<Point> {
+public:
+	Rectangle()
+		: plist::DictionaryOf<Point>(), Shape(), lower(), upper(),
+		xm(lower[0],upper[0]), ym(lower[1],upper[1])
+	{
+		/* The next line 'fixes' the entries during load, save, or assignment.
+		 * The default is to allow dynamic resizing, so you should call this when
+		 * you expect the entry structure to be immutable. (e.g. if you are using
+		 * members as collection entries.) */
+		setLoadSavePolicy(FIXED,SYNC);
+		addEntry("lower",lower); // still can always 'explicitly' add or remove entries
+		addEntry("upper",upper); // ... the LoadSavePolicy only restricts 'implicit' changes
+	}
+	
+	/* Can provide public access to members, the Monitor will provide
+	 * the flexibility usually provided by get/set accessor functions. */
+	Point lower, upper;
+	
+	/* Note automatic conversion to value type, will never be negative due to our Monitor */
+	float getWidth() const { return upper[0] - lower[0]; }
+	float getHeight() const { return upper[1] - lower[1]; }
+	
+protected:
+	/* Implements plist::PrimitiveListener to receive notification when
+	 * a member's value is changed.  We could also do this by having
+	 * rectangle itself be the listener instead of an inner class. */
+	class Monitor : public plist::PrimitiveListener {
+	public:
+		Monitor(coord_t& low, coord_t& high) : _low(low), _high(high) {
+			_low.addPrimitiveListener(this);
+			_high.addPrimitiveListener(this);
+		}
+		virtual void plistValueChanged(const plist::PrimitiveBase&) {
+			if(_low>_high) std::swap(_low,_high);
+		}
+	protected:
+		coord_t &_low, &_high;
+	} xm, ym;
+};
+
+
+/* Here's an example of a purely dynamic class... just a resizeable list
+ * of points!  For a "real" implementation, you'd probably want to use
+ * a dictionary, add a few more properties (e.g. 'isClosed'), and have
+ * the point list as a member variable... */
+class Polygon : public Shape, public virtual plist::ArrayOf<Point> {};
+
+
+// Here's some sample usage...
 int main(int argc, const char** argv) {
+	Point p;
+	p[0]=1; // transparent conversion from value type to plist::Primitive
+	p[1]=2.5;
+	p.saveFile("point.plist");
+	
+	Rectangle r;
+	r.upper=Point(4,5); // we can assign to directly to member...
+	r["lower"]=p; // ... or dynamically via operator[] lookup
+	r.saveFile("rectangle.plist");
+	
+	// test the low/high invariant
+	cout << "Original r, width: " << r.getWidth() << '\n' << r << endl;
+	/* Original r, width: 3
+	 * lower.0 = 1
+	 * lower.1 = 2.5
+	 * upper.0 = 4
+	 * upper.1 = 5 */
+	
+	r.upper[0] = -4; // note we assign to upper.x, but it's lower.x that will be -4
+	// (because of the PrimitiveListener added by Rectangle's constructor)
+	cout << "Negated r, width: " << r.getWidth() << '\n' << r << endl;
+	/* Negated r, width: 5
+	 * lower.0 = -4
+	 * lower.1 = 2.5
+	 * upper.0 = 1
+	 * upper.1 = 5 */
+	
+	// dynamic resizing:
+	Polygon poly;
+	/* Notice we are adding pointers here, vs. references in Rectangle,
+	 * vs. float values in Point.  (De)allocation from pointers or converted 
+	 * values is handled by the collection, whereas entries added from
+	 * references are *not* deallocated. */
+	poly.addEntry(new Point(1,2));
+	poly.addEntry(new Point(3,4));
+	poly.addEntry(new Point(5,0));
+	poly.saveFile("poly.plist");
+
+	
+	// more random tests...
+	
 	Dictionary outer;
 	
 	// Dictionary within a dictionary
@@ -45,13 +163,13 @@
 	Primitive<bool> item4 = true; mixed.addEntry(item4,"or this bool");
 	//mixed.addEntry("dynamic, heap-allocated entries supported too");
 	
-	Array vec(true); // there's also variable sized collections
+	Array vec; // there's also variable sized collections
 	outer.addEntry("vector",vec,"The squares, from 0 to 5");
 	for(int i=0; i<5; i++)
 		vec.addValue(i*i); //now we use value types, the vector maintains the Primitive<>'s internally
 	vec.addValue("can also handle mixed");
 	
-	Dictionary m(true); // named variable sized collections
+	Dictionary m; // named variable sized collections
 	outer.addEntry("map",m,"The squares, from 0 to 5, but with keys");
 	for(int i=0; i<5; i++) {
 		stringstream ss;
@@ -76,6 +194,7 @@
 		return 1;
 	}
 	
+	// not actually a plist, but a custom XML schema we'll test while we're at it...
 	VisionObjectEvent e(0,EventBase::activateETID);
 	e.setTimeStamp(0); // ensures precisely repeatable results
 	e.saveFile("vision.event");
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/test/worldstatepool/Makefile ./tools/test/worldstatepool/Makefile
--- ../Tekkotsu_3.0/tools/test/worldstatepool/Makefile	2006-09-27 18:01:32.000000000 -0400
+++ ./tools/test/worldstatepool/Makefile	2007-11-15 20:03:37.000000000 -0500
@@ -19,13 +19,13 @@
 # Environment.conf file.  This is found using $(TEKKOTSU_ROOT)
 # Remove the '?' if you want to override an environment variable
 # with a value of your own.
-TEKKOTSU_ROOT=../../..
+TEKKOTSU_ROOT:=../../..
 
 .PHONY: all test
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -35,21 +35,26 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
 CXXFLAGS:=-g -Wall -O2 \
          -I$(TEKKOTSU_ROOT) \
-         -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
diff -urdN --exclude=CVS -I'\$[^$]*:[^$]*\$' ../Tekkotsu_3.0/tools/tool_makefile ./tools/tool_makefile
--- ../Tekkotsu_3.0/tools/tool_makefile	2006-09-27 18:01:31.000000000 -0400
+++ ./tools/tool_makefile	2007-11-15 20:03:33.000000000 -0500
@@ -25,7 +25,7 @@
 
 TEMPLATE_PROJECT:=$(TEKKOTSU_ROOT)/project
 TEKKOTSU_ENVIRONMENT_CONFIGURATION?=$(TEMPLATE_PROJECT)/Environment.conf
-$(if $(shell if [ \! -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] \; then echo failure \; fi),$(error An error has occured, `$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
+$(if $(shell [ -r $(TEKKOTSU_ENVIRONMENT_CONFIGURATION) ] || echo "failure"),$(error An error has occured, '$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)' could not be found.  You may need to edit TEKKOTSU_ROOT in the Makefile))
 
 TEKKOTSU_TARGET_PLATFORM:=PLATFORM_LOCAL
 include $(shell echo "$(TEKKOTSU_ENVIRONMENT_CONFIGURATION)" | sed 's/ /\\ /g')
@@ -35,21 +35,26 @@
 
 PROJ_OBJ:=$(patsubst ./%$(SRCSUFFIX),$(PROJ_BD)/%.o,$(PROJ_SRC))
 
-LIBS:= $(TK_BD)/libtekkotsu.a $(TK_BD)/../Motion/roboop/libroboop.a $(TK_BD)/../Shared/newmat/libnewmat.a
+LIBSUFFIX:=$(suffix $(LIBTEKKOTSU))
+LIBS:= $(TK_BD)/$(LIBTEKKOTSU) $(TK_BD)/../Motion/roboop/libroboop$(LIBSUFFIX) $(TK_BD)/../Shared/newmat/libnewmat$(LIBSUFFIX)
 
 DEPENDS:=$(PROJ_OBJ:.o=.d)
 
 CXXFLAGS:=-g -Wall -O2 \
          -I$(TEKKOTSU_ROOT) \
-         -I../../Shared/jpeg-6b $(shell xml2-config --cflags) \
+         -I$(TEKKOTSU_ROOT)/Shared/jpeg-6b $(shell xml2-config --cflags) \
          -D$(TEKKOTSU_TARGET_PLATFORM) -D$(TEKKOTSU_TARGET_MODEL) 
 
+LDFLAGS:=$(LDFLAGS) `xml2-config --libs` $(if $(shell locate librt.a 2> /dev/null),-lrt) \
+        -lreadline -lncurses -ljpeg -lpng12 \
+        $(if $(HAVE_ICE),-L$(ICE_ROOT)/lib -lIce -lGlacier2 -lIceUtil) \
+        $(if $(findstring Darwin,$(shell uname)),-bind_at_load -framework Quicktime -framework Carbon)
 
 all: $(BIN)
 
 $(BIN): $(PROJ_OBJ) $(LIBS)
 	@echo "Linking $@..."
-	@$(CXX) $(PROJ_OBJ) $(LIBS) $(shell xml2-config --libs) -lpthread -o $@
+	@$(CXX) $(PROJ_OBJ) -L$(TK_BD) $(LIBS) $(LDFLAGS) -o $@
 
 ifeq ($(findstring clean,$(MAKECMDGOALS)),)
 -include $(DEPENDS)
@@ -77,7 +82,7 @@
 	test $$retval -eq 0; \
 
 clean:
-	rm -rf $(BIN) $(PROJECT_BUILDDIR) *~
+	rm -rf $(BIN) $(PROJECT_BUILDDIR) test-* *~
 
 test: ./$(BIN)
 	@for x in * ; do \
